Loading...
Searching...
No Matches
ProblemDefinition.cpp
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2010, Rice University
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of the Rice University nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34
35/* Author: Ioan Sucan */
36
37#include "ompl/base/ProblemDefinition.h"
38#include "ompl/base/goals/GoalState.h"
39#include "ompl/base/goals/GoalStates.h"
40#include "ompl/base/OptimizationObjective.h"
41#include "ompl/control/SpaceInformation.h"
42#include "ompl/control/PathControl.h"
43#include "ompl/tools/config/MagicConstants.h"
44#include <sstream>
45#include <algorithm>
46#include <mutex>
47#include <utility>
48
50namespace ompl
51{
52 namespace base
53 {
54 class ProblemDefinition::PlannerSolutionSet
55 {
56 public:
57 PlannerSolutionSet() = default;
58
59 void add(const PlannerSolution &s)
60 {
61 std::lock_guard<std::mutex> slock(lock_);
62 int index = solutions_.size();
63 solutions_.push_back(s);
64 solutions_.back().index_ = index;
65 std::sort(solutions_.begin(), solutions_.end());
66 }
67
68 void clear()
69 {
70 std::lock_guard<std::mutex> slock(lock_);
71 solutions_.clear();
72 }
73
74 std::vector<PlannerSolution> getSolutions()
75 {
76 std::lock_guard<std::mutex> slock(lock_);
77 std::vector<PlannerSolution> copy = solutions_;
78 return copy;
79 }
80
81 bool isApproximate()
82 {
83 std::lock_guard<std::mutex> slock(lock_);
84 bool result = false;
85 if (!solutions_.empty())
86 result = solutions_[0].approximate_;
87 return result;
88 }
89
90 bool isOptimized()
91 {
92 std::lock_guard<std::mutex> slock(lock_);
93 bool result = false;
94 if (!solutions_.empty())
95 result = solutions_[0].optimized_;
96 return result;
97 }
98
99 double getDifference()
100 {
101 std::lock_guard<std::mutex> slock(lock_);
102 double diff = -1.0;
103 if (!solutions_.empty())
104 diff = solutions_[0].difference_;
105 return diff;
106 }
107
108 PathPtr getTopSolution()
109 {
110 std::lock_guard<std::mutex> slock(lock_);
111 PathPtr copy;
112 if (!solutions_.empty())
113 copy = solutions_[0].path_;
114 return copy;
115 }
116
117 bool getTopSolution(PlannerSolution &solution)
118 {
119 std::lock_guard<std::mutex> slock(lock_);
120
121 if (!solutions_.empty())
122 {
123 solution = solutions_[0];
124 return true;
125 }
126 else
127 {
128 return false;
129 }
130 }
131
132 std::size_t getSolutionCount()
133 {
134 std::lock_guard<std::mutex> slock(lock_);
135 std::size_t result = solutions_.size();
136 return result;
137 }
138
139 private:
140 std::vector<PlannerSolution> solutions_;
141 std::mutex lock_;
142 };
143 } // namespace base
144} // namespace ompl
146
148{
149 if (!approximate_ && b.approximate_)
150 return true;
151 if (approximate_ && !b.approximate_)
152 return false;
153 if (approximate_ && b.approximate_)
154 return difference_ < b.difference_;
155 if (optimized_ && !b.optimized_)
156 return true;
157 if (!optimized_ && b.optimized_)
158 return false;
159 return opt_ ? opt_->isCostBetterThan(cost_, b.cost_) : length_ < b.length_;
160}
161
162ompl::base::ProblemDefinition::ProblemDefinition(SpaceInformationPtr si)
163 : si_(std::move(si)), solutions_(std::make_shared<PlannerSolutionSet>())
164{
165}
166
167ompl::base::ProblemDefinitionPtr ompl::base::ProblemDefinition::clone() const
168{
169 auto result = std::make_shared<ProblemDefinition>(si_);
170 result->startStates_.reserve(startStates_.size());
171 for (const auto &state : startStates_)
172 result->addStartState(state);
173 result->setGoal(goal_);
174 result->setOptimizationObjective(optimizationObjective_);
175 result->setSolutionNonExistenceProof(nonExistenceProof_);
176
177 return result;
178}
179
180void ompl::base::ProblemDefinition::setStartAndGoalStates(const State *start, const State *goal, const double threshold)
181{
183 addStartState(start);
184 setGoalState(goal, threshold);
185}
186
187void ompl::base::ProblemDefinition::setGoalState(const State *goal, const double threshold)
188{
189 clearGoal();
190 auto gs(std::make_shared<GoalState>(si_));
191 gs->setState(goal);
192 gs->setThreshold(threshold);
193 setGoal(gs);
194}
195
196bool ompl::base::ProblemDefinition::hasStartState(const State *state, unsigned int *startIndex) const
197{
198 for (unsigned int i = 0; i < startStates_.size(); ++i)
199 if (si_->equalStates(state, startStates_[i]))
200 {
201 if (startIndex)
202 *startIndex = i;
203 return true;
204 }
205 return false;
206}
207
208bool ompl::base::ProblemDefinition::fixInvalidInputState(State *state, double dist, bool start, unsigned int attempts)
209{
210 bool result = false;
211
212 bool b = si_->satisfiesBounds(state);
213 bool v = false;
214 if (b)
215 {
216 v = si_->isValid(state);
217 if (!v)
218 OMPL_DEBUG("%s state is not valid", start ? "Start" : "Goal");
219 }
220 else
221 OMPL_DEBUG("%s state is not within space bounds", start ? "Start" : "Goal");
222
223 if (!b || !v)
224 {
225 std::stringstream ss;
226 si_->printState(state, ss);
227 ss << " within distance " << dist;
228 OMPL_DEBUG("Attempting to fix %s state %s", start ? "start" : "goal", ss.str().c_str());
229
230 State *temp = si_->allocState();
231 if (si_->searchValidNearby(temp, state, dist, attempts))
232 {
233 si_->copyState(state, temp);
234 result = true;
235 }
236 else
237 OMPL_WARN("Unable to fix %s state", start ? "start" : "goal");
238 si_->freeState(temp);
239 }
240
241 return result;
242}
243
244bool ompl::base::ProblemDefinition::fixInvalidInputStates(double distStart, double distGoal, unsigned int attempts)
245{
246 bool result = true;
247
248 // fix start states
249 for (auto &startState : startStates_)
250 if (!fixInvalidInputState(startState, distStart, true, attempts))
251 result = false;
252
253 // fix goal state
254 auto *goal = dynamic_cast<GoalState *>(goal_.get());
255 if (goal)
256 {
257 if (!fixInvalidInputState(const_cast<State *>(goal->getState()), distGoal, false, attempts))
258 result = false;
259 }
260
261 // fix goal state
262 auto *goals = dynamic_cast<GoalStates *>(goal_.get());
263 if (goals)
264 {
265 for (unsigned int i = 0; i < goals->getStateCount(); ++i)
266 if (!fixInvalidInputState(const_cast<State *>(goals->getState(i)), distGoal, false, attempts))
267 result = false;
268 }
269
270 return result;
271}
272
273void ompl::base::ProblemDefinition::getInputStates(std::vector<const State *> &states) const
274{
275 states.clear();
276 for (auto startState : startStates_)
277 states.push_back(startState);
278
279 auto *goal = dynamic_cast<GoalState *>(goal_.get());
280 if (goal)
281 states.push_back(goal->getState());
282
283 auto *goals = dynamic_cast<GoalStates *>(goal_.get());
284 if (goals)
285 for (unsigned int i = 0; i < goals->getStateCount(); ++i)
286 states.push_back(goals->getState(i));
287}
288
290{
291 PathPtr path;
292 if (control::SpaceInformationPtr sic = std::dynamic_pointer_cast<control::SpaceInformation, SpaceInformation>(si_))
293 {
294 unsigned int startIndex;
295 if (isTrivial(&startIndex, nullptr))
296 {
297 auto pc(std::make_shared<control::PathControl>(sic));
298 pc->append(startStates_[startIndex]);
299 control::Control *null = sic->allocControl();
300 sic->nullControl(null);
301 pc->append(startStates_[startIndex], null, 0.0);
302 sic->freeControl(null);
303 path = pc;
304 }
305 else
306 {
307 control::Control *nc = sic->allocControl();
308 State *result1 = sic->allocState();
309 State *result2 = sic->allocState();
310 sic->nullControl(nc);
311
312 for (unsigned int k = 0; k < startStates_.size() && !path; ++k)
313 {
314 const State *start = startStates_[k];
315 if (start && si_->isValid(start) && si_->satisfiesBounds(start))
316 {
317 sic->copyState(result1, start);
318 for (unsigned int i = 0; i < sic->getMaxControlDuration() && !path; ++i)
319 if (sic->propagateWhileValid(result1, nc, 1, result2))
320 {
321 if (goal_->isSatisfied(result2))
322 {
323 auto pc(std::make_shared<control::PathControl>(sic));
324 pc->append(start);
325 pc->append(result2, nc, (i + 1) * sic->getPropagationStepSize());
326 path = pc;
327 break;
328 }
329 std::swap(result1, result2);
330 }
331 }
332 }
333 sic->freeState(result1);
334 sic->freeState(result2);
335 sic->freeControl(nc);
336 }
337 }
338 else
339 {
340 std::vector<const State *> states;
341 auto *goal = dynamic_cast<GoalState *>(goal_.get());
342 if (goal)
343 if (si_->isValid(goal->getState()) && si_->satisfiesBounds(goal->getState()))
344 states.push_back(goal->getState());
345 auto *goals = dynamic_cast<GoalStates *>(goal_.get());
346 if (goals)
347 for (unsigned int i = 0; i < goals->getStateCount(); ++i)
348 if (si_->isValid(goals->getState(i)) && si_->satisfiesBounds(goals->getState(i)))
349 states.push_back(goals->getState(i));
350
351 if (states.empty())
352 {
353 unsigned int startIndex;
354 if (isTrivial(&startIndex))
355 path =
356 std::make_shared<geometric::PathGeometric>(si_, startStates_[startIndex], startStates_[startIndex]);
357 }
358 else
359 {
360 for (const auto start : startStates_)
361 if (start && si_->isValid(start) && si_->satisfiesBounds(start))
362 for (const auto state : states)
363 if (si_->checkMotion(start, state))
364 return std::make_shared<geometric::PathGeometric>(si_, start, state);
365 }
366 }
367
368 return path;
369}
370
371bool ompl::base::ProblemDefinition::isTrivial(unsigned int *startIndex, double *distance) const
372{
373 if (!goal_)
374 {
375 OMPL_ERROR("Goal undefined");
376 return false;
377 }
378
379 for (unsigned int i = 0; i < startStates_.size(); ++i)
380 {
381 const State *start = startStates_[i];
382 if (start && si_->isValid(start) && si_->satisfiesBounds(start))
383 {
384 double dist;
385 if (goal_->isSatisfied(start, &dist))
386 {
387 if (startIndex)
388 *startIndex = i;
389 if (distance)
390 *distance = dist;
391 return true;
392 }
393 }
394 else
395 {
396 OMPL_ERROR("Initial state is in collision!");
397 }
398 }
399
400 return false;
401}
402
404{
405 return solutions_->getSolutionCount() > 0;
406}
407
409{
410 return solutions_->getSolutionCount();
411}
412
414{
415 return solutions_->getTopSolution();
416}
417
419{
420 return solutions_->getTopSolution(solution);
421}
422
423void ompl::base::ProblemDefinition::addSolutionPath(const PathPtr &path, bool approximate, double difference,
424 const std::string &plannerName) const
425{
426 PlannerSolution sol(path);
427 if (approximate)
428 sol.setApproximate(difference);
429 sol.setPlannerName(plannerName);
430 addSolutionPath(sol);
431}
432
434{
435 if (sol.approximate_)
436 OMPL_INFORM("ProblemDefinition: Adding approximate solution from planner %s", sol.plannerName_.c_str());
437 solutions_->add(sol);
438}
439
441{
442 return solutions_->isApproximate();
443}
444
446{
447 return solutions_->isOptimized();
448}
449
451{
452 return solutions_->getDifference();
453}
454
455std::vector<ompl::base::PlannerSolution> ompl::base::ProblemDefinition::getSolutions() const
456{
457 return solutions_->getSolutions();
458}
459
461{
462 solutions_->clear();
463}
464
465void ompl::base::ProblemDefinition::print(std::ostream &out) const
466{
467 out << "Start states:" << std::endl;
468 for (auto startState : startStates_)
469 si_->printState(startState, out);
470 if (goal_)
471 goal_->print(out);
472 else
473 out << "Goal = nullptr" << std::endl;
475 {
476 optimizationObjective_->print(out);
477 out << "Average state cost: " << optimizationObjective_->averageStateCost(magic::TEST_STATE_COUNT) << std::endl;
478 }
479 else
480 out << "OptimizationObjective = nullptr" << std::endl;
481 out << "There are " << solutions_->getSolutionCount() << " solutions" << std::endl;
482}
483
488
493
494const ompl::base::SolutionNonExistenceProofPtr &ompl::base::ProblemDefinition::getSolutionNonExistenceProof() const
495{
496 return nonExistenceProof_;
497}
498
500 const ompl::base::SolutionNonExistenceProofPtr &nonExistenceProof)
501{
502 nonExistenceProof_ = nonExistenceProof;
503}
Definition of a goal state.
Definition GoalState.h:49
Definition of a set of goal states.
Definition GoalStates.h:50
A shared pointer wrapper for ompl::base::Path.
void setGoal(const GoalPtr &goal)
Set the goal.
void getInputStates(std::vector< const State * > &states) const
Get all the input states. This includes start states and states that are part of goal regions that ca...
void setGoalState(const State *goal, double threshold=std::numeric_limits< double >::epsilon())
A simple form of setting the goal. This is called by setStartAndGoalStates(). A more general form is ...
void clearSolutionNonExistenceProof()
Removes any existing instance of SolutionNonExistenceProof.
bool isTrivial(unsigned int *startIndex=nullptr, double *distance=nullptr) const
A problem is trivial if a given starting state already in the goal region, so we need no motion plann...
std::size_t getSolutionCount() const
Get the number of solutions already found.
void addStartState(const State *state)
Add a start state. The state is copied.
bool hasStartState(const State *state, unsigned int *startIndex=nullptr) const
Check whether a specified starting state is already included in the problem definition and optionally...
GoalPtr goal_
The goal representation.
bool fixInvalidInputState(State *state, double dist, bool start, unsigned int attempts)
Helper function for fixInvalidInputStates(). Attempts to fix an individual state.
void print(std::ostream &out=std::cout) const
Print information about the start and goal states and the optimization objective.
void addSolutionPath(const PathPtr &path, bool approximate=false, double difference=-1.0, const std::string &plannerName="Unknown") const
Add a solution path in a thread-safe manner. Multiple solutions can be set for a goal....
void clearStartStates()
Clear all start states (memory is freed).
bool fixInvalidInputStates(double distStart, double distGoal, unsigned int attempts)
Many times the start or goal state will barely touch an obstacle. In this case, we may want to automa...
void setSolutionNonExistenceProof(const SolutionNonExistenceProofPtr &nonExistenceProof)
Set the instance of SolutionNonExistenceProof for this problem definition.
PathPtr isStraightLinePathValid() const
Check if a straight line path is valid. If it is, return an instance of a path that represents the st...
bool hasApproximateSolution() const
Return true if the top found solution is approximate (does not actually reach the desired goal,...
bool hasSolutionNonExistenceProof() const
Returns true if the problem definition has a proof of non existence for a solution.
SolutionNonExistenceProofPtr nonExistenceProof_
A Representation of a proof of non-existence of a solution for this problem definition.
bool hasSolution() const
Returns true if a solution path has been found (could be approximate).
bool getSolution(PlannerSolution &solution) const
Return true if a top solution is found, with the top solution passed by reference in the function hea...
PathPtr getSolutionPath() const
Return the top solution path, if one is found. The top path is a shortest path that was found,...
const SolutionNonExistenceProofPtr & getSolutionNonExistenceProof() const
Retrieve a pointer to the SolutionNonExistenceProof instance for this problem definition.
void setStartAndGoalStates(const State *start, const State *goal, double threshold=std::numeric_limits< double >::epsilon())
In the simplest case possible, we have a single starting state and a single goal state.
OptimizationObjectivePtr optimizationObjective_
The objective to be optimized while solving the planning problem.
std::vector< PlannerSolution > getSolutions() const
Get all the solution paths available for this goal.
SpaceInformationPtr si_
The space information this problem definition is for.
bool hasOptimizedSolution() const
Return true if the top found solution is optimized (satisfies the specified optimization objective).
void clearSolutionPaths() const
Forget the solution paths (thread safe). Memory is freed.
ProblemDefinitionPtr clone() const
Return a copy of the problem definition.
void clearGoal()
Clear the goal. Memory is freed.
double getSolutionDifference() const
Get the distance to the desired goal for the top solution. Return -1.0 if there are no solutions avai...
std::vector< State * > startStates_
The set of start states.
A shared pointer wrapper for ompl::base::SpaceInformation.
Definition of an abstract state.
Definition State.h:50
Definition of an abstract control.
Definition Control.h:48
#define OMPL_INFORM(fmt,...)
Log a formatted information string.
Definition Console.h:68
#define OMPL_ERROR(fmt,...)
Log a formatted error string.
Definition Console.h:64
#define OMPL_DEBUG(fmt,...)
Log a formatted debugging string.
Definition Console.h:70
#define OMPL_WARN(fmt,...)
Log a formatted warning string.
Definition Console.h:66
This namespace contains sampling based planning routines shared by both planning under geometric cons...
static const unsigned int TEST_STATE_COUNT
When multiple states need to be generated as part of the computation of various information (usually ...
Main namespace. Contains everything in this library.
STL namespace.
Representation of a solution to a planning problem.
PlannerSolution(const PathPtr &path)
Construct a solution that consists of a path and its attributes (whether it is approximate and the di...
bool optimized_
True if the solution was optimized to meet the specified optimization criterion.
std::string plannerName_
Name of planner type that generated this solution, as received from Planner::getName().
void setApproximate(double difference)
Specify that the solution is approximate and set the difference to the goal.
Cost cost_
The cost of this solution path, with respect to the optimization objective.
OptimizationObjectivePtr opt_
Optimization objective that was used to optimize this solution.
bool approximate_
True if goal was not achieved, but an approximate solution was found.
double length_
For efficiency reasons, keep the length of the path as well.
double difference_
The achieved difference between the found solution and the desired goal.
void setPlannerName(const std::string &name)
Set the name of the planner used to compute this solution.
bool operator<(const PlannerSolution &b) const
Define a ranking for solutions.