Go to the documentation of this file. 1 #ifndef AIKIDO_PLANNER_VECTORFIELD_MOVEENDEFFECTOROFFSETVECTORFIELD_HPP_
2 #define AIKIDO_PLANNER_VECTORFIELD_MOVEENDEFFECTOROFFSETVECTORFIELD_HPP_
8 namespace vectorfield {
42 ::dart::dynamics::MetaSkeletonPtr metaskeleton,
43 ::dart::dynamics::ConstBodyNodePtr bn,
44 const Eigen::Vector3d& direction,
47 double positionTolerance,
48 double angularTolerance,
50 double jointLimitPadding);
54 const Eigen::Isometry3d& pose,
55 Eigen::Vector6d& cartesianVelocity)
const override;
59 const Eigen::Isometry3d& pose)
const override;
81 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
VectorFieldPlannerStatus evaluateCartesianStatus(const Eigen::Isometry3d &pose) const override
Evaluate current pose to determine the status of planning.
double mMaxDistance
Maximum distance allowed to move.
Definition: MoveEndEffectorOffsetVectorField.hpp:69
Format of serialized trajectory in YAML.
Definition: algorithm.hpp:4
MoveEndEffectorOffsetVectorField(aikido::statespace::dart::ConstMetaSkeletonStateSpacePtr stateSpace, ::dart::dynamics::MetaSkeletonPtr metaskeleton, ::dart::dynamics::ConstBodyNodePtr bn, const Eigen::Vector3d &direction, double minDistance, double maxDistance, double positionTolerance, double angularTolerance, double maxStepSize, double jointLimitPadding)
Constructor.
double mMinDistance
Minimum movement distance.
Definition: MoveEndEffectorOffsetVectorField.hpp:66
bool evaluateCartesianVelocity(const Eigen::Isometry3d &pose, Eigen::Vector6d &cartesianVelocity) const override
Evaluate Cartesian velocity by current pose of body node.
double mAngularTolerance
Tolerance of angular error.
Definition: MoveEndEffectorOffsetVectorField.hpp:75
Eigen::Isometry3d mStartPose
Start pose of the end-effector.
Definition: MoveEndEffectorOffsetVectorField.hpp:78
Eigen::Vector3d mDirection
Movement direction.
Definition: MoveEndEffectorOffsetVectorField.hpp:63
Vector field for moving end-effector by a direction and distance.
Definition: MoveEndEffectorOffsetVectorField.hpp:21
VectorFieldPlannerStatus
Status of planning.
Definition: VectorFieldPlannerStatus.hpp:14
double mPositionTolerance
Tolerance of linear deviation error.
Definition: MoveEndEffectorOffsetVectorField.hpp:72