OptimizationObjective.h
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2012, 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 */
36 
37 #ifndef OMPL_BASE_OPTIMIZATION_OBJECTIVE_
38 #define OMPL_BASE_OPTIMIZATION_OBJECTIVE_
39 
40 #include "ompl/base/Cost.h"
41 #include "ompl/base/SpaceInformation.h"
42 #include "ompl/util/ClassForward.h"
43 #include <boost/noncopyable.hpp>
44 #include <boost/concept_check.hpp>
45 
46 namespace ompl
47 {
48  namespace base
49  {
50  class Goal;
51 
53  typedef boost::function<Cost (const State*, const Goal*)> CostToGoHeuristic;
54 
56 
57  OMPL_CLASS_FORWARD(OptimizationObjective);
59 
66  class OptimizationObjective : private boost::noncopyable
67  {
68  public:
71 
72  virtual ~OptimizationObjective()
73  {
74  }
75 
77  const std::string& getDescription() const;
78 
80  virtual bool isSatisfied(Cost c) const;
81 
83  Cost getCostThreshold() const;
84 
86  void setCostThreshold(Cost c);
87 
89  virtual bool isCostBetterThan(Cost c1, Cost c2) const;
90 
92  virtual Cost stateCost(const State *s) const = 0;
93 
95  virtual Cost motionCost(const State *s1, const State *s2) const = 0;
96 
98  virtual Cost combineCosts(Cost c1, Cost c2) const;
99 
101  virtual Cost identityCost() const;
102 
104  virtual Cost infiniteCost() const;
105 
107  virtual Cost initialCost(const State *s) const;
108 
110  virtual Cost terminalCost(const State *s) const;
111 
113  virtual bool isSymmetric() const;
114 
116  virtual Cost averageStateCost(unsigned int numStates) const;
117 
119  void setCostToGoHeuristic(const CostToGoHeuristic& costToGo);
120 
122  Cost costToGo(const State *state, const Goal *goal) const;
123 
125  virtual Cost motionCostHeuristic(const State *s1, const State *s2) const;
126 
129 
130  protected:
133 
135  std::string description_;
136 
139 
141  CostToGoHeuristic costToGoFn_;
142  };
143 
152  Cost goalRegionCostToGo(const State *state, const Goal *goal);
153 
156  {
157  public:
159 
161  void addObjective(const OptimizationObjectivePtr& objective,
162  double weight);
163 
165  std::size_t getObjectiveCount() const;
166 
168  const OptimizationObjectivePtr& getObjective(unsigned int idx) const;
169 
171  double getObjectiveWeight(unsigned int idx) const;
172 
174  void setObjectiveWeight(unsigned int idx, double weight);
175 
177  void lock();
178 
180  bool isLocked() const;
181 
186  virtual Cost stateCost(const State *s) const;
187 
192  virtual Cost motionCost(const State *s1, const State *s2) const;
193 
194  protected:
195 
197  struct Component
198  {
199  Component(const OptimizationObjectivePtr& obj, double weight);
200  OptimizationObjectivePtr objective;
201  double weight;
202  };
203 
205  std::vector<Component> components_;
206 
208  bool locked_;
209 
210  // Friend functions for operator overloads for easy multiobjective creation
212  const OptimizationObjectivePtr &b);
213 
215 
217  };
218 
221  const OptimizationObjectivePtr &b);
222 
225 
228  }
229 }
230 
231 #endif
virtual Cost initialCost(const State *s) const
Returns a cost value corresponding to starting at a state s. No optimal planners currently support th...
std::string description_
The description of this optimization objective.
This class allows for the definition of multiobjective optimal planning problems. Objectives are adde...
std::vector< Component > components_
List of objective/weight pairs.
virtual bool isSymmetric() const
Check if this objective has a symmetric cost metric, i.e. motionCost(s1, s2) = motionCost(s2, s1). Default implementation returns whether the underlying state space has symmetric interpolation.
boost::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...
Abstract definition of goals.
Definition: Goal.h:63
Cost goalRegionCostToGo(const State *state, const Goal *goal)
For use when goal region&#39;s distanceGoal() is equivalent to the cost-to-go of a state under the optimi...
virtual Cost averageStateCost(unsigned int numStates) const
Compute the average state cost of this objective by taking a sample of numStates states.
void setCostThreshold(Cost c)
Set the cost threshold for objective satisfaction. When a path is found with a cost better than the c...
const std::string & getDescription() const
Get the description of this optimization objective.
virtual Cost infiniteCost() const
Get a cost which is greater than all other costs in this OptimizationObjective; required for use in D...
virtual Cost motionCost(const State *s1, const State *s2) const =0
Get the cost that corresponds to the motion segment between s1 and s2.
CostToGoHeuristic costToGoFn_
The function used for returning admissible estimates on the optimal cost of the path between a given ...
virtual Cost stateCost(const State *s) const =0
Evaluate a cost map defined on the state space at a state s.
Main namespace. Contains everything in this library.
Definition: Cost.h:42
const SpaceInformationPtr & getSpaceInformation() const
Returns this objective&#39;s SpaceInformation. Needed for operators in MultiOptimizationObjective.
OptimizationObjective(const SpaceInformationPtr &si)
Constructor. The objective must always know the space information it is part of. The cost threshold f...
void setCostToGoHeuristic(const CostToGoHeuristic &costToGo)
Set the cost-to-go heuristic function for this objective. The cost-to-go heuristic is a function whic...
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...
Cost getCostThreshold() const
Returns the cost threshold currently being checked for objective satisfaction.
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...
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 on...
A boost shared pointer wrapper for ompl::base::SpaceInformation.
Defines a pairing of an objective and its weight.
Definition of an abstract state.
Definition: State.h:50
OptimizationObjectivePtr operator+(const OptimizationObjectivePtr &a, const OptimizationObjectivePtr &b)
Given two optimization objectives, returns a MultiOptimizationObjective that combines the two objecti...
Abstract definition of optimization objectives.
A boost shared pointer wrapper for ompl::base::OptimizationObjective.
bool locked_
Whether this multiobjective is locked from further additions.
virtual bool isSatisfied(Cost c) const
Verify that our objective is satisfied already and we can stop planning.
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...
SpaceInformationPtr si_
The space information for this objective.
virtual Cost identityCost() const
Get the identity cost value. The identity cost value is the cost c_i such that, for all costs c...
Definition of a cost value. Can represent the cost of a motion or the cost of a state.
Definition: Cost.h:47
OptimizationObjectivePtr operator*(double w, const OptimizationObjectivePtr &a)
Given a weighing factor and an optimization objective, returns a MultiOptimizationObjective containin...