Aikido
ConfigurationToEndEffectorOffsetPlanner.hpp
Go to the documentation of this file.
1 #ifndef AIKIDO_PLANNER_DART_CONFIGURATIONTOENDEFFECTOROFFSETPLANNER_HPP_
2 #define AIKIDO_PLANNER_DART_CONFIGURATIONTOENDEFFECTOROFFSETPLANNER_HPP_
3 
8 
9 namespace aikido {
10 namespace planner {
11 namespace dart {
12 
16  ConfigurationToEndEffectorOffsetPlanner,
17  ConfigurationToEndEffectorOffset>
18 {
19 public:
20  // Expose the implementation of Planner::plan(const Problem&, Result*) in
21  // SingleProblemPlanner. Note that plan() of the base class takes Problem
22  // while the virtual function defined in this class takes SolvableProblem,
23  // which is simply ConfigurationToEndEffectorOffset.
25 
32  ::dart::dynamics::MetaSkeletonPtr metaSkeleton);
33 
39  const SolvableProblem& problem, Result* result = nullptr)
40  = 0;
41  // Note: SolvableProblem is defined in SingleProblemPlanner.
42 };
43 
44 } // namespace dart
45 } // namespace planner
46 } // namespace aikido
47 
48 #endif // AIKIDO_PLANNER_DART_CONFIGURATIONTOENDEFFECTOROFFSETPLANNER_HPP_
aikido::statespace::dart::ConstMetaSkeletonStateSpacePtr
std::shared_ptr< const MetaSkeletonStateSpace > ConstMetaSkeletonStateSpacePtr
Definition: MetaSkeletonStateSpace.hpp:17
SingleProblemPlanner.hpp
aikido
Format of serialized trajectory in YAML.
Definition: algorithm.hpp:4
aikido::trajectory::TrajectoryPtr
std::shared_ptr< Trajectory > TrajectoryPtr
Definition: Trajectory.hpp:13
aikido::planner::dart::ConfigurationToEndEffectorOffsetPlanner::ConfigurationToEndEffectorOffsetPlanner
ConfigurationToEndEffectorOffsetPlanner(statespace::dart::ConstMetaSkeletonStateSpacePtr stateSpace, ::dart::dynamics::MetaSkeletonPtr metaSkeleton)
Constructor.
aikido::planner::SingleProblemPlanner< ConfigurationToEndEffectorOffsetPlanner, ConfigurationToEndEffectorOffset >::SolvableProblem
ConfigurationToEndEffectorOffset SolvableProblem
Definition: SingleProblemPlanner.hpp:25
Trajectory.hpp
aikido::planner::dart::SingleProblemPlanner
Base planner class for all DART single problem planners.
Definition: SingleProblemPlanner.hpp:14
aikido::planner::dart::ConfigurationToEndEffectorOffsetPlanner::plan
virtual trajectory::TrajectoryPtr plan(const SolvableProblem &problem, Result *result=nullptr)=0
Solves problem returning the result to result.
aikido::planner::dart::ConfigurationToEndEffectorOffsetPlanner
Base planner class for ConfigurationToEndEffectorOffset planning problem.
Definition: ConfigurationToEndEffectorOffsetPlanner.hpp:14
MetaSkeletonStateSpace.hpp
dart
Definition: FrameMarker.hpp:11
ConfigurationToEndEffectorOffset.hpp
aikido::planner::SingleProblemPlanner::plan
trajectory::TrajectoryPtr plan(const Problem &problem, Result *result=nullptr) final override
Solves problem returning the result to result.
Definition: SingleProblemPlanner-impl.hpp:30
aikido::planner::Planner::Result
Base class for planning result of various planning problems.
Definition: Planner.hpp:58