Go to the documentation of this file. 1 #ifndef AIKIDO_PLANNER_VECTORFIELD_VECTORFIELDPLANNER_HPP_
2 #define AIKIDO_PLANNER_VECTORFIELD_VECTORFIELDPLANNER_HPP_
12 namespace vectorfield {
34 std::chrono::duration<double> timelimit,
35 double initialStepSize,
36 double checkConstraintResolution,
37 planner::Planner::Result* result);
63 const statespace::dart::MetaSkeletonStateSpace::State& startState,
64 ::dart::dynamics::MetaSkeletonPtr metaskeleton,
65 const ::dart::dynamics::ConstBodyNodePtr& bn,
67 const Eigen::Vector3d& direction,
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);
102 const statespace::dart::MetaSkeletonStateSpace::State& startState,
103 ::dart::dynamics::MetaSkeletonPtr metaskeleton,
104 const ::dart::dynamics::ConstBodyNodePtr& bn,
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);
121 #endif // AIKIDO_PLANNER_VECTORFIELD_VECTORFIELDPLANNER_HPP_
std::shared_ptr< const MetaSkeletonStateSpace > ConstMetaSkeletonStateSpacePtr
Definition: MetaSkeletonStateSpace.hpp:17
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.
Format of serialized trajectory in YAML.
Definition: algorithm.hpp:4
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.
Constraint which can be tested.
Definition: Testable.hpp:17
std::unique_ptr< Interpolated > UniqueInterpolatedPtr
Definition: Interpolated.hpp:11
This class defines a vector field.
Definition: VectorField.hpp:18
Definition: StateSpace.hpp:167
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...
std::shared_ptr< const Testable > ConstTestablePtr
Definition: Testable.hpp:13