ompl::geometric::LightningRetrieveRepair Class Reference

The Lightning Framework's Retrieve-Repair component. More...

#include <ompl/geometric/planners/experience/LightningRetrieveRepair.h>

Inheritance diagram for ompl::geometric::LightningRetrieveRepair:

Public Member Functions

 LightningRetrieveRepair (const base::SpaceInformationPtr &si, tools::LightningDBPtr experienceDB)
 Constructor.
 
void getPlannerData (base::PlannerData &data) const override
 Get information about the exploration data structure the planning from scratch motion planner used.
 
const std::vector< base::PlannerDataPtr > & getLastRecalledNearestPaths () const
 Get debug information about the top recalled paths that were chosen for further filtering. More...
 
std::size_t getLastRecalledNearestPathChosen () const
 Get debug information about the top recalled paths that were chosen for further filtering. More...
 
base::PlannerDataPtr getChosenRecallPath () const
 Get the chosen path used from database for repair. More...
 
void getRepairPlannerDatas (std::vector< base::PlannerDataPtr > &data) const
 Get information about the exploration data structure the repair motion planner used each call.
 
base::PlannerStatus solve (const base::PlannerTerminationCondition &ptc) override
 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 for 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). If clearQuery() is called, the planner may retain prior datastructures generated from a previous query on a new problem definition. The function terminates if the call to ptc returns true.
 
void clear () override
 Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() will ignore all previous work.
 
void setLightningDB (const tools::LightningDBPtr &experienceDB)
 Pass a pointer of the database from the lightning framework.
 
void setRepairPlanner (const base::PlannerPtr &planner)
 Set the planner that will be used for repairing invalid paths recalled from experience.
 
void setup () override
 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.
 
bool repairPath (const base::PlannerTerminationCondition &ptc, geometric::PathGeometric &primaryPath)
 Repairs a path to be valid in the current planning environment. More...
 
bool replan (const base::State *start, const base::State *goal, geometric::PathGeometric &newPathSegment, const base::PlannerTerminationCondition &ptc)
 Use our secondary planner to find a valid path between start and goal, and return that path. More...
 
int getNumNearestSolutions () const
 Getter for number of 'k' close solutions to choose from database for further filtering.
 
void setNumNearestSolutions (int nearestK)
 Setter for number of 'k' close solutions to choose from database for further filtering.
 
- Public Member Functions inherited from ompl::base::Planner
 Planner (const Planner &)=delete
 
Planneroperator= (const Planner &)=delete
 
 Planner (SpaceInformationPtr si, std::string name)
 Constructor.
 
virtual ~Planner ()=default
 Destructor.
 
template<class T >
T * as ()
 Cast this instance to a desired type. More...
 
template<class T >
const T * as () const
 Cast this instance to a desired type. More...
 
const SpaceInformationPtrgetSpaceInformation () const
 Get the space information this planner is using.
 
const ProblemDefinitionPtrgetProblemDefinition () const
 Get the problem definition the planner is trying to solve.
 
ProblemDefinitionPtrgetProblemDefinition ()
 Get the problem definition the planner is trying to solve.
 
const PlannerInputStatesgetPlannerInputStates () const
 Get the planner input states.
 
virtual void setProblemDefinition (const ProblemDefinitionPtr &pdef)
 Set the problem definition for the planner. The problem needs to be set before calling solve(). Note: If this problem definition replaces a previous one, it may also be necessary to call clear() or clearQuery().
 
PlannerStatus solve (const PlannerTerminationConditionFn &ptc, double checkInterval)
 Same as above except the termination condition is only evaluated at a specified interval.
 
PlannerStatus solve (double solveTime)
 Same as above except the termination condition is solely a time limit: the number of seconds the algorithm is allowed to spend planning.
 
virtual void clearQuery ()
 Clears internal datastructures of any query-specific information from the previous query. Planner settings are not affected. The planner, if able, should retain all datastructures generated from previous queries that can be used to help solve the next query. Note that clear() should also clear all query-specific information along with all other datastructures in the planner. By default clearQuery() calls clear().
 
const std::string & getName () const
 Get the name of the planner.
 
void setName (const std::string &name)
 Set the name of the planner.
 
const PlannerSpecsgetSpecs () const
 Return the specifications (capabilities of this planner)
 
virtual void checkValidity ()
 Check to see if the planner is in a working state (setup has been called, a goal was set, the input states seem to be in order). In case of error, this function throws an exception.
 
bool isSetup () const
 Check if setup() was called for this planner.
 
ParamSetparams ()
 Get the parameters for this planner.
 
const ParamSetparams () const
 Get the parameters for this planner.
 
const PlannerProgressPropertiesgetPlannerProgressProperties () const
 Retrieve a planner's planner progress property map.
 
virtual void printProperties (std::ostream &out) const
 Print properties of the motion planner.
 
virtual void printSettings (std::ostream &out) const
 Print information about the motion planner's settings.
 

Protected Member Functions

std::size_t checkMotionScore (const base::State *s1, const base::State *s2) const
 Count the number of states along the discretized path that are in collision Note: This is kind of an ill-defined score though. It depends on the resolution of collision checking. I am more inclined to try to compute the percent of the length of the motion that is valid. That could go in SpaceInformation, as a utility function.
 
bool findBestPath (const base::State *startState, const base::State *goalState, base::PlannerDataPtr &chosenPath)
 Filters the top n paths in nearestPaths_ to the top 1, based on state validity with current environment. More...
 
