Program Listing for File OptimizationObjective.h
↰ Return to documentation for file (src/ompl/base/OptimizationObjective.h
)
/*********************************************************************
* Software License Agreement (BSD License)
*
* Copyright (c) 2012, Willow Garage, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above
* copyright notice, this list of conditions and the following
* disclaimer in the documentation and/or other materials provided
* with the distribution.
* * Neither the name of the Willow Garage nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
/* Author: Luis G. Torres, Ioan Sucan, Jonathan Gammell */
#ifndef OMPL_BASE_OPTIMIZATION_OBJECTIVE_
#define OMPL_BASE_OPTIMIZATION_OBJECTIVE_
#include "ompl/base/Cost.h"
#include "ompl/base/SpaceInformation.h"
#include "ompl/util/ClassForward.h"
#include "ompl/base/ProblemDefinition.h"
#include "ompl/base/samplers/InformedStateSampler.h"
// This is needed to correctly generate the python bindings
#ifndef __castxml__
#include "ompl/control/Control.h"
#endif
#include <functional>
#include <iostream>
namespace ompl
{
namespace base
{
class Goal;
using CostToGoHeuristic = std::function<Cost(const State *, const Goal *)>;
OMPL_CLASS_FORWARD(OptimizationObjective);
class OptimizationObjective
{
public:
// non-copyable
OptimizationObjective(const OptimizationObjective &) = delete;
OptimizationObjective &operator=(const OptimizationObjective &) = delete;
OptimizationObjective(SpaceInformationPtr si);
virtual ~OptimizationObjective() = default;
const std::string &getDescription() const;
virtual bool isSatisfied(Cost c) const;
Cost getCostThreshold() const;
void setCostThreshold(Cost c);
virtual bool isCostBetterThan(Cost c1, Cost c2) const;
virtual bool isCostEquivalentTo(Cost c1, Cost c2) const;
virtual bool isFinite(Cost cost) const;
virtual Cost betterCost(Cost c1, Cost c2) const;
virtual Cost stateCost(const State *s) const = 0;
virtual Cost motionCost(const State *s1, const State *s2) const = 0;
// This is needed to correctly generate the python bindings
#ifndef __castxml__
virtual Cost controlCost(const control::Control *c, unsigned int steps) const;
#endif
virtual Cost combineCosts(Cost c1, Cost c2) const;
virtual Cost subtractCosts(Cost c1, Cost c2) const;
virtual Cost identityCost() const;
virtual Cost infiniteCost() const;
virtual Cost initialCost(const State *s) const;
virtual Cost terminalCost(const State *s) const;
virtual bool isSymmetric() const;
virtual Cost averageStateCost(unsigned int numStates) const;
void setCostToGoHeuristic(const CostToGoHeuristic &costToGo);
bool hasCostToGoHeuristic() const;
Cost costToGo(const State *state, const Goal *goal) const;
virtual Cost motionCostHeuristic(const State *s1, const State *s2) const;
virtual Cost motionCostBestEstimate(const State *s1, const State *s2) const;
const SpaceInformationPtr &getSpaceInformation() const;
virtual InformedSamplerPtr allocInformedStateSampler(const ProblemDefinitionPtr &probDefn,
unsigned int maxNumberCalls) const;
virtual void print(std::ostream &out) const;
protected:
SpaceInformationPtr si_;
std::string description_;
Cost threshold_;
CostToGoHeuristic costToGoFn_;
};
Cost goalRegionCostToGo(const State *state, const Goal *goal);
class MultiOptimizationObjective : public OptimizationObjective
{
public:
MultiOptimizationObjective(const SpaceInformationPtr &si);
void addObjective(const OptimizationObjectivePtr &objective, double weight);
std::size_t getObjectiveCount() const;
const OptimizationObjectivePtr &getObjective(unsigned int idx) const;
double getObjectiveWeight(unsigned int idx) const;
void setObjectiveWeight(unsigned int idx, double weight);
void lock();
bool isLocked() const;
Cost stateCost(const State *s) const override;
Cost motionCost(const State *s1, const State *s2) const override;
protected:
struct Component
{
Component(OptimizationObjectivePtr obj, double weight);
OptimizationObjectivePtr objective;
double weight;
};
std::vector<Component> components_;
bool locked_;
// Friend functions for operator overloads for easy multiobjective creation
friend OptimizationObjectivePtr operator+(const OptimizationObjectivePtr &a,
const OptimizationObjectivePtr &b);
friend OptimizationObjectivePtr operator*(double weight, const OptimizationObjectivePtr &a);
friend OptimizationObjectivePtr operator*(const OptimizationObjectivePtr &a, double weight);
};
OptimizationObjectivePtr operator+(const OptimizationObjectivePtr &a, const OptimizationObjectivePtr &b);
OptimizationObjectivePtr operator*(double weight, const OptimizationObjectivePtr &a);
OptimizationObjectivePtr operator*(const OptimizationObjectivePtr &a, double weight);
} // namespace base
} // namespace ompl
#endif