Aikido
MoveEndEffectorPoseVectorField.hpp
Go to the documentation of this file.
1 #ifndef AIKIDO_PLANNER_VECTORFIELD_MOVEENDEFFECTORPOSEVECTORFIELD_HPP_
2 #define AIKIDO_PLANNER_VECTORFIELD_MOVEENDEFFECTORPOSEVECTORFIELD_HPP_
3 
4 #include <limits>
5 
7 
8 namespace aikido {
9 namespace planner {
10 namespace vectorfield {
11 
23 {
24 public:
41  ::dart::dynamics::MetaSkeletonPtr metaskeleton,
42  ::dart::dynamics::ConstBodyNodePtr bn,
43  const Eigen::Isometry3d& goalPose,
44  double goalTolerance,
45  double r,
46  double positionTolerance,
47  double angularTolerance,
48  double maxStepSize,
49  double jointLimitPadding);
50 
51  // Documentation inherited.
53  const Eigen::Isometry3d& pose,
54  Eigen::Vector6d& cartesianVelocity) const override;
55 
56  // Documentation inherited.
58  const Eigen::Isometry3d& pose) const override;
59 
60 protected:
62  Eigen::Isometry3d mGoalPose;
63 
66 
69 
72 
75 
77  Eigen::Isometry3d mStartPose;
78 
80  Eigen::Vector6d mDesiredTwist;
81  Eigen::Vector3d mDirection;
82  Eigen::Vector3d mRotation;
83 
85  std::shared_ptr<double> mLastPoseError;
86 
87 public:
88  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
89 };
90 
91 } // namespace vectorfield
92 } // namespace planner
93 } // namespace aikido
94 
95 #endif // ifndef
96  // AIKIDO_PLANNER_VECTORFIELD_MOVEENDEFFECTORPOSEVECTORFIELD_HPP_
aikido::statespace::dart::ConstMetaSkeletonStateSpacePtr
std::shared_ptr< const MetaSkeletonStateSpace > ConstMetaSkeletonStateSpacePtr
Definition: MetaSkeletonStateSpace.hpp:17
BodyNodePoseVectorField.hpp
aikido::planner::vectorfield::BodyNodePoseVectorField
This class is a vector field over a MetaSkeletonStateSpace that is defined in terms of a Cartesian ve...
Definition: BodyNodePoseVectorField.hpp:24
aikido::planner::vectorfield::MoveEndEffectorPoseVectorField::mAngularTolerance
double mAngularTolerance
Tolerance of angular error.
Definition: MoveEndEffectorPoseVectorField.hpp:74
aikido::planner::vectorfield::MoveEndEffectorPoseVectorField::mDesiredTwist
Eigen::Vector6d mDesiredTwist
Cache for desired twist between start and goal.
Definition: MoveEndEffectorPoseVectorField.hpp:80
aikido
Format of serialized trajectory in YAML.
Definition: algorithm.hpp:4
aikido::planner::vectorfield::MoveEndEffectorPoseVectorField::mGoalTolerance
double mGoalTolerance
Tolerance of pose error.
Definition: MoveEndEffectorPoseVectorField.hpp:65
aikido::planner::vectorfield::MoveEndEffectorPoseVectorField
Vector field for moving end-effector to a goal pose in SE(3).
Definition: MoveEndEffectorPoseVectorField.hpp:22
aikido::planner::vectorfield::MoveEndEffectorPoseVectorField::mGoalPose
Eigen::Isometry3d mGoalPose
Goal pose.
Definition: MoveEndEffectorPoseVectorField.hpp:62
aikido::planner::vectorfield::MoveEndEffectorPoseVectorField::mConversionRatioFromRadianToMeter
double mConversionRatioFromRadianToMeter
Conversion ratio from radius to meter.
Definition: MoveEndEffectorPoseVectorField.hpp:68
aikido::planner::vectorfield::MoveEndEffectorPoseVectorField::mRotation
Eigen::Vector3d mRotation
Definition: MoveEndEffectorPoseVectorField.hpp:82
aikido::planner::vectorfield::MoveEndEffectorPoseVectorField::mLastPoseError
std::shared_ptr< double > mLastPoseError
Cache of last pose error.
Definition: MoveEndEffectorPoseVectorField.hpp:85
aikido::planner::vectorfield::MoveEndEffectorPoseVectorField::evaluateCartesianStatus
VectorFieldPlannerStatus evaluateCartesianStatus(const Eigen::Isometry3d &pose) const override
Evaluate current pose to determine the status of planning.
aikido::planner::vectorfield::MoveEndEffectorPoseVectorField::mStartPose
Eigen::Isometry3d mStartPose
Start pose of the end-effector.
Definition: MoveEndEffectorPoseVectorField.hpp:77
aikido::planner::vectorfield::MoveEndEffectorPoseVectorField::MoveEndEffectorPoseVectorField
MoveEndEffectorPoseVectorField(aikido::statespace::dart::ConstMetaSkeletonStateSpacePtr stateSpace, ::dart::dynamics::MetaSkeletonPtr metaskeleton, ::dart::dynamics::ConstBodyNodePtr bn, const Eigen::Isometry3d &goalPose, double goalTolerance, double r, double positionTolerance, double angularTolerance, double maxStepSize, double jointLimitPadding)
Constructor.
aikido::planner::vectorfield::VectorFieldPlannerStatus
VectorFieldPlannerStatus
Status of planning.
Definition: VectorFieldPlannerStatus.hpp:14
aikido::planner::vectorfield::MoveEndEffectorPoseVectorField::mDirection
Eigen::Vector3d mDirection
Definition: MoveEndEffectorPoseVectorField.hpp:81
aikido::planner::vectorfield::MoveEndEffectorPoseVectorField::mPositionTolerance
double mPositionTolerance
Tolerance of linear deviation error.
Definition: MoveEndEffectorPoseVectorField.hpp:71
aikido::planner::vectorfield::MoveEndEffectorPoseVectorField::evaluateCartesianVelocity
bool evaluateCartesianVelocity(const Eigen::Isometry3d &pose, Eigen::Vector6d &cartesianVelocity) const override
Evaluate Cartesian velocity by current pose of body node.