Go to the documentation of this file. 1 #ifndef AIKIDO_PLANNER_DART_CONFIGURATIONTOENDEFFECTORPOSEPLANNER_HPP_
2 #define AIKIDO_PLANNER_DART_CONFIGURATIONTOENDEFFECTORPOSEPLANNER_HPP_
16 ConfigurationToEndEffectorPosePlanner,
17 ConfigurationToEndEffectorPose>
32 ::dart::dynamics::MetaSkeletonPtr metaSkeleton);
51 #endif // AIKIDO_PLANNER_DART_CONFIGURATIONTOENDEFFECTORPOSEPLANNER_HPP_
std::shared_ptr< const MetaSkeletonStateSpace > ConstMetaSkeletonStateSpacePtr
Definition: MetaSkeletonStateSpace.hpp:17
Format of serialized trajectory in YAML.
Definition: algorithm.hpp:4
Base planner class for ConfigurationToEndEffectorPose planning problem.
Definition: ConfigurationToEndEffectorPosePlanner.hpp:14
std::shared_ptr< Trajectory > TrajectoryPtr
Definition: Trajectory.hpp:13
virtual trajectory::TrajectoryPtr plan(const SolvableProblem &problem, Result *result=nullptr)=0
Solves problem returning the result to result.
ConfigurationToEndEffectorPose SolvableProblem
Definition: SingleProblemPlanner.hpp:25
Base planner class for all DART single problem planners.
Definition: SingleProblemPlanner.hpp:14
ConfigurationToEndEffectorPosePlanner(statespace::dart::ConstMetaSkeletonStateSpacePtr stateSpace, ::dart::dynamics::MetaSkeletonPtr metaSkeleton)
Constructor.
Definition: FrameMarker.hpp:11
trajectory::TrajectoryPtr plan(const Problem &problem, Result *result=nullptr) final override
Solves problem returning the result to result.
Definition: SingleProblemPlanner-impl.hpp:30
Base class for planning result of various planning problems.
Definition: Planner.hpp:58