Definition of a geometric path. More...
#include <PathGeometric.h>
Public Member Functions | |
PathGeometric (const base::SpaceInformationPtr &si) | |
Construct a path instance for a given space information. | |
PathGeometric (const PathGeometric &path) | |
Copy constructor. | |
PathGeometric (const base::SpaceInformationPtr &si, const base::State *state) | |
Construct a path instance from a single state. | |
PathGeometric (const base::SpaceInformationPtr &si, const base::State *state1, const base::State *state2) | |
Construct a path instance from two states (thus making a segment) | |
PathGeometric & | operator= (const PathGeometric &other) |
Assignment operator. | |
virtual double | length (void) const |
Compute the length of a geometric path (sum of lengths of segments that make up the path) | |
virtual bool | check (void) const |
Check if the path is valid. | |
double | smoothness (void) const |
Compute a notion of smootheness for this path. The closer the value is to 0, the smoother the path. Detailed formula follows. | |
double | clearance (void) const |
Compute the clearance of the way-points along the path (no interpolation is performed). Detailed formula follows. | |
virtual void | print (std::ostream &out) const |
Print the path to a stream. | |
void | computeFastTimeParametrization (double maxVel, double maxAcc, std::vector< double > ×, unsigned int maxSteps=10) const |
Compute the time parametrization for the states along this path. | |
Path operations | |
void | interpolate (unsigned int count) |
Insert a number of states in a path so that the path is made up of exactly count states. States are inserted uniformly (more states on longer segments). Changes are performed only if a path has less than count states. | |
void | interpolate (void) |
Insert a number of states in a path so that the path is made up of (approximately) the states checked for validity when a discrete motion validator is used. | |
void | subdivide (void) |
Add a state at the middle of each segment. | |
void | reverse (void) |
Reverse the path. | |
std::pair< bool, bool > | checkAndRepair (unsigned int attempts) |
Check if the path is valid. If it is not, attempts are made to fix the path by sampling around invalid states. Not more than attempts samples are drawn. A pair of boolean values is returned. The first value represents the validity of the path before any change was made. The second value represents the validity of the path after changes were attempted. If no changes are attempted, the both values are true. | |
void | overlay (const PathGeometric &over, unsigned int startIndex=0) |
Overlay the path over on top of the current path. States are added to the current path if needed (by copying the last state). | |
void | append (const base::State *state) |
Append state to the end of this path. The memory for state is copied. | |
void | append (const PathGeometric &path) |
Append path at the end of this path. States from path are copied. | |
void | keepAfter (const base::State *state) |
Keep the part of the path that is after state (getClosestIndex() is used to find out which way-point is closest to state) | |
void | keepBefore (const base::State *state) |
Keep the part of the path that is before state (getClosestIndex() is used to find out which way-point is closest to state) | |
void | random (void) |
Set this path to a random segment. | |
bool | randomValid (unsigned int attempts) |
Set this path to a random valid segment. Sample attempts times for valid segments. Returns true on success. | |
Functionality for accessing states | |
int | getClosestIndex (const base::State *state) const |
Get the index of the way-point along the path that is closest to state. Returns -1 for an empty path. | |
std::vector< base::State * > & | getStates (void) |
Get the states that make up the path (as a reference, so it can be modified, hence the function is not const) | |
base::State * | getState (unsigned int index) |
Get the state located at index along the path. | |
const base::State * | getState (unsigned int index) const |
Get the state located at index along the path. | |
std::size_t | getStateCount (void) const |
Get the number of states (way-points) that make up this path. | |
![]() | |
Path (const SpaceInformationPtr &si) | |
Constructor. A path must always know the space information it is part of. | |
virtual | ~Path (void) |
Destructor. | |
const SpaceInformationPtr & | getSpaceInformation (void) const |
Get the space information associated to this class. |
Protected Member Functions | |
void | freeMemory (void) |
Free the memory corresponding to the states on this path. | |
void | copyFrom (const PathGeometric &other) |
Copy data to this path from another path instance. |
Protected Attributes | |
std::vector< base::State * > | states_ |
The list of states that make up the path. | |
![]() | |
SpaceInformationPtr | si_ |
The space information this path is part of. |
Definition of a geometric path.
This is the type of path computed by geometric planners.
Definition at line 55 of file PathGeometric.h.
void ompl::geometric::PathGeometric::append | ( | const PathGeometric & | path | ) |
Append path at the end of this path. States from path are copied.
Let the existing path consist of states [ s1, s2, ..., sk ]. Let path consist of states [y1, ..., yp].
If the existing path and path consist of states from the same state space, [y1, ..., yp] are added after sk. If they are not from the same state space, states [z1, ..., zp] are added, where each zi is a copy of sk that has components overwritten with ones in yi (if there are any common subspaces).
Definition at line 413 of file PathGeometric.cpp.
std::pair< bool, bool > ompl::geometric::PathGeometric::checkAndRepair | ( | unsigned int | attempts | ) |
Check if the path is valid. If it is not, attempts are made to fix the path by sampling around invalid states. Not more than attempts samples are drawn. A pair of boolean values is returned. The first value represents the validity of the path before any change was made. The second value represents the validity of the path after changes were attempted. If no changes are attempted, the both values are true.
Definition at line 170 of file PathGeometric.cpp.
double ompl::geometric::PathGeometric::clearance | ( | void | ) | const |
Compute the clearance of the way-points along the path (no interpolation is performed). Detailed formula follows.
The formula used for computing clearance is:
is the number of states along the path (see getStateCount())
is the ith state along the path (see getState())
gives the distance to the nearest invalid state for a particular state (see ompl::base::StateValidityChecker::clearance())
Definition at line 95 of file PathGeometric.cpp.
void ompl::geometric::PathGeometric::computeFastTimeParametrization | ( | double | maxVel, |
double | maxAcc, | ||
std::vector< double > & | times, | ||
unsigned int | maxSteps = 10 |
||
) | const |
Compute the time parametrization for the states along this path.
maxVel | The maximum velocity to be attained |
maxAcc | The maximum acceleration of the system |
times | The time stamp (in seconds) for each of the states along the path. Starts at 0.0 |
maxSteps | The maximum number of steps to run this algorithm for (the algorithm is iterative) |
Definition at line 493 of file PathGeometric.cpp.
void ompl::geometric::PathGeometric::overlay | ( | const PathGeometric & | over, |
unsigned int | startIndex = 0 |
||
) |
Overlay the path over on top of the current path. States are added to the current path if needed (by copying the last state).
If over consists of states form a different state space than the existing path, the data from those states is copied over, for the corresponding components. If over is from the same state space as this path, and startIndex is 0, this function's result will be the same as with operator=()
Definition at line 387 of file PathGeometric.cpp.
double ompl::geometric::PathGeometric::smoothness | ( | void | ) | const |
Compute a notion of smootheness for this path. The closer the value is to 0, the smoother the path. Detailed formula follows.
The idea is to look at the triangles formed by consecutive path segments and compute the angle between those segments using Pythagora's theorem. Then, the outside angle for the computed angle is normalized by the path segments and contributes to the path smoothness. For a straight line path, the smoothness will be 0.
where ,
is the ith state along the path (see getState()) and
gives the distance between two states (see ompl::base::StateSpace::distance()).
Definition at line 107 of file PathGeometric.cpp.