ompl::tools::ExperienceSetup Class Referenceabstract
Create the set of classes typically needed to solve a geometric problem. More...
#include <ompl/tools/experience/ExperienceSetup.h>
Inheritance diagram for ompl::tools::ExperienceSetup:

Classes | |
| struct | ExperienceLog |
| Single entry for the csv data logging file. More... | |
| struct | ExperienceStats |
| Simple logging functionality encapsled in a struct. More... | |
Public Member Functions | |
| ExperienceSetup (const base::SpaceInformationPtr &si) | |
| Constructor needs the state space used for planning. | |
| ExperienceSetup (const base::StateSpacePtr &space) | |
| Constructor needs the state space used for planning. | |
| void | logInitialize () |
| Load the header (first row) of the csv file. | |
| void | convertLogToString (const ExperienceLog &log) |
| Move data to string format and put in buffer. | |
| virtual void | printResultsInfo (std::ostream &out=std::cout) const =0 |
| Display debug data about potential available solutions. | |
| virtual void | printLogs (std::ostream &out=std::cout) const =0 |
| Display debug data about overall results since being loaded. | |
| virtual void | saveDataLog (std::ostream &out=std::cout) |
| Save debug data about overall results since being loaded. | |
| virtual void | setRepairPlanner (const base::PlannerPtr &planner)=0 |
| Set the planner to use for repairing experience paths inside the RetrieveRepair planner. If the planner is not set, a default planner is set. | |
| virtual bool | save ()=0 |
| Save the experience database to file. | |
| virtual bool | saveIfChanged ()=0 |
| Save the experience database to file if there has been a change. | |
| void | enablePlanningFromRecall (bool enable) |
| Optionally disable the ability to use previous plans in solutions (but will still save them) | |
| void | enablePlanningFromScratch (bool enable) |
| Optionally disable the ability to plan from scratch Note: Lightning can still save modified experiences if they are different enough. | |
| virtual void | getAllPlannerDatas (std::vector< ompl::base::PlannerDataPtr > &plannerDatas) const =0 |
| Get a vector of all the planning data in the database. | |
| virtual std::size_t | getExperiencesCount () const =0 |
| Get the total number of paths stored in the database. | |
| virtual const std::string & | getFilePath () const |
| After setFile() is called, access the generated file path for loading and saving the experience database. | |
| virtual bool | setFilePath (const std::string &filePath) |
| Set the database file to load. Actual loading occurs when setup() is called. More... | |
| const ExperienceStats & | getStats () const |
| Getter for logging data. | |
| virtual bool | doPostProcessing () |
| Allow accumlated experiences to be processed. | |
Public Member Functions inherited from ompl::geometric::SimpleSetup | |
| SimpleSetup (const base::SpaceInformationPtr &si) | |
| Constructor needs the state space used for planning. | |
| SimpleSetup (const base::StateSpacePtr &space) | |
| Constructor needs the state space used for planning. | |
| const base::SpaceInformationPtr & | getSpaceInformation () const |
| Get the current instance of the space information. | |
| const base::ProblemDefinitionPtr & | getProblemDefinition () const |
| Get the current instance of the problem definition. | |
| base::ProblemDefinitionPtr & | getProblemDefinition () |
| Get the current instance of the problem definition. | |
| const base::StateSpacePtr & | getStateSpace () const |
| Get the current instance of the state space. | |
| const base::StateValidityCheckerPtr & | getStateValidityChecker () const |
| Get the current instance of the state validity checker. | |
| const base::GoalPtr & | getGoal () const |
| Get the current goal definition. | |
| const base::PlannerPtr & | getPlanner () const |
| Get the current planner. | |
| const base::PlannerAllocator & | getPlannerAllocator () const |
| Get the planner allocator. | |
| const PathSimplifierPtr & | getPathSimplifier () const |
| Get the path simplifier. | |
| PathSimplifierPtr & | getPathSimplifier () |
| Get the path simplifier. | |
| const base::OptimizationObjectivePtr & | getOptimizationObjective () const |
| Get the optimization objective to use. | |
| bool | haveExactSolutionPath () const |
| Return true if a solution path is available (previous call to solve() was successful) and the solution is exact (not approximate) | |
| bool | haveSolutionPath () const |
| Return true if a solution path is available (previous call to solve() was successful). The solution may be approximate. | |
| const std::string | getSolutionPlannerName () const |
| Get the best solution's planer name. Throw an exception if no solution is available. | |
| PathGeometric & | getSolutionPath () const |
| Get the solution path. Throw an exception if no solution is available. | |
| void | getPlannerData (base::PlannerData &pd) const |
| Get information about the exploration data structure the motion planner used. | |
| void | setStateValidityChecker (const base::StateValidityCheckerPtr &svc) |
| Set the state validity checker to use. | |
| void | setStateValidityChecker (const base::StateValidityCheckerFn &svc) |
| Set the state validity checker to use. | |
| void | setOptimizationObjective (const base::OptimizationObjectivePtr &optimizationObjective) |
| Set the optimization objective to use. | |
| void | setStartAndGoalStates (const base::ScopedState<> &start, const base::ScopedState<> &goal, double threshold=std::numeric_limits< double >::epsilon()) |
| Set the start and goal states to use. | |
| void | addStartState (const base::ScopedState<> &state) |
| Add a starting state for planning. This call is not needed if setStartAndGoalStates() has been called. | |
| void | clearStartStates () |
| Clear the currently set starting states. | |
| void | setStartState (const base::ScopedState<> &state) |
| Clear the currently set starting states and add state as the starting state. | |
| void | setGoalState (const base::ScopedState<> &goal, double threshold=std::numeric_limits< double >::epsilon()) |
| A simple form of setGoal(). The goal will be an instance of ompl::base::GoalState. | |
| void | setGoal (const base::GoalPtr &goal) |
| Set the goal for planning. This call is not needed if setStartAndGoalStates() has been called. | |
| void | setPlanner (const base::PlannerPtr &planner) |
| Set the planner to use. If the planner is not set, an attempt is made to use the planner allocator. If no planner allocator is available either, a default planner is set. | |
| void | setPlannerAllocator (const base::PlannerAllocator &pa) |
| Set the planner allocator to use. This is only used if no planner has been set. This is optional – a default planner will be used if no planner is otherwise specified. | |
| virtual base::PlannerStatus | solve (double time=1.0) |
| Run the planner for up to a specified amount of time (default is 1 second) | |
| virtual base::PlannerStatus | solve (const base::PlannerTerminationCondition &ptc) |
| Run the planner until ptc becomes true (at most) | |
| base::PlannerStatus | getLastPlannerStatus () const |
| Return the status of the last planning attempt. | |
| double | getLastPlanComputationTime () const |
| Get the amount of time (in seconds) spent during the last planning step. | |
| double | getLastSimplificationTime () const |
| Get the amount of time (in seconds) spend during the last path simplification step. | |
| void | simplifySolution (double duration=0.0) |
| Attempt to simplify the current solution path. Spent at most duration seconds in the simplification process. If duration is 0 (the default), a default simplification procedure is executed. | |
| void | simplifySolution (const base::PlannerTerminationCondition &ptc) |
| Attempt to simplify the current solution path. Stop computation when ptc becomes true at the latest. | |
| virtual void | clear () |
| Clear all planning data. This only includes data generated by motion plan computation. Planner settings, start & goal states are not affected. | |
| virtual void | print (std::ostream &out=std::cout) const |
| Print information about the current setup. | |
| virtual void | setup () |
| This method will create the necessary classes for planning. The solve() method will call this function automatically. | |
Protected Attributes | |
| bool | recallEnabled_ {true} |
| Flag indicating whether recalled plans should be used to find solutions. Enabled by default. | |
| bool | scratchEnabled_ {true} |
| Flag indicating whether planning from scratch should be used to find solutions. Enabled by default. | |
| std::string | filePath_ |
| File location of database. | |
| std::stringstream | csvDataLogStream_ |
| ExperienceStats | stats_ |
| States data for display to console | |
Protected Attributes inherited from ompl::geometric::SimpleSetup | |
| base::SpaceInformationPtr | si_ |
| The created space information. | |
| base::ProblemDefinitionPtr | pdef_ |
| The created problem definition. | |
| base::PlannerPtr | planner_ |
| The maintained planner instance. | |
| base::PlannerAllocator | pa_ |
| The optional planner allocator. | |
| PathSimplifierPtr | psk_ |
| The instance of the path simplifier. | |
| bool | configured_ |
| Flag indicating whether the classes needed for planning are set up. | |
| double | planTime_ |
| The amount of time the last planning step took. | |
| double | simplifyTime_ |
| The amount of time the last path simplification step took. | |
| base::PlannerStatus | lastStatus_ |
| The status of the last planning request. | |
Detailed Description
Create the set of classes typically needed to solve a geometric problem.
Definition at line 120 of file ExperienceSetup.h.
Member Function Documentation
◆ setFilePath()
|
virtual |
Set the database file to load. Actual loading occurs when setup() is called.
- Parameters
-
filePath - full absolute path to a experience database to load
Definition at line 93 of file ExperienceSetup.cpp.
The documentation for this class was generated from the following files:
- ompl/tools/experience/ExperienceSetup.h
- ompl/tools/experience/src/ExperienceSetup.cpp
Public Member Functions inherited from