Kinodynamic Planning by Interior-Exterior Cell Exploration. More...
#include <KPIECE1.h>
Classes | |
struct | CellData |
The data held by a cell in the grid of motions. More... | |
class | Motion |
Representation of a motion for this algorithm. More... | |
struct | OrderCellsByImportance |
Definintion of an operator passed to the Grid structure, to order cells by importance. More... | |
struct | TreeData |
The data defining a tree of motions for this algorithm. More... | |
Public Member Functions | |
virtual void | clear (void) |
Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() will ignore all previous work. | |
double | getBadCellScoreFactor (void) const |
Get the factor that is multiplied to a cell's score if extending a motion from that cell failed. | |
double | getBorderFraction (void) const |
Get the fraction of time to focus exploration on boundary. | |
double | getGoalBias (void) const |
double | getGoodCellScoreFactor (void) const |
Get the factor that is multiplied to a cell's score if extending a motion from that cell succeeded. | |
virtual void | getPlannerData (base::PlannerData &data) const |
Get information about the current run of the motion planner. Repeated calls to this function will update data (only additions are made). This is useful to see what changed in the exploration datastructure, between calls to solve(), for example (without calling clear() in between). | |
const base::ProjectionEvaluatorPtr & | getProjectionEvaluator (void) const |
Get the projection evaluator. | |
KPIECE1 (const SpaceInformationPtr &si) | |
Constructor. | |
void | setBorderFraction (double bp) |
Set the fraction of time for focusing on the border (between 0 and 1). This is the minimum fraction used to select cells that are exterior (minimum because if 95% of cells are on the border, they will be selected with 95% chance, even if this fraction is set to 90%). | |
void | setCellScoreFactor (double good, double bad) |
When extending a motion from a cell, the extension can be successful or it can fail. If the extension is successful, the score of the cell is multiplied by good. If the extension fails, the score of the cell is multiplied by bad. These numbers should be in the range (0, 1]. | |
void | setGoalBias (double goalBias) |
void | setProjectionEvaluator (const std::string &name) |
Set the projection evaluator (select one from the ones registered with the state space). | |
void | setProjectionEvaluator (const base::ProjectionEvaluatorPtr &projectionEvaluator) |
Set the projection evaluator. This class is able to compute the projection of a given state. | |
virtual void | setup (void) |
Perform extra configuration steps, if needed. This call will also issue a call to ompl::base::SpaceInformation::setup() if needed. This must be called before solving. | |
virtual bool | solve (const base::PlannerTerminationCondition &ptc) |
Function that can solve the motion planning problem. This function can be called multiple times on the same problem, without calling clear() in between. This allows the planner to continue work more time on an unsolved problem, for example. If this option is used, it is assumed the problem definition is not changed (unpredictable results otherwise). The only change in the problem definition that is accounted for is the addition of starting or goal states (but not changing previously added start/goal states). The function terminates if the call to ptc returns true. | |
virtual | ~KPIECE1 (void) |
Protected Types | |
typedef GridB< CellData *, OrderCellsByImportance > | Grid |
The datatype for the maintained grid datastructure. | |
Protected Member Functions | |
unsigned int | addMotion (Motion *motion, double dist) |
Add a motion to the grid containing motions. As a hint, dist specifies the distance to the goal from the state of the motion being added. The function Returns the number of cells created to accommodate the new motion (0 or 1). | |
unsigned int | findNextMotion (const std::vector< Grid::Coord > &coords, unsigned int index, unsigned int count) |
When generated motions are to be added to the tree of motions, they often need to be split, so they don't cross cell boundaries. Given that a motion starts out in the cell origin and it crosses the cells in coords[index] through coords[last] (inclusively), return the index of the state to be used in the next part of the motion (that is within a cell). This will be a value between index and last. | |
void | freeCellData (CellData *cdata) |
Free the memory for the data contained in a grid cell. | |
void | freeGridMotions (Grid &grid) |
Free the memory for the motions contained in a grid. | |
void | freeMemory (void) |
Free all the memory allocated by this planner. | |
void | freeMotion (Motion *motion) |
Free the memory for a motion. | |
bool | selectMotion (Motion *&smotion, Grid::Cell *&scell) |
Select a motion and the cell it is part of from the grid of motions. This is where preference is given to cells on the boundary of the grid. | |
Static Protected Member Functions | |
static void | computeImportance (Grid::Cell *cell, void *) |
This function is provided as a calback to the grid datastructure to update the importance of a cell. | |
Protected Attributes | |
double | badScoreFactor_ |
When extending a motion from a cell, the extension can fail. If it is, the score of the cell is multiplied by this factor. | |
ControlSamplerPtr | controlSampler_ |
A control sampler. | |
double | goalBias_ |
The fraction of time the goal is picked as the state to expand towards (if such a state is available). | |
double | goodScoreFactor_ |
When extending a motion from a cell, the extension can be successful. If it is, the score of the cell is multiplied by this factor. | |
base::ProjectionEvaluatorPtr | projectionEvaluator_ |
This algorithm uses a discretization (a grid) to guide the exploration. The exploration is imposed on a projection of the state space. | |
RNG | rng_ |
The random number generator. | |
double | selectBorderFraction_ |
The fraction of time to focus exploration on the border of the grid. | |
const SpaceInformation * | siC_ |
The base::SpaceInformation cast as control::SpaceInformation, for convenience. | |
TreeData | tree_ |
The tree datastructure. |
Kinodynamic Planning by Interior-Exterior Cell Exploration.
Definition at line 72 of file control/planners/kpiece/KPIECE1.h.
typedef GridB<CellData*, OrderCellsByImportance> ompl::control::KPIECE1::Grid [protected] |
The datatype for the maintained grid datastructure.
Definition at line 234 of file control/planners/kpiece/KPIECE1.h.
ompl::control::KPIECE1::KPIECE1 | ( | const SpaceInformationPtr & | si | ) | [inline] |
Constructor.
Definition at line 47 of file control/planners/kpiece/KPIECE1.h.
virtual ompl::control::KPIECE1::~KPIECE1 | ( | void | ) | [inline, virtual] |
Definition at line 59 of file control/planners/kpiece/KPIECE1.h.
unsigned int ompl::control::KPIECE1::addMotion | ( | Motion * | motion, | |
double | dist | |||
) | [protected] |
Add a motion to the grid containing motions. As a hint, dist specifies the distance to the goal from the state of the motion being added. The function Returns the number of cells created to accommodate the new motion (0 or 1).
virtual void ompl::control::KPIECE1::clear | ( | void | ) | [virtual] |
Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() will ignore all previous work.
Reimplemented from ompl::base::Planner.
static void ompl::control::KPIECE1::computeImportance | ( | Grid::Cell * | cell, | |
void * | ||||
) | [inline, static, protected] |
This function is provided as a calback to the grid datastructure to update the importance of a cell.
Definition at line 258 of file control/planners/kpiece/KPIECE1.h.
unsigned int ompl::control::KPIECE1::findNextMotion | ( | const std::vector< Grid::Coord > & | coords, | |
unsigned int | index, | |||
unsigned int | count | |||
) | [protected] |
When generated motions are to be added to the tree of motions, they often need to be split, so they don't cross cell boundaries. Given that a motion starts out in the cell origin and it crosses the cells in coords[index] through coords[last] (inclusively), return the index of the state to be used in the next part of the motion (that is within a cell). This will be a value between index and last.
void ompl::control::KPIECE1::freeCellData | ( | CellData * | cdata | ) | [protected] |
Free the memory for the data contained in a grid cell.
void ompl::control::KPIECE1::freeGridMotions | ( | Grid & | grid | ) | [protected] |
Free the memory for the motions contained in a grid.
void ompl::control::KPIECE1::freeMemory | ( | void | ) | [protected] |
Free all the memory allocated by this planner.
void ompl::control::KPIECE1::freeMotion | ( | Motion * | motion | ) | [protected] |
Free the memory for a motion.
double ompl::control::KPIECE1::getBadCellScoreFactor | ( | void | ) | const [inline] |
Get the factor that is multiplied to a cell's score if extending a motion from that cell failed.
Definition at line 126 of file control/planners/kpiece/KPIECE1.h.
double ompl::control::KPIECE1::getBorderFraction | ( | void | ) | const [inline] |
Get the fraction of time to focus exploration on boundary.
Definition at line 99 of file control/planners/kpiece/KPIECE1.h.
double ompl::control::KPIECE1::getGoalBias | ( | void | ) | const [inline] |
Get the goal bias the planner is using
Definition at line 81 of file control/planners/kpiece/KPIECE1.h.
double ompl::control::KPIECE1::getGoodCellScoreFactor | ( | void | ) | const [inline] |
Get the factor that is multiplied to a cell's score if extending a motion from that cell succeeded.
Definition at line 119 of file control/planners/kpiece/KPIECE1.h.
virtual void ompl::control::KPIECE1::getPlannerData | ( | base::PlannerData & | data | ) | const [virtual] |
Get information about the current run of the motion planner. Repeated calls to this function will update data (only additions are made). This is useful to see what changed in the exploration datastructure, between calls to solve(), for example (without calling clear() in between).
Reimplemented from ompl::base::Planner.
const base::ProjectionEvaluatorPtr& ompl::control::KPIECE1::getProjectionEvaluator | ( | void | ) | const [inline] |
Get the projection evaluator.
Definition at line 146 of file control/planners/kpiece/KPIECE1.h.
bool ompl::control::KPIECE1::selectMotion | ( | Motion *& | smotion, | |
Grid::Cell *& | scell | |||
) | [protected] |
Select a motion and the cell it is part of from the grid of motions. This is where preference is given to cells on the boundary of the grid.
void ompl::control::KPIECE1::setBorderFraction | ( | double | bp | ) | [inline] |
Set the fraction of time for focusing on the border (between 0 and 1). This is the minimum fraction used to select cells that are exterior (minimum because if 95% of cells are on the border, they will be selected with 95% chance, even if this fraction is set to 90%).
Definition at line 92 of file control/planners/kpiece/KPIECE1.h.
void ompl::control::KPIECE1::setCellScoreFactor | ( | double | good, | |
double | bad | |||
) | [inline] |
When extending a motion from a cell, the extension can be successful or it can fail. If the extension is successful, the score of the cell is multiplied by good. If the extension fails, the score of the cell is multiplied by bad. These numbers should be in the range (0, 1].
Definition at line 111 of file control/planners/kpiece/KPIECE1.h.
void ompl::control::KPIECE1::setGoalBias | ( | double | goalBias | ) | [inline] |
In the process of randomly selecting states in the state space to attempt to go towards, the algorithm may in fact choose the actual goal state, if it knows it, with some probability. This probability is a real number between 0.0 and 1.0; its value should usually be around 0.05 and should not be too large. It is probably a good idea to use the default value.
Definition at line 75 of file control/planners/kpiece/KPIECE1.h.
void ompl::control::KPIECE1::setProjectionEvaluator | ( | const std::string & | name | ) | [inline] |
Set the projection evaluator (select one from the ones registered with the state space).
Definition at line 140 of file control/planners/kpiece/KPIECE1.h.
void ompl::control::KPIECE1::setProjectionEvaluator | ( | const base::ProjectionEvaluatorPtr & | projectionEvaluator | ) | [inline] |
Set the projection evaluator. This class is able to compute the projection of a given state.
Definition at line 133 of file control/planners/kpiece/KPIECE1.h.
virtual void ompl::control::KPIECE1::setup | ( | void | ) | [virtual] |
Perform extra configuration steps, if needed. This call will also issue a call to ompl::base::SpaceInformation::setup() if needed. This must be called before solving.
Reimplemented from ompl::base::Planner.
virtual bool ompl::control::KPIECE1::solve | ( | const base::PlannerTerminationCondition & | ptc | ) | [virtual] |
Function that can solve the motion planning problem. This function can be called multiple times on the same problem, without calling clear() in between. This allows the planner to continue work more time on an unsolved problem, for example. If this option is used, it is assumed the problem definition is not changed (unpredictable results otherwise). The only change in the problem definition that is accounted for is the addition of starting or goal states (but not changing previously added start/goal states). The function terminates if the call to ptc returns true.
Implements ompl::base::Planner.
double ompl::control::KPIECE1::badScoreFactor_ [protected] |
When extending a motion from a cell, the extension can fail. If it is, the score of the cell is multiplied by this factor.
Definition at line 315 of file control/planners/kpiece/KPIECE1.h.
A control sampler.
Definition at line 294 of file control/planners/kpiece/KPIECE1.h.
double ompl::control::KPIECE1::goalBias_ [protected] |
The fraction of time the goal is picked as the state to expand towards (if such a state is available).
Definition at line 323 of file control/planners/kpiece/KPIECE1.h.
double ompl::control::KPIECE1::goodScoreFactor_ [protected] |
When extending a motion from a cell, the extension can be successful. If it is, the score of the cell is multiplied by this factor.
Definition at line 310 of file control/planners/kpiece/KPIECE1.h.
This algorithm uses a discretization (a grid) to guide the exploration. The exploration is imposed on a projection of the state space.
Definition at line 305 of file control/planners/kpiece/KPIECE1.h.
RNG ompl::control::KPIECE1::rng_ [protected] |
The random number generator.
Definition at line 326 of file control/planners/kpiece/KPIECE1.h.
double ompl::control::KPIECE1::selectBorderFraction_ [protected] |
The fraction of time to focus exploration on the border of the grid.
Definition at line 320 of file control/planners/kpiece/KPIECE1.h.
const SpaceInformation* ompl::control::KPIECE1::siC_ [protected] |
The base::SpaceInformation cast as control::SpaceInformation, for convenience.
Definition at line 300 of file control/planners/kpiece/KPIECE1.h.
TreeData ompl::control::KPIECE1::tree_ [protected] |
The tree datastructure.
Definition at line 297 of file control/planners/kpiece/KPIECE1.h.