Class SelfConfig

Class Documentation

class SelfConfig

This class contains methods that automatically configure various parameters for motion planning. If expensive computation is performed, the results are cached.

Public Functions

SelfConfig(const base::SpaceInformationPtr &si, const std::string &context = std::string())

Construct an instance that can configure the space encapsulated by si. Any information printed to the console is prefixed by context.

~SelfConfig()
double getProbabilityOfValidState()

Get the probability of a sampled state being valid (calls base::SpaceInformation::probabilityOfValidState())

double getAverageValidMotionLength()

Get the probability of a sampled state being valid (calls base::SpaceInformation::averageValidMotionLength())

void configureValidStateSamplingAttempts(unsigned int &attempts)

Instances of base::ValidStateSampler need a number of attempts to be specified — the maximum number of times a new sample is selected and checked to be valid. This function computes a number of attempts such that the probability of obtaining a valid sample is 90%.

void configurePlannerRange(double &range)

Compute what a good length for motion segments is.

void configureProjectionEvaluator(base::ProjectionEvaluatorPtr &proj)

If proj is undefined, it is set to the default projection reported by base::StateSpace::getDefaultProjection(). If no default projection is available either, an exception is thrown.

void print(std::ostream &out = std::cout) const

Print the computed configuration parameters.

Public Static Functions

template<typename _T>
static inline NearestNeighbors<_T> *getDefaultNearestNeighbors(const base::Planner *planner)

Select a default nearest neighbor datastructure for the given space.

The default depends on the planning algorithm and the space the planner operates in:

static base::PlannerPtr getDefaultPlanner(const base::GoalPtr &goal)

Given a goal specification, decide on a planner for that goal.