Aikido
VectorFieldConfigurationToEndEffectorOffsetPlanner.hpp
Go to the documentation of this file.
1 #ifndef AIKIDO_PLANNER_VECTORFIELD_VECTORFIELDCONFIGURATIONTOENDEFFECTOROFFSETPLANNER_HPP_
2 #define AIKIDO_PLANNER_VECTORFIELD_VECTORFIELDCONFIGURATIONTOENDEFFECTOROFFSETPLANNER_HPP_
3 
6 
7 namespace aikido {
8 namespace planner {
9 namespace vectorfield {
10 
15 {
16 public:
36  ::dart::dynamics::MetaSkeletonPtr metaSkeleton,
37  double distanceTolerance,
38  double positionTolerance,
39  double angularTolerance,
40  double initialStepSize,
41  double jointLimitTolerance,
42  double constraintCheckResolution,
43  std::chrono::duration<double> timelimit);
44 
57  const SolvableProblem& problem, Result* result = nullptr) override;
58 
59 protected:
63 
67 
70 
73 
77 
80 
82  std::chrono::duration<double> mTimelimit;
83 };
84 
85 } // namespace vectorfield
86 } // namespace planner
87 } // namespace aikido
88 
89 #endif // AIKIDO_PLANNER_VECTORFIELD_VECTORFIELDCONFIGURATIONTOENDEFFECTOROFFSETPLANNER_HPP_
aikido::statespace::dart::ConstMetaSkeletonStateSpacePtr
std::shared_ptr< const MetaSkeletonStateSpace > ConstMetaSkeletonStateSpacePtr
Definition: MetaSkeletonStateSpace.hpp:17
aikido::planner::vectorfield::VectorFieldConfigurationToEndEffectorOffsetPlanner::mPositionTolerance
double mPositionTolerance
How a planned trajectory is allowed to deviated from a straight line segment defined by the direction...
Definition: VectorFieldConfigurationToEndEffectorOffsetPlanner.hpp:66
aikido::planner::vectorfield::VectorFieldConfigurationToEndEffectorOffsetPlanner::mAngularTolerance
double mAngularTolerance
How a planned trajectory is allowed to deviate from a given direction.
Definition: VectorFieldConfigurationToEndEffectorOffsetPlanner.hpp:69
aikido
Format of serialized trajectory in YAML.
Definition: algorithm.hpp:4
aikido::planner::vectorfield::VectorFieldConfigurationToEndEffectorOffsetPlanner::mConstraintCheckResolution
double mConstraintCheckResolution
Resolution used in constraint checking.
Definition: VectorFieldConfigurationToEndEffectorOffsetPlanner.hpp:79
aikido::planner::vectorfield::VectorFieldConfigurationToEndEffectorOffsetPlanner::plan
trajectory::TrajectoryPtr plan(const SolvableProblem &problem, Result *result=nullptr) override
Plan to a trajectory that moves the end-effector by a given direction and distance.
aikido::trajectory::TrajectoryPtr
std::shared_ptr< Trajectory > TrajectoryPtr
Definition: Trajectory.hpp:13
aikido::planner::vectorfield::VectorFieldConfigurationToEndEffectorOffsetPlanner::mTimelimit
std::chrono::duration< double > mTimelimit
Timeout in seconds.
Definition: VectorFieldConfigurationToEndEffectorOffsetPlanner.hpp:82
aikido::planner::SingleProblemPlanner< ConfigurationToEndEffectorOffsetPlanner, ConfigurationToEndEffectorOffset >::SolvableProblem
ConfigurationToEndEffectorOffset SolvableProblem
Definition: SingleProblemPlanner.hpp:25
aikido::planner::dart::ConfigurationToEndEffectorOffsetPlanner
Base planner class for ConfigurationToEndEffectorOffset planning problem.
Definition: ConfigurationToEndEffectorOffsetPlanner.hpp:14
ConfigurationToEndEffectorOffsetPlanner.hpp
aikido::planner::vectorfield::VectorFieldConfigurationToEndEffectorOffsetPlanner::mInitialStepSize
double mInitialStepSize
Initial step size.
Definition: VectorFieldConfigurationToEndEffectorOffsetPlanner.hpp:72
aikido::planner::vectorfield::VectorFieldConfigurationToEndEffectorOffsetPlanner::mJointLimitTolerance
double mJointLimitTolerance
If less then this distance to joint limit, velocity is bounded in that direction to 0.
Definition: VectorFieldConfigurationToEndEffectorOffsetPlanner.hpp:76
ConfigurationToEndEffectorOffset.hpp
aikido::planner::vectorfield::VectorFieldConfigurationToEndEffectorOffsetPlanner::VectorFieldConfigurationToEndEffectorOffsetPlanner
VectorFieldConfigurationToEndEffectorOffsetPlanner(statespace::dart::ConstMetaSkeletonStateSpacePtr stateSpace, ::dart::dynamics::MetaSkeletonPtr metaSkeleton, double distanceTolerance, double positionTolerance, double angularTolerance, double initialStepSize, double jointLimitTolerance, double constraintCheckResolution, std::chrono::duration< double > timelimit)
Constructor.
aikido::planner::vectorfield::VectorFieldConfigurationToEndEffectorOffsetPlanner
Planner that generates a trajectory that moves the end-effector by a given direction and distance.
Definition: VectorFieldConfigurationToEndEffectorOffsetPlanner.hpp:13
aikido::planner::vectorfield::VectorFieldConfigurationToEndEffectorOffsetPlanner::mDistanceTolerance
double mDistanceTolerance
How much a planned trajectory is allowed to deviate from the requested distance to move the end-effec...
Definition: VectorFieldConfigurationToEndEffectorOffsetPlanner.hpp:62
aikido::planner::Planner::Result
Base class for planning result of various planning problems.
Definition: Planner.hpp:58