Aikido
ConfigurationToEndEffectorOffset.hpp
Go to the documentation of this file.
1 #ifndef AIKIDO_PLANNER_DART_CONFIGURATIONTOENDEFFECTOROFFSET_HPP_
2 #define AIKIDO_PLANNER_DART_CONFIGURATIONTOENDEFFECTOROFFSET_HPP_
3 
4 #include <boost/optional.hpp>
5 #include <dart/dart.hpp>
6 
11 
12 namespace aikido {
13 namespace planner {
14 namespace dart {
15 
24 {
25 public:
42  ::dart::dynamics::ConstMetaSkeletonPtr metaSkeleton,
43  ::dart::dynamics::ConstBodyNodePtr endEffectorBodyNode,
44  const Eigen::Vector3d& direction,
45  double signedDistance,
46  constraint::ConstTestablePtr constraint = nullptr);
47 
63  ::dart::dynamics::ConstBodyNodePtr endEffectorBodyNode,
64  const Eigen::Vector3d& direction,
65  double signedDistance,
66  constraint::ConstTestablePtr constraint = nullptr);
67 
82  ::dart::dynamics::ConstMetaSkeletonPtr metaSkeleton,
83  ::dart::dynamics::ConstBodyNodePtr endEffectorBodyNode,
84  double signedDistance,
85  constraint::ConstTestablePtr constraint = nullptr);
86 
101  ::dart::dynamics::ConstBodyNodePtr endEffectorBodyNode,
102  double signedDistance,
103  constraint::ConstTestablePtr constraint = nullptr);
104 
105  // Documentation inherited.
106  const std::string& getType() const override;
107 
109  static const std::string& getStaticType();
110 
113  ::dart::dynamics::ConstBodyNodePtr getEndEffectorBodyNode() const;
114 
118 
122  Eigen::Vector3d getDirection() const;
123 
125  double getDistance() const;
126 
127 protected:
131 
133  ::dart::dynamics::ConstMetaSkeletonPtr mMetaSkeleton;
134 
137 
139  const ::dart::dynamics::ConstBodyNodePtr mEndEffectorBodyNode;
140 
142  const boost::optional<Eigen::Vector3d> mDirection;
143 
145  const double mDistance;
146 };
147 
148 } // namespace dart
149 } // namespace planner
150 } // namespace aikido
151 
152 #endif // AIKIDO_PLANNER_DART_CONFIGURATIONTOENDEFFECTOROFFSET_HPP_
aikido::statespace::dart::ConstMetaSkeletonStateSpacePtr
std::shared_ptr< const MetaSkeletonStateSpace > ConstMetaSkeletonStateSpacePtr
Definition: MetaSkeletonStateSpace.hpp:17
aikido::planner::dart::ConfigurationToEndEffectorOffset::ConfigurationToEndEffectorOffset
ConfigurationToEndEffectorOffset(statespace::dart::ConstMetaSkeletonStateSpacePtr stateSpace, ::dart::dynamics::ConstMetaSkeletonPtr metaSkeleton, ::dart::dynamics::ConstBodyNodePtr endEffectorBodyNode, const Eigen::Vector3d &direction, double signedDistance, constraint::ConstTestablePtr constraint=nullptr)
Constructor.
aikido
Format of serialized trajectory in YAML.
Definition: algorithm.hpp:4
aikido::planner::dart::ConfigurationToEndEffectorOffset::getDirection
Eigen::Vector3d getDirection() const
Returns the direction of motion specified in the world frame.
aikido::planner::dart::ConfigurationToEndEffectorOffset::getType
const std::string & getType() const override
Returns type of this planning problem.
Interpolated.hpp
Problem.hpp
aikido::planner::dart::ConfigurationToEndEffectorOffset::mDistance
const double mDistance
Signed distance to move in the direction specified.
Definition: ConfigurationToEndEffectorOffset.hpp:145
aikido::planner::dart::ConfigurationToEndEffectorOffset::mDirection
const boost::optional< Eigen::Vector3d > mDirection
Direction of motion, if set on construction.
Definition: ConfigurationToEndEffectorOffset.hpp:142
aikido::planner::dart::ConfigurationToEndEffectorOffset::getDistance
double getDistance() const
Returns the signed distance in meters to move in the specified direction.
aikido::planner::dart::ConfigurationToEndEffectorOffset::mMetaSkeleton
::dart::dynamics::ConstMetaSkeletonPtr mMetaSkeleton
MetaSkeleton, if given.
Definition: ConfigurationToEndEffectorOffset.hpp:133
aikido::planner::Problem
Base class for various planning problems.
Definition: Problem.hpp:13
aikido::statespace::ScopedState< StateHandle >
aikido::planner::dart::ConfigurationToEndEffectorOffset::mStartState
statespace::dart::MetaSkeletonStateSpace::ScopedState mStartState
Start state, if set on construction.
Definition: ConfigurationToEndEffectorOffset.hpp:136
aikido::statespace::CartesianProduct::State
A tuple of states where the i-th state is from the i-th subspace.
Definition: CartesianProduct.hpp:162
Testable.hpp
MetaSkeletonStateSpace.hpp
aikido::planner::dart::ConfigurationToEndEffectorOffset::getStaticType
static const std::string & getStaticType()
Returns the type of the planning problem.
aikido::planner::dart::ConfigurationToEndEffectorOffset
Planning problem to plan to desired end-effector offset while maintaining the current end-effector or...
Definition: ConfigurationToEndEffectorOffset.hpp:23
aikido::planner::dart::ConfigurationToEndEffectorOffset::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::ConfigurationToEndEffectorOffset::getEndEffectorBodyNode
::dart::dynamics::ConstBodyNodePtr getEndEffectorBodyNode() const
Returns the end-effector BodyNode to be planned to move a desired offest while maintaining the curren...
aikido::planner::dart::ConfigurationToEndEffectorOffset::mMetaSkeletonStateSpace
statespace::dart::ConstMetaSkeletonStateSpacePtr mMetaSkeletonStateSpace
MetaSkeletonStateSpace.
Definition: ConfigurationToEndEffectorOffset.hpp:130
aikido::planner::dart::ConfigurationToEndEffectorOffset::mEndEffectorBodyNode
const ::dart::dynamics::ConstBodyNodePtr mEndEffectorBodyNode
End-effector body node.
Definition: ConfigurationToEndEffectorOffset.hpp:139
aikido::constraint::ConstTestablePtr
std::shared_ptr< const Testable > ConstTestablePtr
Definition: Testable.hpp:13