This class contains methods that automatically configure various parameters for motion planning. If expensive computation is performed, the results are cached. More...
#include <SelfConfig.h>
Public Member Functions | |
| 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 | 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%. | |
| double | getAverageValidMotionLength (void) |
| Get the probability of a sampled state being valid (calls base::SpaceInformation::averageValidMotionLength()). | |
| double | getProbabilityOfValidState (void) |
| Get the probability of a sampled state being valid (calls base::SpaceInformation::probabilityOfValidState()). | |
| void | print (std::ostream &out=std::cout) const |
| Print the computed configuration parameters. | |
| 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. | |
This class contains methods that automatically configure various parameters for motion planning. If expensive computation is performed, the results are cached.
Definition at line 51 of file SelfConfig.h.
| ompl::SelfConfig::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.
| void ompl::SelfConfig::configurePlannerRange | ( | double & | range | ) |
Compute what a good length for motion segments is.
| void ompl::SelfConfig::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 ompl::SelfConfig::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%.
| double ompl::SelfConfig::getAverageValidMotionLength | ( | void | ) |
Get the probability of a sampled state being valid (calls base::SpaceInformation::averageValidMotionLength()).
| double ompl::SelfConfig::getProbabilityOfValidState | ( | void | ) |
Get the probability of a sampled state being valid (calls base::SpaceInformation::probabilityOfValidState()).
| void ompl::SelfConfig::print | ( | std::ostream & | out = std::cout |
) | const |
Print the computed configuration parameters.