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 
5 
6 namespace aikido {
7 namespace planner {
8 namespace vectorfield {
9 
21 {
22 public:
38  dart::dynamics::MetaSkeletonPtr metaskeleton,
39  dart::dynamics::BodyNodePtr bn,
40  const Eigen::Isometry3d& goalPose,
41  double poseErrorTolerance,
42  double r,
43  double maxStepSize,
44  double jointLimitPadding);
45 
46  // Documentation inherited.
48  const Eigen::Isometry3d& pose,
49  Eigen::Vector6d& cartesianVelocity) const override;
50 
51  // Documentation inherited.
53  const Eigen::Isometry3d& pose) const override;
54 
55 protected:
57  Eigen::Isometry3d mGoalPose;
58 
61 
64 
65 public:
66  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
67 };
68 
69 } // namespace vectorfield
70 } // namespace planner
71 } // namespace aikido
72 
73 #endif // ifndef
74  // AIKIDO_PLANNER_VECTORFIELD_MOVEENDEFFECTORPOSEVECTORFIELD_HPP_
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::statespace::dart::MetaSkeletonStateSpacePtr
std::shared_ptr< MetaSkeletonStateSpace > MetaSkeletonStateSpacePtr
Definition: MetaSkeletonStateSpace.hpp:17
aikido
Format of serialized trajectory in YAML.
Definition: algorithm.hpp:4
aikido::planner::vectorfield::MoveEndEffectorPoseVectorField::MoveEndEffectorPoseVectorField
MoveEndEffectorPoseVectorField(aikido::statespace::dart::MetaSkeletonStateSpacePtr stateSpace, dart::dynamics::MetaSkeletonPtr metaskeleton, dart::dynamics::BodyNodePtr bn, const Eigen::Isometry3d &goalPose, double poseErrorTolerance, double r, double maxStepSize, double jointLimitPadding)
Constructor.
aikido::planner::vectorfield::MoveEndEffectorPoseVectorField
Vector field for moving end-effector to a goal pose in SE(3).
Definition: MoveEndEffectorPoseVectorField.hpp:20
aikido::planner::vectorfield::MoveEndEffectorPoseVectorField::mGoalPose
Eigen::Isometry3d mGoalPose
Goal pose.
Definition: MoveEndEffectorPoseVectorField.hpp:57
aikido::planner::vectorfield::MoveEndEffectorPoseVectorField::mConversionRatioFromRadiusToMeter
double mConversionRatioFromRadiusToMeter
Conversion ratio from radius to meter.
Definition: MoveEndEffectorPoseVectorField.hpp:63
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::mPoseErrorTolerance
double mPoseErrorTolerance
Tolerance of pose error.
Definition: MoveEndEffectorPoseVectorField.hpp:60
aikido::planner::vectorfield::VectorFieldPlannerStatus
VectorFieldPlannerStatus
Status of planning.
Definition: VectorFieldPlannerStatus.hpp:14
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.