ompl::base::Goal Class Reference

Abstract definition of goals. Will contain solutions, if found. More...

#include <Goal.h>

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

List of all members.

Public Member Functions

template<class T >
const T * as (void) const
 Cast this instance to a desired type.
template<class T >
T * as (void)
 Cast this instance to a desired type.
void clearSolutionPath (void)
 Forget the solution path. Memory is freed.
double getDifference (void) const
 If a difference between the desired solution and the solution found is computed by the planner, this functions returns it.
double getMaximumPathLength (void) const
 Get the maximum length allowed for a solution path.
const PathPtrgetSolutionPath (void) const
 Return the found solution path.
const SpaceInformationPtrgetSpaceInformation (void) const
 Get the space information this goal is for.
GoalType getType (void) const
 Return the goal type.
 Goal (const SpaceInformationPtr &si)
 Constructor. The goal must always know the space information it is part of.
bool hasType (GoalType type) const
 Check if this goal can be cast to a particular goal type.
bool isAchieved (void) const
 Returns true if a solution path has been found (could be approximate).
bool isApproximate (void) const
 Return true if the found solution is approximate (does not actually reach the desired goal, but hopefully is closer to it).
bool isSatisfied (const State *st, double pathLength, double *distance) const
 Return true if the state satisfies the goal constraints and the path length is less than the desired maximum length. This call also computes the distance between the state given as argument and the goal.
virtual bool isSatisfied (const State *st, double *distance) const
 Return true if the state satisfies the goal constraints and compute the distance between the state given as argument and the goal (even if the goal is not satisfied). This distance can be an approximation. It can even be set to a constant, if such a computation is not possible.
virtual bool isSatisfied (const State *st) const =0
 Return true if the state satisfies the goal constraints.
virtual bool isStartGoalPairValid (const State *, const State *) const
 Since there can be multiple starting states (and multiple goal states) it is possible certain pairs are not to be allowed. By default we however assume all such pairs are allowed. Note: if this function returns true, isSatisfied() need not be called.
virtual void print (std::ostream &out=std::cout) const
 Print information about the goal.
void setDifference (double difference)
 Set the difference between the found solution path and the desired solution path.
void setMaximumPathLength (double maximumPathLength)
 Set the maximum length allowed for a solution path. This value is checked only in the version of isSatisfied() that takes the path length as argument.
void setSolutionPath (const PathPtr &path, bool approximate=false)
 Update the solution path. If a previous solution path exists, it is deleted.
virtual ~Goal (void)
 Destructor. Clears the solution as well.

Protected Attributes

bool approximate_
 True if goal was not achieved, but an approximate solution was found.
double difference_
 The achieved difference between the found solution and the desired goal.
double maximumPathLength_
 The maximum length allowed for the solution path.
PathPtr path_
 Solution path, if found.
SpaceInformationPtr si_
 The space information for this goal.
GoalType type_
 Goal type.

Detailed Description

Abstract definition of goals. Will contain solutions, if found.

Definition at line 54 of file Goal.h.


Constructor & Destructor Documentation

ompl::base::Goal::Goal ( const SpaceInformationPtr si  ) 

Constructor. The goal must always know the space information it is part of.

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

Destructor. Clears the solution as well.

Definition at line 62 of file Goal.h.


Member Function Documentation

template<class T >
const T* ompl::base::Goal::as ( void   )  const [inline]

Cast this instance to a desired type.

Make sure the type we are casting to is indeed a goal

Definition at line 78 of file Goal.h.

template<class T >
T* ompl::base::Goal::as ( void   )  [inline]

Cast this instance to a desired type.

Make sure the type we are casting to is indeed a goal

Definition at line 68 of file Goal.h.

void ompl::base::Goal::clearSolutionPath ( void   )  [inline]

Forget the solution path. Memory is freed.

Definition at line 181 of file Goal.h.

double ompl::base::Goal::getDifference ( void   )  const [inline]

If a difference between the desired solution and the solution found is computed by the planner, this functions returns it.

Definition at line 189 of file Goal.h.

double ompl::base::Goal::getMaximumPathLength ( void   )  const [inline]

