Aikido
VectorFieldPlanner.hpp
Go to the documentation of this file.
1 #ifndef AIKIDO_PLANNER_VECTORFIELD_VECTORFIELDPLANNER_HPP_
2 #define AIKIDO_PLANNER_VECTORFIELD_VECTORFIELDPLANNER_HPP_
3 
9 
10 namespace aikido {
11 namespace planner {
12 namespace vectorfield {
13 
32  const aikido::statespace::StateSpace::State& startState,
33  const aikido::constraint::Testable& constraint,
34  std::chrono::duration<double> timelimit,
35  double initialStepSize,
36  double checkConstraintResolution,
37  planner::Planner::Result* result);
38 
63  const statespace::dart::MetaSkeletonStateSpace::State& startState,
64  ::dart::dynamics::MetaSkeletonPtr metaskeleton,
65  const ::dart::dynamics::ConstBodyNodePtr& bn,
66  const aikido::constraint::ConstTestablePtr& constraint,
67  const Eigen::Vector3d& direction,
68  double minDistance,
69  double maxDistance,
70  double positionTolerance,
71  double angularTolerance,
72  double initialStepSize,
73  double jointLimitTolerance,
74  double constraintCheckResolution,
75  std::chrono::duration<double> timelimit,
76  planner::Planner::Result* result = nullptr);
77 
102  const statespace::dart::MetaSkeletonStateSpace::State& startState,
103  ::dart::dynamics::MetaSkeletonPtr metaskeleton,
104  const ::dart::dynamics::ConstBodyNodePtr& bn,
105  const aikido::constraint::ConstTestablePtr& constraint,
106  const Eigen::Isometry3d& goalPose,
107  double goalTolerance,
108  double conversionRatioInGeodesicDistance,
109  double positionTolerance,
110  double angularTolerance,
111  double initialStepSize,
112  double jointLimitTolerance,
113  double constraintCheckResolution,
114  std::chrono::duration<double> timelimit,
115  planner::Planner::Result* result = nullptr);
116 
117 } // namespace vectorfield
118 } // namespace planner
119 } // namespace aikido
120 
121 #endif // AIKIDO_PLANNER_VECTORFIELD_VECTORFIELDPLANNER_HPP_
aikido::statespace::dart::ConstMetaSkeletonStateSpacePtr
std::shared_ptr< const MetaSkeletonStateSpace > ConstMetaSkeletonStateSpacePtr
Definition: MetaSkeletonStateSpace.hpp:17
aikido::planner::vectorfield::followVectorField
aikido::trajectory::UniqueInterpolatedPtr followVectorField(const aikido::planner::vectorfield::VectorField &vectorField, const aikido::statespace::StateSpace::State &startState, const aikido::constraint::Testable &constraint, std::chrono::duration< double > timelimit, double initialStepSize, double checkConstraintResolution, planner::Planner::Result *result)
Generate a trajectory following the vector field along given time.
aikido
Format of serialized trajectory in YAML.
Definition: algorithm.hpp:4
aikido::planner::vectorfield::planToEndEffectorOffset
aikido::trajectory::UniqueInterpolatedPtr planToEndEffectorOffset(const aikido::statespace::dart::ConstMetaSkeletonStateSpacePtr &stateSpace, const statespace::dart::MetaSkeletonStateSpace::State &startState, ::dart::dynamics::MetaSkeletonPtr metaskeleton, const ::dart::dynamics::ConstBodyNodePtr &bn, const aikido::constraint::ConstTestablePtr &constraint, const Eigen::Vector3d &direction, double minDistance, double maxDistance, double positionTolerance, double angularTolerance, double initialStepSize, double jointLimitTolerance, double constraintCheckResolution, std::chrono::duration< double > timelimit, planner::Planner::Result *result=nullptr)
Plan to a trajectory that moves the end-effector by a given direction and distance.
aikido::constraint::Testable
Constraint which can be tested.
Definition: Testable.hpp:17
Interpolated.hpp
aikido::trajectory::UniqueInterpolatedPtr
std::unique_ptr< Interpolated > UniqueInterpolatedPtr
Definition: Interpolated.hpp:11
VectorField.hpp
Testable.hpp
MetaSkeletonStateSpace.hpp
aikido::planner::vectorfield::VectorField
This class defines a vector field.
Definition: VectorField.hpp:18
aikido::statespace::StateSpace::State
Definition: StateSpace.hpp:167
aikido::planner::vectorfield::planToEndEffectorPose
aikido::trajectory::UniqueInterpolatedPtr planToEndEffectorPose(const aikido::statespace::dart::ConstMetaSkeletonStateSpacePtr &stateSpace, const statespace::dart::MetaSkeletonStateSpace::State &startState, ::dart::dynamics::MetaSkeletonPtr metaskeleton, const ::dart::dynamics::ConstBodyNodePtr &bn, const aikido::constraint::ConstTestablePtr &constraint, const Eigen::Isometry3d &goalPose, double goalTolerance, double conversionRatioInGeodesicDistance, double positionTolerance, double angularTolerance, double initialStepSize, double jointLimitTolerance, double constraintCheckResolution, std::chrono::duration< double > timelimit, planner::Planner::Result *result=nullptr)
Plan to an end-effector pose by following a geodesic loss function in SE(3) via an optimized Jacobian...
Planner.hpp
aikido::constraint::ConstTestablePtr
std::shared_ptr< const Testable > ConstTestablePtr
Definition: Testable.hpp:13