Aikido
ConfigurationToTSR.hpp
Go to the documentation of this file.
1 #ifndef AIKIDO_PLANNER_DART_CONFIGURATIONTOTSR_HPP_
2 #define AIKIDO_PLANNER_DART_CONFIGURATIONTOTSR_HPP_
3 
4 #include <dart/dart.hpp>
5 
10 
11 namespace aikido {
12 namespace planner {
13 namespace dart {
14 
17 {
18 public:
34  ::dart::dynamics::ConstMetaSkeletonPtr metaSkeleton,
35  ::dart::dynamics::ConstBodyNodePtr endEffectorBodyNode,
36  std::size_t maxSamples,
38  constraint::ConstTestablePtr constraint = nullptr);
39 
55  ::dart::dynamics::ConstBodyNodePtr endEffectorBodyNode,
56  std::size_t maxSamples,
58  constraint::ConstTestablePtr constraint = nullptr);
59 
60  // Documentation inherited.
61  const std::string& getType() const override;
62 
64  static const std::string& getStaticType();
65 
67  ::dart::dynamics::ConstBodyNodePtr getEndEffectorBodyNode() const;
68 
70  std::size_t getMaxSamples() const;
71 
75 
78 
79 protected:
83 
85  ::dart::dynamics::ConstMetaSkeletonPtr mMetaSkeleton;
86 
89 
91  const ::dart::dynamics::ConstBodyNodePtr mEndEffectorBodyNode;
92 
94  std::size_t mMaxSamples;
95 
98 };
99 
100 } // namespace dart
101 } // namespace planner
102 } // namespace aikido
103 
104 #endif // AIKIDO_PLANNER_DART_CONFIGURATIONTOTSR_HPP_
aikido::statespace::dart::ConstMetaSkeletonStateSpacePtr
std::shared_ptr< const MetaSkeletonStateSpace > ConstMetaSkeletonStateSpacePtr
Definition: MetaSkeletonStateSpace.hpp:17
aikido::planner::dart::ConfigurationToTSR
Planning problem to plan to a given single Task Space Region (TSR).
Definition: ConfigurationToTSR.hpp:16
aikido::planner::dart::ConfigurationToTSR::mMetaSkeleton
::dart::dynamics::ConstMetaSkeletonPtr mMetaSkeleton
MetaSkeleton, if given.
Definition: ConfigurationToTSR.hpp:85
aikido
Format of serialized trajectory in YAML.
Definition: algorithm.hpp:4
aikido::planner::dart::ConfigurationToTSR::mMetaSkeletonStateSpace
statespace::dart::ConstMetaSkeletonStateSpacePtr mMetaSkeletonStateSpace
MetaSkeletonStateSpace.
Definition: ConfigurationToTSR.hpp:82
aikido::constraint::dart::ConstTSRPtr
std::shared_ptr< const TSR > ConstTSRPtr
Definition: TSR.hpp:17
TSR.hpp
aikido::planner::dart::ConfigurationToTSR::getType
const std::string & getType() const override
Returns type of this planning problem.
Interpolated.hpp
aikido::planner::dart::ConfigurationToTSR::getStaticType
static const std::string & getStaticType()
Returns the type of the planning problem.
aikido::planner::dart::ConfigurationToTSR::getMaxSamples
std::size_t getMaxSamples() const
Returns the maximum number of TSR samples to plan to.
Problem.hpp
aikido::planner::dart::ConfigurationToTSR::mStartState
statespace::dart::MetaSkeletonStateSpace::ScopedState mStartState
Start state, if set on construction.
Definition: ConfigurationToTSR.hpp:88
aikido::planner::Problem
Base class for various planning problems.
Definition: Problem.hpp:13
aikido::planner::dart::ConfigurationToTSR::getGoalTSR
constraint::dart::ConstTSRPtr getGoalTSR() const
Returns the goal TSR.
aikido::statespace::ScopedState< StateHandle >
aikido::planner::dart::ConfigurationToTSR::getEndEffectorBodyNode
::dart::dynamics::ConstBodyNodePtr getEndEffectorBodyNode() const
Returns the end-effector BodyNode to be planned to move to a desired TSR.
aikido::statespace::CartesianProduct::State
A tuple of states where the i-th state is from the i-th subspace.
Definition: CartesianProduct.hpp:162
MetaSkeletonStateSpace.hpp
aikido::planner::dart::ConfigurationToTSR::mMaxSamples
std::size_t mMaxSamples
Maximum number of TSR samples to plan to.
Definition: ConfigurationToTSR.hpp:94
aikido::planner::dart::ConfigurationToTSR::ConfigurationToTSR
ConfigurationToTSR(statespace::dart::ConstMetaSkeletonStateSpacePtr stateSpace, ::dart::dynamics::ConstMetaSkeletonPtr metaSkeleton, ::dart::dynamics::ConstBodyNodePtr endEffectorBodyNode, std::size_t maxSamples, constraint::dart::ConstTSRPtr goalTSR, constraint::ConstTestablePtr constraint=nullptr)
Constructor.
aikido::planner::dart::ConfigurationToTSR::getStartState
const statespace::dart::MetaSkeletonStateSpace::State * getStartState() const
Returns the start state to plan from, either set on construction or taken from the current state of t...
dart
Definition: FrameMarker.hpp:11
aikido::planner::dart::ConfigurationToTSR::mGoalTSR
const constraint::dart::ConstTSRPtr mGoalTSR
Goal TSR.
Definition: ConfigurationToTSR.hpp:97
aikido::planner::dart::ConfigurationToTSR::mEndEffectorBodyNode
const ::dart::dynamics::ConstBodyNodePtr mEndEffectorBodyNode
End-effector body node.
Definition: ConfigurationToTSR.hpp:91
aikido::constraint::ConstTestablePtr
std::shared_ptr< const Testable > ConstTestablePtr
Definition: Testable.hpp:13