Aikido
VectorFieldConfigurationToEndEffectorPosePlanner.hpp
Go to the documentation of this file.
1 #ifndef AIKIDO_PLANNER_VECTORFIELD_VECTORFIELDCONFIGURATIONTOENDEFFECTORPOSEPLANNER_HPP_
2 #define AIKIDO_PLANNER_VECTORFIELD_VECTORFIELDCONFIGURATIONTOENDEFFECTORPOSEPLANNER_HPP_
3 
6 
7 namespace aikido {
8 namespace planner {
9 namespace vectorfield {
10 
15 {
16 public:
37  ::dart::dynamics::MetaSkeletonPtr metaSkeleton,
38  double goalTolerance,
39  double anglePoseRatio,
40  double positionTolerance,
41  double angularTolerance,
42  double initialStepSize,
43  double jointLimitTolerance,
44  double constraintCheckResolution,
45  std::chrono::duration<double> timelimit);
46 
59  const SolvableProblem& problem, Result* result = nullptr) override;
60 
61 protected:
64 
68 
72 
75 
78 
82 
85 
87  std::chrono::duration<double> mTimelimit;
88 };
89 
90 } // namespace vectorfield
91 } // namespace planner
92 } // namespace aikido
93 
94 #endif // AIKIDO_PLANNER_VECTORFIELD_VECTORFIELDCONFIGURATIONTOENDEFFECTORPOSEPLANNER_HPP_
aikido::planner::vectorfield::VectorFieldConfigurationToEndEffectorPosePlanner::mPositionTolerance
double mPositionTolerance
How a planned trajectory is allowed to deviated from a straight line segment defined by the direction...
Definition: VectorFieldConfigurationToEndEffectorPosePlanner.hpp:71
aikido::statespace::dart::ConstMetaSkeletonStateSpacePtr
std::shared_ptr< const MetaSkeletonStateSpace > ConstMetaSkeletonStateSpacePtr
Definition: MetaSkeletonStateSpace.hpp:17
aikido::planner::vectorfield::VectorFieldConfigurationToEndEffectorPosePlanner::mGoalTolerance
double mGoalTolerance
Tolerated geodesic distance from goal.
Definition: VectorFieldConfigurationToEndEffectorPosePlanner.hpp:63
aikido::planner::vectorfield::VectorFieldConfigurationToEndEffectorPosePlanner::mConstraintCheckResolution
double mConstraintCheckResolution
Resolution used in constraint checking.
Definition: VectorFieldConfigurationToEndEffectorPosePlanner.hpp:84
aikido
Format of serialized trajectory in YAML.
Definition: algorithm.hpp:4
aikido::planner::vectorfield::VectorFieldConfigurationToEndEffectorPosePlanner
Planner that generates a trajectory that moves the end-effector to a given pose.
Definition: VectorFieldConfigurationToEndEffectorPosePlanner.hpp:13
aikido::planner::dart::ConfigurationToEndEffectorPosePlanner
Base planner class for ConfigurationToEndEffectorPose planning problem.
Definition: ConfigurationToEndEffectorPosePlanner.hpp:14
ConfigurationToEndEffectorPose.hpp
aikido::trajectory::TrajectoryPtr
std::shared_ptr< Trajectory > TrajectoryPtr
Definition: Trajectory.hpp:13
aikido::planner::vectorfield::VectorFieldConfigurationToEndEffectorPosePlanner::mAnglePoseRatio
double mAnglePoseRatio
Conversion ratio from radian to meter in computing the combined geodesic error.
Definition: VectorFieldConfigurationToEndEffectorPosePlanner.hpp:67
aikido::planner::vectorfield::VectorFieldConfigurationToEndEffectorPosePlanner::VectorFieldConfigurationToEndEffectorPosePlanner
VectorFieldConfigurationToEndEffectorPosePlanner(statespace::dart::ConstMetaSkeletonStateSpacePtr stateSpace, ::dart::dynamics::MetaSkeletonPtr metaSkeleton, double goalTolerance, double anglePoseRatio, double positionTolerance, double angularTolerance, double initialStepSize, double jointLimitTolerance, double constraintCheckResolution, std::chrono::duration< double > timelimit)
Constructor.
aikido::planner::SingleProblemPlanner< ConfigurationToEndEffectorPosePlanner, ConfigurationToEndEffectorPose >::SolvableProblem
ConfigurationToEndEffectorPose SolvableProblem
Definition: SingleProblemPlanner.hpp:25
aikido::planner::vectorfield::VectorFieldConfigurationToEndEffectorPosePlanner::plan
trajectory::TrajectoryPtr plan(const SolvableProblem &problem, Result *result=nullptr) override
Plan to a trajectory that moves the end-effector to a given pose.
aikido::planner::vectorfield::VectorFieldConfigurationToEndEffectorPosePlanner::mAngularTolerance
double mAngularTolerance
How a planned trajectory is allowed to deviate from a given direction.
Definition: VectorFieldConfigurationToEndEffectorPosePlanner.hpp:74
aikido::planner::vectorfield::VectorFieldConfigurationToEndEffectorPosePlanner::mInitialStepSize
double mInitialStepSize
Initial step size.
Definition: VectorFieldConfigurationToEndEffectorPosePlanner.hpp:77
aikido::planner::vectorfield::VectorFieldConfigurationToEndEffectorPosePlanner::mJointLimitTolerance
double mJointLimitTolerance
If less then this distance to joint limit, velocity is bounded in that direction to 0.
Definition: VectorFieldConfigurationToEndEffectorPosePlanner.hpp:81
ConfigurationToEndEffectorPosePlanner.hpp
aikido::planner::vectorfield::VectorFieldConfigurationToEndEffectorPosePlanner::mTimelimit
std::chrono::duration< double > mTimelimit
Timeout in seconds.
Definition: VectorFieldConfigurationToEndEffectorPosePlanner.hpp:87
aikido::planner::Planner::Result
Base class for planning result of various planning problems.
Definition: Planner.hpp:58