Aikido
|
Planner that generates a trajectory that moves the end-effector by a given direction and distance. More...
#include <aikido/planner/vectorfield/VectorFieldConfigurationToEndEffectorOffsetPlanner.hpp>
Public Member Functions | |
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. More... | |
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. More... | |
![]() | |
ConfigurationToEndEffectorOffsetPlanner (statespace::dart::ConstMetaSkeletonStateSpacePtr stateSpace, ::dart::dynamics::MetaSkeletonPtr metaSkeleton) | |
Constructor. More... | |
virtual trajectory::TrajectoryPtr | plan (const SolvableProblem &problem, Result *result=nullptr)=0 |
Solves problem returning the result to result . More... | |
![]() | |
SingleProblemPlanner (statespace::dart::ConstMetaSkeletonStateSpacePtr stateSpace, ::dart::dynamics::MetaSkeletonPtr metaSkeleton) | |
Constructor. More... | |
statespace::dart::ConstMetaSkeletonStateSpacePtr | getMetaSkeletonStateSpace () const |
Return this planner's MetaSkeletonStateSpace. More... | |
::dart::dynamics::MetaSkeletonPtr | getMetaSkeleton () |
Return this planner's MetaSkeleton. More... | |
![]() | |
SingleProblemPlanner (statespace::ConstStateSpacePtr stateSpace, common::RNG *rng=nullptr) | |
bool | canSolve (const Problem &problem) const final override |
Returns true if this planner can solve problem . More... | |
trajectory::TrajectoryPtr | plan (const Problem &problem, Result *result=nullptr) final override |
Solves problem returning the result to result . More... | |
![]() | |
Planner (statespace::ConstStateSpacePtr stateSpace, common::RNG *rng=nullptr) | |
Constructs from a state space. More... | |
virtual | ~Planner ()=default |
Default destructor. More... | |
statespace::ConstStateSpacePtr | getStateSpace () const |
Returns const state space. More... | |
common::RNG * | getRng () |
Returns RNG. More... | |
Protected Attributes | |
double | mDistanceTolerance |
How much a planned trajectory is allowed to deviate from the requested distance to move the end-effector. More... | |
double | mPositionTolerance |
How a planned trajectory is allowed to deviated from a straight line segment defined by the direction and the distance. More... | |
double | mAngularTolerance |
How a planned trajectory is allowed to deviate from a given direction. More... | |
double | mInitialStepSize |
Initial step size. More... | |
double | mJointLimitTolerance |
If less then this distance to joint limit, velocity is bounded in that direction to 0. More... | |
double | mConstraintCheckResolution |
Resolution used in constraint checking. More... | |
std::chrono::duration< double > | mTimelimit |
Timeout in seconds. More... | |
![]() | |
statespace::dart::ConstMetaSkeletonStateSpacePtr | mMetaSkeletonStateSpace |
Stores stateSpace pointer as a ConstMetaSkeletonStateSpacePtr. More... | |
::dart::dynamics::MetaSkeletonPtr | mMetaSkeleton |
MetaSkeleton to use for planning. More... | |
![]() | |
statespace::ConstStateSpacePtr | mStateSpace |
State space associated with this planner. More... | |
std::unique_ptr< common::RNG > | mRng |
RNG the planner uses. More... | |
Additional Inherited Members | |
![]() | |
using | SolvableProblem = ConfigurationToEndEffectorOffset |
Planner that generates a trajectory that moves the end-effector by a given direction and distance.
aikido::planner::vectorfield::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.
[in] | stateSpace | State space that this planner is associated with. |
[in] | metaSkeleton | MetaSkeleton to plan with. |
[in] | distanceTolerance | How much a planned trajectory is allowed to deviate from the requested distance to move the end-effector. |
[in] | positionTolerance | How a planned trajectory is allowed to deviated from a straight line segment defined by the direction and the distance. |
[in] | angularTolerance | How a planned trajectory is allowed to deviate from a given direction. |
[in] | initialStepSize | Initial step size. |
[in] | jointLimitTolerance | If less then this distance to joint limit, velocity is bounded in that direction to 0. |
[in] | constraintCheckResolution | Resolution used in constraint checking. |
[in] | timelimit | timeout in seconds. |
|
override |
Plan to a trajectory that moves the end-effector by a given direction and distance.
The planner returns success if the resulting trajectory satisfies constraint at some resolution and failure (returning nullptr
) otherwise. The reason for the failure is stored in the result
output parameter.
[in] | problem | Planning problem. |
[out] | result | Information about success or failure. |
nullptr
if planning failed.
|
protected |
How a planned trajectory is allowed to deviate from a given direction.
|
protected |
Resolution used in constraint checking.
|
protected |
How much a planned trajectory is allowed to deviate from the requested distance to move the end-effector.
|
protected |
Initial step size.
|
protected |
If less then this distance to joint limit, velocity is bounded in that direction to 0.
|
protected |
How a planned trajectory is allowed to deviated from a straight line segment defined by the direction and the distance.
|
protected |
Timeout in seconds.