Go to the documentation of this file. 1 #ifndef AIKIDO_PLANNER_VECTORFIELD_MOVEENDEFFECTORPOSEVECTORFIELD_HPP_
2 #define AIKIDO_PLANNER_VECTORFIELD_MOVEENDEFFECTORPOSEVECTORFIELD_HPP_
10 namespace vectorfield {
41 ::dart::dynamics::MetaSkeletonPtr metaskeleton,
42 ::dart::dynamics::ConstBodyNodePtr bn,
43 const Eigen::Isometry3d& goalPose,
46 double positionTolerance,
47 double angularTolerance,
49 double jointLimitPadding);
53 const Eigen::Isometry3d& pose,
54 Eigen::Vector6d& cartesianVelocity)
const override;
58 const Eigen::Isometry3d& pose)
const override;
88 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
std::shared_ptr< const MetaSkeletonStateSpace > ConstMetaSkeletonStateSpacePtr
Definition: MetaSkeletonStateSpace.hpp:17
This class is a vector field over a MetaSkeletonStateSpace that is defined in terms of a Cartesian ve...
Definition: BodyNodePoseVectorField.hpp:24
double mAngularTolerance
Tolerance of angular error.
Definition: MoveEndEffectorPoseVectorField.hpp:74
Eigen::Vector6d mDesiredTwist
Cache for desired twist between start and goal.
Definition: MoveEndEffectorPoseVectorField.hpp:80
Format of serialized trajectory in YAML.
Definition: algorithm.hpp:4
double mGoalTolerance
Tolerance of pose error.
Definition: MoveEndEffectorPoseVectorField.hpp:65
Vector field for moving end-effector to a goal pose in SE(3).
Definition: MoveEndEffectorPoseVectorField.hpp:22
Eigen::Isometry3d mGoalPose
Goal pose.
Definition: MoveEndEffectorPoseVectorField.hpp:62
double mConversionRatioFromRadianToMeter
Conversion ratio from radius to meter.
Definition: MoveEndEffectorPoseVectorField.hpp:68
Eigen::Vector3d mRotation
Definition: MoveEndEffectorPoseVectorField.hpp:82
std::shared_ptr< double > mLastPoseError
Cache of last pose error.
Definition: MoveEndEffectorPoseVectorField.hpp:85
VectorFieldPlannerStatus evaluateCartesianStatus(const Eigen::Isometry3d &pose) const override
Evaluate current pose to determine the status of planning.
Eigen::Isometry3d mStartPose
Start pose of the end-effector.
Definition: MoveEndEffectorPoseVectorField.hpp:77
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.
VectorFieldPlannerStatus
Status of planning.
Definition: VectorFieldPlannerStatus.hpp:14
Eigen::Vector3d mDirection
Definition: MoveEndEffectorPoseVectorField.hpp:81
double mPositionTolerance
Tolerance of linear deviation error.
Definition: MoveEndEffectorPoseVectorField.hpp:71
bool evaluateCartesianVelocity(const Eigen::Isometry3d &pose, Eigen::Vector6d &cartesianVelocity) const override
Evaluate Cartesian velocity by current pose of body node.