Aikido
ConfigurationToConfiguration.hpp
Go to the documentation of this file.
1 #ifndef AIKIDO_PLANNER_DART_CONFIGURATIONTOCONFIGURATION_HPP_
2 #define AIKIDO_PLANNER_DART_CONFIGURATIONTOCONFIGURATION_HPP_
3 
4 #include <dart/dart.hpp>
5 
9 
10 namespace aikido {
11 namespace planner {
12 namespace dart {
13 
16 {
17 public:
28  ::dart::dynamics::ConstMetaSkeletonPtr metaSkeleton,
30  constraint::ConstTestablePtr constraint = nullptr);
31 
43  constraint::ConstTestablePtr constraint = nullptr);
44 
45  // Documentation inherited.
46  const std::string& getType() const override;
47 
49  static const std::string& getStaticType();
50 
53 
56 
57 protected:
61 
63  ::dart::dynamics::ConstMetaSkeletonPtr mMetaSkeleton;
64 
67 
70 };
71 
72 } // namespace dart
73 } // namespace planner
74 } // namespace aikido
75 
76 #endif // AIKIDO_PLANNER_DART_CONFIGURATIONTOCONFIGURATION_HPP_
aikido::statespace::dart::ConstMetaSkeletonStateSpacePtr
std::shared_ptr< const MetaSkeletonStateSpace > ConstMetaSkeletonStateSpacePtr
Definition: MetaSkeletonStateSpace.hpp:17
aikido
Format of serialized trajectory in YAML.
Definition: algorithm.hpp:4
aikido::planner::dart::ConfigurationToConfiguration::getStartState
const statespace::dart::MetaSkeletonStateSpace::State * getStartState() const
Returns the start state.
Problem.hpp
aikido::planner::dart::ConfigurationToConfiguration::mMetaSkeletonStateSpace
statespace::dart::ConstMetaSkeletonStateSpacePtr mMetaSkeletonStateSpace
MetaSkeletonStateSpace.
Definition: ConfigurationToConfiguration.hpp:60
aikido::planner::dart::ConfigurationToConfiguration::getStaticType
static const std::string & getStaticType()
Returns the type of the planning problem.
aikido::planner::Problem
Base class for various planning problems.
Definition: Problem.hpp:13
aikido::statespace::ScopedState< StateHandle >
aikido::statespace::CartesianProduct::State
A tuple of states where the i-th state is from the i-th subspace.
Definition: CartesianProduct.hpp:162
aikido::planner::dart::ConfigurationToConfiguration::mGoalState
statespace::dart::MetaSkeletonStateSpace::ScopedState mGoalState
Goal state.
Definition: ConfigurationToConfiguration.hpp:69
aikido::planner::dart::ConfigurationToConfiguration::mStartState
statespace::dart::MetaSkeletonStateSpace::ScopedState mStartState
Start state.
Definition: ConfigurationToConfiguration.hpp:66
Testable.hpp
MetaSkeletonStateSpace.hpp
aikido::planner::dart::ConfigurationToConfiguration
Planning problem to plan to a single goal configuration.
Definition: ConfigurationToConfiguration.hpp:15
aikido::planner::dart::ConfigurationToConfiguration::mMetaSkeleton
::dart::dynamics::ConstMetaSkeletonPtr mMetaSkeleton
MetaSkeleton, if given.
Definition: ConfigurationToConfiguration.hpp:63
aikido::planner::dart::ConfigurationToConfiguration::getType
const std::string & getType() const override
Returns type of this planning problem.
dart
Definition: FrameMarker.hpp:11
aikido::planner::dart::ConfigurationToConfiguration::ConfigurationToConfiguration
ConfigurationToConfiguration(statespace::dart::ConstMetaSkeletonStateSpacePtr stateSpace, ::dart::dynamics::ConstMetaSkeletonPtr metaSkeleton, const statespace::dart::MetaSkeletonStateSpace::State *goalState, constraint::ConstTestablePtr constraint=nullptr)
Constructor.
aikido::planner::dart::ConfigurationToConfiguration::getGoalState
const statespace::dart::MetaSkeletonStateSpace::State * getGoalState() const
Returns the goal state.
aikido::constraint::ConstTestablePtr
std::shared_ptr< const Testable > ConstTestablePtr
Definition: Testable.hpp:13