Aikido
MoveEndEffectorOffsetVectorField.hpp
Go to the documentation of this file.
1 #ifndef AIKIDO_PLANNER_VECTORFIELD_MOVEENDEFFECTOROFFSETVECTORFIELD_HPP_
2 #define AIKIDO_PLANNER_VECTORFIELD_MOVEENDEFFECTOROFFSETVECTORFIELD_HPP_
3 
5 
6 namespace aikido {
7 namespace planner {
8 namespace vectorfield {
9 
22 {
23 public:
42  ::dart::dynamics::MetaSkeletonPtr metaskeleton,
43  ::dart::dynamics::ConstBodyNodePtr bn,
44  const Eigen::Vector3d& direction,
45  double minDistance,
46  double maxDistance,
47  double positionTolerance,
48  double angularTolerance,
49  double maxStepSize,
50  double jointLimitPadding);
51 
52  // Documentation inherited.
54  const Eigen::Isometry3d& pose,
55  Eigen::Vector6d& cartesianVelocity) const override;
56 
57  // Documentation inherited.
59  const Eigen::Isometry3d& pose) const override;
60 
61 protected:
63  Eigen::Vector3d mDirection;
64 
66  double mMinDistance;
67 
69  double mMaxDistance;
70 
73 
76 
78  Eigen::Isometry3d mStartPose;
79 
80 public:
81  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
82 };
83 
84 } // namespace vectorfield
85 } // namespace planner
86 } // namespace aikido
87 
88 #endif // ifndef
89  // AIKIDO_PLANNER_VECTORFIELD_MOVEENDEFFECTOROFFSETVECTORFIELD_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::MoveEndEffectorOffsetVectorField::evaluateCartesianStatus
VectorFieldPlannerStatus evaluateCartesianStatus(const Eigen::Isometry3d &pose) const override
Evaluate current pose to determine the status of planning.
aikido::planner::vectorfield::MoveEndEffectorOffsetVectorField::mMaxDistance
double mMaxDistance
Maximum distance allowed to move.
Definition: MoveEndEffectorOffsetVectorField.hpp:69
aikido
Format of serialized trajectory in YAML.
Definition: algorithm.hpp:4
aikido::planner::vectorfield::MoveEndEffectorOffsetVectorField::MoveEndEffectorOffsetVectorField
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.
aikido::planner::vectorfield::MoveEndEffectorOffsetVectorField::mMinDistance
double mMinDistance
Minimum movement distance.
Definition: MoveEndEffectorOffsetVectorField.hpp:66
aikido::planner::vectorfield::MoveEndEffectorOffsetVectorField::evaluateCartesianVelocity
bool evaluateCartesianVelocity(const Eigen::Isometry3d &pose, Eigen::Vector6d &cartesianVelocity) const override
Evaluate Cartesian velocity by current pose of body node.
aikido::planner::vectorfield::MoveEndEffectorOffsetVectorField::mAngularTolerance
double mAngularTolerance
Tolerance of angular error.
Definition: MoveEndEffectorOffsetVectorField.hpp:75
aikido::planner::vectorfield::MoveEndEffectorOffsetVectorField::mStartPose
Eigen::Isometry3d mStartPose
Start pose of the end-effector.
Definition: MoveEndEffectorOffsetVectorField.hpp:78
aikido::planner::vectorfield::MoveEndEffectorOffsetVectorField::mDirection
Eigen::Vector3d mDirection
Movement direction.
Definition: MoveEndEffectorOffsetVectorField.hpp:63
aikido::planner::vectorfield::MoveEndEffectorOffsetVectorField
Vector field for moving end-effector by a direction and distance.
Definition: MoveEndEffectorOffsetVectorField.hpp:21
aikido::planner::vectorfield::VectorFieldPlannerStatus
VectorFieldPlannerStatus
Status of planning.
Definition: VectorFieldPlannerStatus.hpp:14
aikido::planner::vectorfield::MoveEndEffectorOffsetVectorField::mPositionTolerance
double mPositionTolerance
Tolerance of linear deviation error.
Definition: MoveEndEffectorOffsetVectorField.hpp:72