ProblemDefinition.h
143 typedef boost::function<void(const Planner*, const std::vector<const base::State*> &, const Cost)> ReportIntermediateSolutionFn;
242 void setStartAndGoalStates(const State *start, const State *goal, const double threshold = std::numeric_limits<double>::epsilon());
245 void setGoalState(const State *goal, const double threshold = std::numeric_limits<double>::epsilon());
248 void setStartAndGoalStates(const ScopedState<> &start, const ScopedState<> &goal, const double threshold = std::numeric_limits<double>::epsilon())
254 void setGoalState(const ScopedState<> &goal, const double threshold = std::numeric_limits<double>::epsilon())
346 void addSolutionPath(const PathPtr &path, bool approximate = false, double difference = -1.0, const std::string& plannerName = "Unknown") const;
PlannerSolution(const PathPtr &path)
Construct a solution that consists of a path and its attributes (whether it is approximate and the di...
Definition: ProblemDefinition.h:75
void setApproximate(double difference)
Specify that the solution is approximate and set the difference to the goal.
Definition: ProblemDefinition.h:91
bool optimized_
True if the solution was optimized to meet the specified optimization criterion.
Definition: ProblemDefinition.h:127
void setOptimizationObjective(const OptimizationObjectivePtr &optimizationObjective)
Set the optimization objective to be considered during planning.
Definition: ProblemDefinition.h:272
Representation of a solution to a planning problem.
Definition: ProblemDefinition.h:72
State * getStartState(unsigned int index)
Returns a specific start state.
Definition: ProblemDefinition.h:206
A boost shared pointer wrapper for ompl::base::SolutionNonExistenceProof.
ReportIntermediateSolutionFn intermediateSolutionCallback_
Callback function which is called when a new intermediate solution has been found.
Definition: ProblemDefinition.h:396
void addStartState(const ScopedState<> &state)
Add a start state. The state is copied.
Definition: ProblemDefinition.h:175
SolutionNonExistenceProofPtr nonExistenceProof_
A Representation of a proof of non-existence of a solution for this problem definition.
Definition: ProblemDefinition.h:390
bool approximate_
True if goal was not achieved, but an approximate solution was found.
Definition: ProblemDefinition.h:121
void setStartAndGoalStates(const ScopedState<> &start, const ScopedState<> &goal, const double threshold=std::numeric_limits< double >::epsilon())
In the simplest case possible, we have a single starting state and a single goal state.
Definition: ProblemDefinition.h:248
bool operator==(const PlannerSolution &p) const
Return true if two solutions are the same.
Definition: ProblemDefinition.h:82
boost::function< void(const Planner *, const std::vector< const base::State * > &, const Cost)> ReportIntermediateSolutionFn
When a planner has an intermediate solution (e.g., optimizing planners), a function with this signatu...
Definition: ProblemDefinition.h:139
void setGoalState(const ScopedState<> &goal, const double threshold=std::numeric_limits< double >::epsilon())
A simple form of setting the goal. This is called by setStartAndGoalStates(). A more general form is ...
Definition: ProblemDefinition.h:254
OptimizationObjectivePtr optimizationObjective_
The objective to be optimized while solving the planning problem.
Definition: ProblemDefinition.h:393
const State * getStartState(unsigned int index) const
Returns a specific start state.
Definition: ProblemDefinition.h:200
int index_
When multiple solutions are found, each is given a number starting at 0, so that the order in which t...
Definition: ProblemDefinition.h:112
A boost shared pointer wrapper for ompl::base::SpaceInformation.
Cost cost_
The cost of this solution path, with respect to the optimization objective.
Definition: ProblemDefinition.h:133
Abstract definition of optimization objectives.
Definition: OptimizationObjective.h:66
void setOptimized(const OptimizationObjectivePtr &opt, Cost cost, bool meetsObjective)
Set the optimization objective used to optimize this solution, the cost of the solution and whether i...
Definition: ProblemDefinition.h:98
Definition of a problem to be solved. This includes the start state(s) for the system and a goal spec...
Definition: ProblemDefinition.h:150
A boost shared pointer wrapper for ompl::base::OptimizationObjective.
OptimizationObjectivePtr opt_
Optimization objective that was used to optimize this solution.
Definition: ProblemDefinition.h:130
std::string plannerName_
Name of planner type that generated this solution, as received from Planner::getName() ...
Definition: ProblemDefinition.h:136
bool operator<(const PlannerSolution &b) const
Define a ranking for solutions.
Definition: ProblemDefinition.cpp:152
SpaceInformationPtr si_
The space information this problem definition is for.
Definition: ProblemDefinition.h:381
void addStartState(const State *state)
Add a start state. The state is copied.
Definition: ProblemDefinition.h:169
A boost shared pointer wrapper for ompl::base::Goal.
const SpaceInformationPtr & getSpaceInformation() const
Get the space information this problem definition is for.
Definition: ProblemDefinition.h:163
double difference_
The achieved difference between the found solution and the desired goal.
Definition: ProblemDefinition.h:124
bool hasOptimizationObjective() const
Check if an optimization objective was defined for planning.
Definition: ProblemDefinition.h:260
unsigned int getStartStateCount() const
Returns the number of start states.
Definition: ProblemDefinition.h:194
double length_
For efficiency reasons, keep the length of the path as well.
Definition: ProblemDefinition.h:118
const OptimizationObjectivePtr & getOptimizationObjective() const
Get the optimization objective to be considered during planning.
Definition: ProblemDefinition.h:266
void setIntermediateSolutionCallback(const ReportIntermediateSolutionFn &callback)
Set the callback to be called by planners that can compute intermediate solutions.
Definition: ProblemDefinition.h:285
const ReportIntermediateSolutionFn & getIntermediateSolutionCallback() const
When this function returns a valid function pointer, that function should be called by planners that ...
Definition: ProblemDefinition.h:279
void setPlannerName(const std::string &name)
Set the name of the planner used to compute this solution.
Definition: ProblemDefinition.h:106
Definition of a cost value. Can represent the cost of a motion or the cost of a state.
Definition: Cost.h:47
A boost shared pointer wrapper for ompl::base::Path.