- Protected Member Functions inherited from ompl::base::Planner
template<typename T , typename PlannerType , typename SetterType , typename GetterType >
void declareParam (const std::string &name, const PlannerType &planner, const SetterType &setter, const GetterType &getter, const std::string &rangeSuggestion="")
 This function declares a parameter for this planner instance, and specifies the setter and getter functions.
 
template<typename T , typename PlannerType , typename SetterType >
void declareParam (const std::string &name, const PlannerType &planner, const SetterType &setter, const std::string &rangeSuggestion="")
 This function declares a parameter for this planner instance, and specifies the setter function.
 
void addPlannerProgressProperty (const std::string &progressPropertyName, const PlannerProgressProperty &prop)
 Add a planner progress property called progressPropertyName with a property querying function prop to this planner's progress property map.
 

Protected Attributes

tools::LightningDBPtr experienceDB_
 The database of motions to search through.
 
std::vector< base::PlannerDataPtr > nearestPaths_
 Recall the nearest paths and store this in planner data for introspection later.
 
std::size_t nearestPathsChosenID_
 the ID within nearestPaths_ of the path that was chosen for repair
 
base::PlannerPtr repairPlanner_
 A secondary planner for replanning.
 
base::ProblemDefinitionPtr repairProblemDef_
 A secondary problem definition for the repair planner to use.
 
std::vector< base::PlannerDataPtr > repairPlannerDatas_
 Debug the repair planner by saving its planner data each time it is used.
 
geometric::PathSimplifierPtr psk_
 The instance of the path simplifier.
 
int nearestK_
 Number of 'k' close solutions to choose from database for further filtering.
 
- Protected Attributes inherited from ompl::base::Planner
SpaceInformationPtr si_
 The space information for which planning is done.
 
ProblemDefinitionPtr pdef_
 The user set problem definition.
 
PlannerInputStates pis_
 Utility class to extract valid input states

 
std::string name_
 The name of this planner.
 
PlannerSpecs specs_
 The specifications of the planner (its capabilities)
 
ParamSet params_
 A map from parameter names to parameter instances for this planner. This field is populated by the declareParam() function.
 
PlannerProgressProperties plannerProgressProperties_
 A mapping between this planner's progress property names and the functions used for querying those progress properties.
 
bool setup_
 Flag indicating whether setup() has been called.
 

Additional Inherited Members

- Public Types inherited from ompl::base::Planner
using PlannerProgressProperty = std::function< std::string()>
 Definition of a function which returns a property about the planner's progress that can be queried by a benchmarking routine.
 
using PlannerProgressProperties = std::map< std::string, PlannerProgressProperty >
 A dictionary which maps the name of a progress property to the function to be used for querying that property.
 

Detailed Description

The Lightning Framework's Retrieve-Repair component.

- Lightning Retrieve and Repair

Short description
LightningRetrieveRepair is an experienced-based motion planner that recalls from a database of previous actions the most similar one to the current planning problem and attempts to repair it.
External documentation
Berenson, Dmitry, Pieter Abbeel, and Ken Goldberg: A robot path planning framework that learns from experience, in IEEE Intl. Conf. Robotics and Automation (ICRA), 2012. [PDF]

Definition at line 108 of file LightningRetrieveRepair.h.

Member Function Documentation

◆ findBestPath()

bool ompl::geometric::LightningRetrieveRepair::findBestPath ( const base::State startState,
const base::State goalState,
base::PlannerDataPtr &  chosenPath 
)
protected

Filters the top n paths in nearestPaths_ to the top 1, based on state validity with current environment.

Returns
true if no error

Definition at line 198 of file LightningRetrieveRepair.cpp.

◆ getChosenRecallPath()

ompl::base::PlannerDataPtr ompl::geometric::LightningRetrieveRepair::getChosenRecallPath ( ) const

Get the chosen path used from database for repair.

Returns
PlannerData of chosen path

Definition at line 572 of file LightningRetrieveRepair.cpp.

◆ getLastRecalledNearestPathChosen()

std::size_t ompl::geometric::LightningRetrieveRepair::getLastRecalledNearestPathChosen ( ) const

Get debug information about the top recalled paths that were chosen for further filtering.

Returns
chosenID - the index of the PlannerData object that was chosen for repair

Definition at line 567 of file LightningRetrieveRepair.cpp.

◆ getLastRecalledNearestPaths()

const std::vector< ompl::base::PlannerDataPtr > & ompl::geometric::LightningRetrieveRepair::getLastRecalledNearestPaths ( ) const

Get debug information about the top recalled paths that were chosen for further filtering.

Returns
data - vector of PlannerData objects that each hold a single path

Definition at line 562 of file LightningRetrieveRepair.cpp.

◆ repairPath()

bool ompl::geometric::LightningRetrieveRepair::repairPath ( const base::PlannerTerminationCondition ptc,
geometric::PathGeometric primaryPath 
)

Repairs a path to be valid in the current planning environment.

Parameters
path- old from experience
ptc- when to stop attempting repair
Returns
true if no error

Definition at line 352 of file LightningRetrieveRepair.cpp.

◆ replan()

bool ompl::geometric::LightningRetrieveRepair::replan ( const base::State start,
const base::State goal,
geometric::PathGeometric newPathSegment,
const base::PlannerTerminationCondition ptc 
)

Use our secondary planner to find a valid path between start and goal, and return that path.

Parameters
start
goal
newPathSegment- the solution
Returns
true if path found

Definition at line 472 of file LightningRetrieveRepair.cpp.


The documentation for this class was generated from the following files: