Class LightningRetrieveRepair
Defined in File LightningRetrieveRepair.h
Inheritance Relationships
Base Type
public ompl::base::Planner
(Class Planner)
Class Documentation
-
class LightningRetrieveRepair : public ompl::base::Planner
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]
Public Functions
-
LightningRetrieveRepair(const base::SpaceInformationPtr &si, tools::LightningDBPtr experienceDB)
Constructor.
-
~LightningRetrieveRepair() override
-
virtual 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.
- Returns:
data - vector of PlannerData objects that each hold a single path
-
std::size_t 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
-
base::PlannerDataPtr getChosenRecallPath() const
Get the chosen path used from database for repair.
- Returns:
PlannerData of chosen path
-
void getRepairPlannerDatas(std::vector<base::PlannerDataPtr> &data) const
Get information about the exploration data structure the repair motion planner used each call.
-
virtual 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.
-
virtual 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.
-
virtual 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.
- Parameters:
path – - old from experience
ptc – - when to stop attempting repair
- Returns:
true if no error
-
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.
- Parameters:
start –
goal –
newPathSegment – - the solution
- Returns:
true if path found
-
inline int getNumNearestSolutions() const
Getter for number of ‘k’ close solutions to choose from database for further filtering.
-
inline void setNumNearestSolutions(int nearestK)
Setter for number of ‘k’ close solutions to choose from database for further filtering.
Protected 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.
- Returns:
true if no error
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.