Get the maximum length allowed for a solution path.

Definition at line 150 of file Goal.h.

const PathPtr& ompl::base::Goal::getSolutionPath ( void   )  const [inline]

Return the found solution path.

This will need to be casted into the specialization computed by the planner

Definition at line 168 of file Goal.h.

const SpaceInformationPtr& ompl::base::Goal::getSpaceInformation ( void   )  const [inline]

Get the space information this goal is for.

Definition at line 99 of file Goal.h.

GoalType ompl::base::Goal::getType ( void   )  const [inline]

Return the goal type.

Definition at line 87 of file Goal.h.

bool ompl::base::Goal::hasType ( GoalType  type  )  const [inline]

Check if this goal can be cast to a particular goal type.

Definition at line 93 of file Goal.h.

bool ompl::base::Goal::isAchieved ( void   )  const [inline]

Returns true if a solution path has been found (could be approximate).

Definition at line 144 of file Goal.h.

bool ompl::base::Goal::isApproximate ( void   )  const [inline]

Return true if the found solution is approximate (does not actually reach the desired goal, but hopefully is closer to it).

Definition at line 204 of file Goal.h.

bool ompl::base::Goal::isSatisfied ( const State st,
double  pathLength,
double *  distance 
) const

Return true if the state satisfies the goal constraints and the path length is less than the desired maximum length. This call also computes the distance between the state given as argument and the goal.

Parameters:
st the state to check for validity
pathLength the length of the path that leads to st
distance location at which distance to goal will be stored
virtual bool ompl::base::Goal::isSatisfied ( const State st,
double *  distance 
) const [virtual]

Return true if the state satisfies the goal constraints and compute the distance between the state given as argument and the goal (even if the goal is not satisfied). This distance can be an approximation. It can even be set to a constant, if such a computation is not possible.

Parameters:
st the state to check for validity
distance location at which distance to goal will be stored
Note:
The default implementation sets the distance to a constant.
If this function returns true, isStartGoalPairValid() need not be called.

Reimplemented in ompl::base::GoalRegion.

virtual bool ompl::base::Goal::isSatisfied ( const State st  )  const [pure virtual]

Return true if the state satisfies the goal constraints.

Implemented in ompl::base::GoalRegion.

virtual bool ompl::base::Goal::isStartGoalPairValid ( const State ,
const State  
) const [inline, virtual]

Since there can be multiple starting states (and multiple goal states) it is possible certain pairs are not to be allowed. By default we however assume all such pairs are allowed. Note: if this function returns true, isSatisfied() need not be called.

Definition at line 138 of file Goal.h.

virtual void ompl::base::Goal::print ( std::ostream &  out = std::cout  )  const [inline, virtual]

Print information about the goal.

Reimplemented in ompl::base::GoalRegion, ompl::base::GoalState, and ompl::base::GoalStates.

Definition at line 210 of file Goal.h.

void ompl::base::Goal::setDifference ( double  difference  )  [inline]

Set the difference between the found solution path and the desired solution path.

Definition at line 196 of file Goal.h.

void ompl::base::Goal::setMaximumPathLength ( double  maximumPathLength  )  [inline]

Set the maximum length allowed for a solution path. This value is checked only in the version of isSatisfied() that takes the path length as argument.

Definition at line 159 of file Goal.h.

void ompl::base::Goal::setSolutionPath ( const PathPtr path,
bool  approximate = false 
) [inline]

Update the solution path. If a previous solution path exists, it is deleted.

Definition at line 174 of file Goal.h.


Member Data Documentation

True if goal was not achieved, but an approximate solution was found.

Definition at line 233 of file Goal.h.

double ompl::base::Goal::difference_ [protected]

The achieved difference between the found solution and the desired goal.

Definition at line 230 of file Goal.h.

The maximum length allowed for the solution path.

Definition at line 224 of file Goal.h.

Solution path, if found.

Definition at line 227 of file Goal.h.

The space information for this goal.

Definition at line 221 of file Goal.h.

Goal type.

Definition at line 218 of file Goal.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 11:37:46 2013