ompl::base::MotionValidator Class Reference

Abstract definition for a class checking the validity of motions -- path segments between states. This is often called a local planner. The implementation of this class must be thread safe. More...

#include <MotionValidator.h>

Inheritance diagram for ompl::base::MotionValidator:
Inheritance graph
[legend]

List of all members.

Public Member Functions

virtual bool checkMotion (const State *s1, const State *s2, std::pair< State *, double > &lastValid) const =0
 Check if the path between two states is valid. Also compute the last state that was valid and the time of that state. The time is used to parametrize the motion from s1 to s2, s1 being at t = 0 and s2 being at t = 1. This function assumes s1 is valid.
virtual bool checkMotion (const State *s1, const State *s2) const =0
 Check if the path between two states (from s1 to s2) is valid. This function assumes s1 is valid.
unsigned int getInvalidMotionCount (void) const
 Get the number of segments that tested as invalid.
unsigned int getValidMotionCount (void) const
 Get the number of segments that tested as valid.
double getValidMotionFraction (void) const
 Get the fraction of segments that tested as valid.
 MotionValidator (const SpaceInformationPtr &si)
 Constructor.
 MotionValidator (SpaceInformation *si)
 Constructor.
void resetMotionCounter (void)
 Reset the counters for valid and invalid segments.
virtual ~MotionValidator (void)

Protected Attributes

unsigned int invalid_
 Number of invalid segments.
SpaceInformationsi_
 The instance of space information this state validity checker operates on.
unsigned int valid_
 Number of valid segments.

Detailed Description

Abstract definition for a class checking the validity of motions -- path segments between states. This is often called a local planner. The implementation of this class must be thread safe.

Definition at line 62 of file MotionValidator.h.


Constructor & Destructor Documentation

ompl::base::MotionValidator::MotionValidator ( SpaceInformation si  )  [inline]

Constructor.

Definition at line 67 of file MotionValidator.h.

ompl::base::MotionValidator::MotionValidator ( const SpaceInformationPtr si  )  [inline]

Constructor.

Definition at line 72 of file MotionValidator.h.

virtual ompl::base::MotionValidator::~MotionValidator ( void   )  [inline, virtual]

Definition at line 76 of file MotionValidator.h.


Member Function Documentation

virtual bool ompl::base::MotionValidator::checkMotion ( const State s1,
const State s2,
std::pair< State *, double > &  lastValid 
) const [pure virtual]

Check if the path between two states is valid. Also compute the last state that was valid and the time of that state. The time is used to parametrize the motion from s1 to s2, s1 being at t = 0 and s2 being at t = 1. This function assumes s1 is valid.

Parameters:
s1 start state of the motion to be checked (assumed to be valid)
s2 final state of the motion to be checked
lastValid first: storage for the last valid state (may be NULL, if the user does not care about the exact state); this need not be different from s1 or s2. second: the time (between 0 and 1) of the last valid state, on the motion from s1 to s2. If the function returns false, lastValid.first must be set to a valid state, even if that implies copying s1 to lastValid.first (in case lastValid.second = 0). If the function returns true, lastValid.first and lastValid.second should not be modified.
Note:
This function updates the number of valid and invalid segments.

Implemented in ompl::base::DiscreteMotionValidator.

virtual bool ompl::base::MotionValidator::checkMotion ( const State s1,
const State s2 
) const [pure virtual]

Check if the path between two states (from s1 to s2) is valid. This function assumes s1 is valid.

Note:
This function updates the number of valid and invalid segments.

Implemented in ompl::base::DiscreteMotionValidator.

unsigned int ompl::base::MotionValidator::getInvalidMotionCount ( void   )  const [inline]

Get the number of segments that tested as invalid.

Definition at line 102 of file MotionValidator.h.

unsigned int ompl::base::MotionValidator::getValidMotionCount ( void   )  const [inline]

Get the number of segments that tested as valid.

Definition at line 96 of file MotionValidator.h.

double ompl::base::MotionValidator::getValidMotionFraction ( void   )  const [inline]

Get the fraction of segments that tested as valid.

Definition at line 108 of file MotionValidator.h.

void ompl::base::MotionValidator::resetMotionCounter ( void   )  [inline]

Reset the counters for valid and invalid segments.

Definition at line 114 of file MotionValidator.h.


Member Data Documentation

unsigned int ompl::base::MotionValidator::invalid_ [mutable, protected]

Number of invalid segments.

Definition at line 128 of file MotionValidator.h.

The instance of space information this state validity checker operates on.

Definition at line 122 of file MotionValidator.h.

unsigned int ompl::base::MotionValidator::valid_ [mutable, protected]

Number of valid segments.

Definition at line 125 of file MotionValidator.h.


The documentation for this class was generated from the following file:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines


ompl
Author(s): Ioan Sucan/isucan@rice.edu, Mark Moll/mmoll@rice.edu, Lydia Kavraki/kavraki@rice.edu
autogenerated on Fri Jan 11 09:33:59 2013