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:
39  ::dart::dynamics::ConstMetaSkeletonPtr metaSkeleton,
40  ::dart::dynamics::ConstBodyNodePtr endEffectorBodyNode,
41  std::size_t maxSamplingTries,
42  std::size_t batchSize,
43  std::size_t maxBatches,
44  std::size_t numMaxIterations,
46  constraint::ConstTestablePtr constraint = nullptr);
47 
68  ::dart::dynamics::ConstBodyNodePtr endEffectorBodyNode,
69  std::size_t maxSamplingTries,
70  std::size_t batchSize,
71  std::size_t maxBatches,
72  std::size_t numMaxIterations,
74  constraint::ConstTestablePtr constraint = nullptr);
75 
76  // Documentation inherited.
77  const std::string& getType() const override;
78 
80  static const std::string& getStaticType();
81 
83  ::dart::dynamics::ConstBodyNodePtr getEndEffectorBodyNode() const;
84 
86  std::size_t getMaxSamplingTries() const;
87 
89  std::size_t getBatchSize() const;
90 
92  std::size_t getMaxBatches() const;
93 
95  std::size_t getNumMaxIterations() const;
96 
100 
103 
104 protected:
108 
110  ::dart::dynamics::ConstMetaSkeletonPtr mMetaSkeleton;
111 
114 
116  const ::dart::dynamics::ConstBodyNodePtr mEndEffectorBodyNode;
117 
119  std::size_t mMaxSamplingTries;
120 
122  std::size_t mBatchSize;
123 
125  std::size_t mMaxBatches;
126 
128  std::size_t mNumMaxIterations;
129 
132 };
133 
134 } // namespace dart
135 } // namespace planner
136 } // namespace aikido
137 
138 #endif // AIKIDO_PLANNER_DART_CONFIGURATIONTOTSR_HPP_
aikido::statespace::dart::ConstMetaSkeletonStateSpacePtr
std::shared_ptr< const MetaSkeletonStateSpace > ConstMetaSkeletonStateSpacePtr
Definition: MetaSkeletonStateSpace.hpp:17
aikido::planner::dart::ConfigurationToTSR::ConfigurationToTSR
ConfigurationToTSR(statespace::dart::ConstMetaSkeletonStateSpacePtr stateSpace, ::dart::dynamics::ConstMetaSkeletonPtr metaSkeleton, ::dart::dynamics::ConstBodyNodePtr endEffectorBodyNode, std::size_t maxSamplingTries, std::size_t batchSize, std::size_t maxBatches, std::size_t numMaxIterations, constraint::dart::ConstTSRPtr goalTSR, constraint::ConstTestablePtr constraint=nullptr)
Constructor.
aikido::planner::dart::ConfigurationToTSR::getMaxSamplingTries
std::size_t getMaxSamplingTries() const
Returns the maximum number of times to try when sampling from the TSR.
aikido::planner::dart::ConfigurationToTSR::getNumMaxIterations
std::size_t getNumMaxIterations() const
Returns the maximum number of iterations for the IK Solver.
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:110
aikido
Format of serialized trajectory in YAML.
Definition: algorithm.hpp:4
aikido::planner::dart::ConfigurationToTSR::mMetaSkeletonStateSpace
statespace::dart::ConstMetaSkeletonStateSpacePtr mMetaSkeletonStateSpace
MetaSkeletonStateSpace.
Definition: ConfigurationToTSR.hpp:107
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.
aikido::planner::dart::ConfigurationToTSR::mMaxSamplingTries
std::size_t mMaxSamplingTries
Maximum number of times to try when sampling from the TSR.
Definition: ConfigurationToTSR.hpp:119
Interpolated.hpp
aikido::planner::dart::ConfigurationToTSR::getStaticType
static const std::string & getStaticType()
Returns the type of the planning problem.
Problem.hpp
aikido::planner::dart::ConfigurationToTSR::mStartState
statespace::dart::MetaSkeletonStateSpace::ScopedState mStartState
Start state, if set on construction.
Definition: ConfigurationToTSR.hpp:113
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::planner::dart::ConfigurationToTSR::mBatchSize
std::size_t mBatchSize
Number of TSR samples to include per batch.
Definition: ConfigurationToTSR.hpp:122
aikido::planner::dart::ConfigurationToTSR::mNumMaxIterations
std::size_t mNumMaxIterations
Maximum number of iterations for the IK Solver.
Definition: ConfigurationToTSR.hpp:128
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::getBatchSize
std::size_t getBatchSize() const
Returns the number of samples from the TSR to include per batch.
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::mMaxBatches
std::size_t mMaxBatches
Maximum number of batches to run when planning to TSR samples.
Definition: ConfigurationToTSR.hpp:125
aikido::planner::dart::ConfigurationToTSR::mGoalTSR
const constraint::dart::ConstTSRPtr mGoalTSR
Goal TSR.
Definition: ConfigurationToTSR.hpp:131
aikido::planner::dart::ConfigurationToTSR::mEndEffectorBodyNode
const ::dart::dynamics::ConstBodyNodePtr mEndEffectorBodyNode
End-effector body node.
Definition: ConfigurationToTSR.hpp:116
aikido::planner::dart::ConfigurationToTSR::getMaxBatches
std::size_t getMaxBatches() const
Returns the maximum number of batches to run when planning to TSR samples.
aikido::constraint::ConstTestablePtr
std::shared_ptr< const Testable > ConstTestablePtr
Definition: Testable.hpp:13