Loading...
Searching...
No Matches
OptimizationObjective.cpp
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2008, Willow Garage, Inc.
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 Willow Garage 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: Luis G. Torres, Ioan Sucan, Jonathan Gammell */
36
37#include "ompl/base/OptimizationObjective.h"
38#include "ompl/tools/config/MagicConstants.h"
39#include "ompl/base/goals/GoalRegion.h"
40#include "ompl/base/samplers/informed/RejectionInfSampler.h"
41#include <limits>
42// For std::make_shared
43#include <memory>
44#include <utility>
45
46ompl::base::OptimizationObjective::OptimizationObjective(SpaceInformationPtr si) : si_(std::move(si)), threshold_(0.0)
47{
48}
49
51{
52 return description_;
53}
54
59
64
69
71{
72 return c1.value() < c2.value();
73}
74
76{
77 // If c1 is not better than c2, and c2 is not better than c1, then they are equal
78 return !isCostBetterThan(c1, c2) && !isCostBetterThan(c2, c1);
79}
80
85
90
95
100
105
110
112{
113 return Cost(std::numeric_limits<double>::infinity());
114}
115
120
125
127{
128 return si_->getStateSpace()->hasSymmetricInterpolate();
129}
130
132{
133 StateSamplerPtr ss = si_->allocStateSampler();
134 State *state = si_->allocState();
135 Cost totalCost(identityCost());
136
137 for (unsigned int i = 0; i < numStates; ++i)
138 {
139 ss->sampleUniform(state);
140 totalCost = combineCosts(totalCost, stateCost(state));
141 }
142
143 si_->freeState(state);
144
145 return Cost(totalCost.value() / (double)numStates);
146}
147
152
154{
155 return static_cast<bool>(costToGoFn_);
156}
157
159{
161 return costToGoFn_(state, goal);
162
163 return identityCost(); // assumes that identity < all costs
164}
165
167{
168 return identityCost(); // assumes that identity < all costs
169}
170
172{
173 return identityCost(); // assumes that identity < all costs
174}
175
176const ompl::base::SpaceInformationPtr &ompl::base::OptimizationObjective::getSpaceInformation() const
177{
178 return si_;
179}
180
182 const ProblemDefinitionPtr &probDefn, unsigned int maxNumberCalls) const
183{
184 OMPL_INFORM("%s: No direct informed sampling scheme is defined, defaulting to rejection sampling.",
185 description_.c_str());
186 return std::make_shared<RejectionInfSampler>(probDefn, maxNumberCalls);
187}
188
189void ompl::base::OptimizationObjective::print(std::ostream &out) const
190{
191 out << "Optimization Objective: " << description_ << " @" << this << std::endl;
192 out << "Optimization Threshold: " << threshold_ << std::endl;
193}
194
196{
197 const auto *goalRegion = goal->as<GoalRegion>();
198
199 // Ensures that all states within the goal region's threshold to
200 // have a cost-to-go of exactly zero.
201 return Cost(std::max(goalRegion->distanceGoal(state) - goalRegion->getThreshold(), 0.0));
202}
203
204ompl::base::MultiOptimizationObjective::MultiOptimizationObjective(const SpaceInformationPtr &si)
205 : OptimizationObjective(si), locked_(false)
206{
207}
208
209ompl::base::MultiOptimizationObjective::Component::Component(OptimizationObjectivePtr obj, double weight)
210 : objective(std::move(obj)), weight(weight)
211{
212}
213
215{
216 if (locked_)
217 {
218 throw Exception("This optimization objective is locked. No further objectives can be added.");
219 }
220 else
221 components_.emplace_back(objective, weight);
222}
223
225{
226 return components_.size();
227}
228
229const ompl::base::OptimizationObjectivePtr &ompl::base::MultiOptimizationObjective::getObjective(unsigned int idx) const
230{
231 if (components_.size() > idx)
232 return components_[idx].objective;
233 throw Exception("Objective index does not exist.");
234}
235
237{
238 if (components_.size() > idx)
239 return components_[idx].weight;
240 throw Exception("Objective index does not exist.");
241}
242
244{
245 if (components_.size() > idx)
246 components_[idx].weight = weight;
247 else
248 throw Exception("Objecitve index does not exist.");
249}
250
255
260
262{
263 Cost c = identityCost();
264 for (const auto &component : components_)
265 {
266 c = Cost(c.value() + component.weight * (component.objective->stateCost(s).value()));
267 }
268
269 return c;
270}
271
273{
274 Cost c = identityCost();
275 for (const auto &component : components_)
276 {
277 c = Cost(c.value() + component.weight * (component.objective->motionCost(s1, s2).value()));
278 }
279
280 return c;
281}
282
283ompl::base::OptimizationObjectivePtr ompl::base::operator+(const OptimizationObjectivePtr &a,
285{
286 std::vector<MultiOptimizationObjective::Component> components;
287
288 if (a)
289 {
290 if (auto *mult = dynamic_cast<MultiOptimizationObjective *>(a.get()))
291 {
292 for (std::size_t i = 0; i < mult->getObjectiveCount(); ++i)
293 {
294 components.emplace_back(mult->getObjective(i), mult->getObjectiveWeight(i));
295 }
296 }
297 else
298 components.emplace_back(a, 1.0);
299 }
300
301 if (b)
302 {
303 if (auto *mult = dynamic_cast<MultiOptimizationObjective *>(b.get()))
304 {
305 for (std::size_t i = 0; i < mult->getObjectiveCount(); ++i)
306 {
307 components.emplace_back(mult->getObjective(i), mult->getObjectiveWeight(i));
308 }
309 }
310 else
311 components.emplace_back(b, 1.0);
312 }
313
314 auto multObj(std::make_shared<MultiOptimizationObjective>(a->getSpaceInformation()));
315 for (const auto &comp : components)
316 multObj->addObjective(comp.objective, comp.weight);
317
318 return multObj;
319}
320
321ompl::base::OptimizationObjectivePtr ompl::base::operator*(double weight, const OptimizationObjectivePtr &a)
322{
323 std::vector<MultiOptimizationObjective::Component> components;
324
325 if (a)
326 {
327 if (auto *mult = dynamic_cast<MultiOptimizationObjective *>(a.get()))
328 {
329 for (std::size_t i = 0; i < mult->getObjectiveCount(); ++i)
330 {
331 components.emplace_back(mult->getObjective(i), weight * mult->getObjectiveWeight(i));
332 }
333 }
334 else
335 components.emplace_back(a, weight);
336 }
337
338 auto multObj(std::make_shared<MultiOptimizationObjective>(a->getSpaceInformation()));
339 for (auto const &comp : components)
340 multObj->addObjective(comp.objective, comp.weight);
341
342 return multObj;
343}
344
345ompl::base::OptimizationObjectivePtr ompl::base::operator*(const OptimizationObjectivePtr &a, double weight)
346{
347 return weight * a;
348}
The exception type for ompl.
Definition Exception.h:47
Definition of a cost value. Can represent the cost of a motion or the cost of a state.
Definition Cost.h:48
double value() const
The value of the cost.
Definition Cost.h:56
Definition of a goal region.
Definition GoalRegion.h:48
Abstract definition of goals.
Definition Goal.h:63
T * as()
Cast this instance to a desired type.
Definition Goal.h:77
This class allows for the definition of multiobjective optimal planning problems. Objectives are adde...
const OptimizationObjectivePtr & getObjective(unsigned int idx) const
Returns a specific objective from this multiobjective, where the individual objectives are in order o...
void setObjectiveWeight(unsigned int idx, double weight)
Sets the weighing factor of a specific objective.
std::size_t getObjectiveCount() const
Returns the number of objectives that make up this multiobjective.
Cost stateCost(const State *s) const override
double getObjectiveWeight(unsigned int idx) const
Returns the weighing factor of a specific objective.
bool locked_
Whether this multiobjective is locked from further additions.
bool isLocked() const
Returns whether this multiobjective has been locked from adding further objectives.
std::vector< Component > components_
List of objective/weight pairs.
void addObjective(const OptimizationObjectivePtr &objective, double weight)
Adds a new objective for this multiobjective. A weight must also be specified for specifying importan...
Cost motionCost(const State *s1, const State *s2) const override
void lock()
This method "freezes" this multiobjective so that no more objectives can be added to it.
A shared pointer wrapper for ompl::base::OptimizationObjective.
Cost costToGo(const State *state, const Goal *goal) const
Uses a cost-to-go heuristic to calculate an admissible estimate of the optimal cost from a given stat...
std::string description_
The description of this optimization objective.
virtual Cost subtractCosts(Cost c1, Cost c2) const
Get the cost that corresponds to subtracting the cost c2 from c1.
void setCostThreshold(Cost c)
Set the cost threshold for objective satisfaction. When a path is found with a cost better than the c...
virtual Cost averageStateCost(unsigned int numStates) const
Compute the average state cost of this objective by taking a sample of numStates states.
bool hasCostToGoHeuristic() const
Check if this objective has a cost-to-go heuristic function.
virtual bool isCostEquivalentTo(Cost c1, Cost c2) const
Compare whether cost c1 and cost c2 are equivalent. By default defined as !isCostBetterThan(c1,...
virtual bool isFinite(Cost cost) const
Returns whether the cost is finite or not.
void setCostToGoHeuristic(const CostToGoHeuristic &costToGo)
Set the cost-to-go heuristic function for this objective. The cost-to-go heuristic is a function whic...
virtual Cost stateCost(const State *s) const =0
Evaluate a cost map defined on the state space at a state s.
const SpaceInformationPtr & getSpaceInformation() const
Returns this objective's SpaceInformation. Needed for operators in MultiOptimizationObjective.
Cost threshold_
The cost threshold used for checking whether this objective has been satisfied during planning.
virtual Cost motionCostHeuristic(const State *s1, const State *s2) const
Defines an admissible estimate on the optimal cost on the motion between states s1 and s2....
virtual Cost identityCost() const
Get the identity cost value. The identity cost value is the cost c_i such that, for all costs c,...
virtual Cost combineCosts(Cost c1, Cost c2) const
Get the cost that corresponds to combining the costs c1 and c2. Default implementation defines this c...
virtual Cost terminalCost(const State *s) const
Returns a cost value corresponding to a path ending at a state s. No optimal planners currently suppo...
virtual Cost controlCost(const control::Control *c, unsigned int steps) const
Get the cost that corresponds to the motion created by a control c applied for duration steps....
virtual bool isCostBetterThan(Cost c1, Cost c2) const
Check whether the the cost c1 is considered better than the cost c2. By default, this returns true if...
CostToGoHeuristic costToGoFn_
The function used for returning admissible estimates on the optimal cost of the path between a given ...
Cost getCostThreshold() const
Returns the cost threshold currently being checked for objective satisfaction.
virtual bool isSatisfied(Cost c) const
Check if the the given cost c satisfies the specified cost objective, defined as better than the spec...
virtual Cost motionCostBestEstimate(const State *s1, const State *s2) const
Defines a possibly inadmissible estimate on the optimal cost on the motion between states s1 and s2....
virtual Cost betterCost(Cost c1, Cost c2) const
Return the minimum cost given c1 and c2. Uses isCostBetterThan.
virtual bool isSymmetric() const
Check if this objective has a symmetric cost metric, i.e. motionCost(s1, s2) = motionCost(s2,...
virtual Cost infiniteCost() const
Get a cost which is greater than all other costs in this OptimizationObjective; required for use in D...
const std::string & getDescription() const
Get the description of this optimization objective.
virtual Cost initialCost(const State *s) const
Returns a cost value corresponding to starting at a state s. No optimal planners currently support th...
virtual void print(std::ostream &out) const
Print information about this optimization objective.
virtual InformedSamplerPtr allocInformedStateSampler(const ProblemDefinitionPtr &probDefn, unsigned int maxNumberCalls) const
Allocate a heuristic-sampling state generator for this cost function, defaults to a basic rejection s...
SpaceInformationPtr si_
The space information for this objective.
A shared pointer wrapper for ompl::base::ProblemDefinition.
A shared pointer wrapper for ompl::base::SpaceInformation.
A shared pointer wrapper for ompl::base::StateSampler.
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
Cost goalRegionCostToGo(const State *state, const Goal *goal)
For use when the cost-to-go of a state under the optimization objective is equivalent to the goal reg...
std::function< Cost(const State *, const Goal *)> CostToGoHeuristic
The definition of a function which returns an admissible estimate of the optimal path cost from a giv...
OptimizationObjectivePtr operator+(const OptimizationObjectivePtr &a, const OptimizationObjectivePtr &b)
Given two optimization objectives, returns a MultiOptimizationObjective that combines the two objecti...
OptimizationObjectivePtr operator*(double weight, const OptimizationObjectivePtr &a)
Given a weighing factor and an optimization objective, returns a MultiOptimizationObjective containin...
STL namespace.