Program Listing for File ProblemDefinition.h
↰ Return to documentation for file (src/ompl/base/ProblemDefinition.h
)
/*********************************************************************
* Software License Agreement (BSD License)
*
* Copyright (c) 2010, Rice University
* 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 Rice University 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: Ioan Sucan */
#ifndef OMPL_BASE_PROBLEM_DEFINITION_
#define OMPL_BASE_PROBLEM_DEFINITION_
#include "ompl/base/State.h"
#include "ompl/base/Goal.h"
#include "ompl/base/Path.h"
#include "ompl/base/Cost.h"
#include "ompl/base/SpaceInformation.h"
#include "ompl/base/SolutionNonExistenceProof.h"
#include "ompl/util/Console.h"
#include "ompl/util/ClassForward.h"
#include "ompl/base/ScopedState.h"
#include <vector>
#include <cstdlib>
#include <iostream>
#include <limits>
namespace ompl
{
namespace base
{
OMPL_CLASS_FORWARD(ProblemDefinition);
OMPL_CLASS_FORWARD(OptimizationObjective);
struct PlannerSolution
{
PlannerSolution(const PathPtr &path)
: path_(path)
, length_(path ? path->length() : std::numeric_limits<double>::infinity())
{
}
bool operator==(const PlannerSolution &p) const
{
return path_ == p.path_;
}
bool operator<(const PlannerSolution &b) const;
void setApproximate(double difference)
{
approximate_ = true;
difference_ = difference;
}
void setOptimized(const OptimizationObjectivePtr &opt, Cost cost, bool meetsObjective)
{
opt_ = opt;
cost_ = cost;
optimized_ = meetsObjective;
}
void setPlannerName(const std::string &name)
{
plannerName_ = name;
}
int index_{-1};
PathPtr path_;
double length_;
bool approximate_{false};
double difference_{0.};
bool optimized_{false};
OptimizationObjectivePtr opt_;
Cost cost_;
std::string plannerName_;
};
class Planner;
using ReportIntermediateSolutionFn =
std::function<void(const Planner *, const std::vector<const base::State *> &, const Cost)>;
OMPL_CLASS_FORWARD(OptimizationObjective);
class ProblemDefinition
{
public:
// non-copyable
ProblemDefinition(const ProblemDefinition &) = delete;
ProblemDefinition &operator=(const ProblemDefinition &) = delete;
ProblemDefinition(SpaceInformationPtr si);
ProblemDefinitionPtr clone() const;
virtual ~ProblemDefinition()
{
clearStartStates();
}
const SpaceInformationPtr &getSpaceInformation() const
{
return si_;
}
void addStartState(const State *state)
{
startStates_.push_back(si_->cloneState(state));
}
void addStartState(const ScopedState<> &state)
{
startStates_.push_back(si_->cloneState(state.get()));
}
bool hasStartState(const State *state, unsigned int *startIndex = nullptr) const;
void clearStartStates()
{
for (auto &startState : startStates_)
si_->freeState(startState);
startStates_.clear();
}
unsigned int getStartStateCount() const
{
return startStates_.size();
}
const State *getStartState(unsigned int index) const
{
return startStates_[index];
}
State *getStartState(unsigned int index)
{
return startStates_[index];
}
void setGoal(const GoalPtr &goal)
{
goal_ = goal;
}
void clearGoal()
{
goal_.reset();
}
const GoalPtr &getGoal() const
{
return goal_;
}
void getInputStates(std::vector<const State *> &states) const;
void setStartAndGoalStates(const State *start, const State *goal,
double threshold = std::numeric_limits<double>::epsilon());
void setGoalState(const State *goal, double threshold = std::numeric_limits<double>::epsilon());
void setStartAndGoalStates(const ScopedState<> &start, const ScopedState<> &goal,
const double threshold = std::numeric_limits<double>::epsilon())
{
setStartAndGoalStates(start.get(), goal.get(), threshold);
}
void setGoalState(const ScopedState<> &goal,
const double threshold = std::numeric_limits<double>::epsilon())
{
setGoalState(goal.get(), threshold);
}
bool hasOptimizationObjective() const
{
return optimizationObjective_ != nullptr;
}
const OptimizationObjectivePtr &getOptimizationObjective() const
{
return optimizationObjective_;
}
void setOptimizationObjective(const OptimizationObjectivePtr &optimizationObjective)
{
optimizationObjective_ = optimizationObjective;
}
const ReportIntermediateSolutionFn &getIntermediateSolutionCallback() const
{
return intermediateSolutionCallback_;
}
void setIntermediateSolutionCallback(const ReportIntermediateSolutionFn &callback)
{
intermediateSolutionCallback_ = callback;
}
bool isTrivial(unsigned int *startIndex = nullptr, double *distance = nullptr) const;
PathPtr isStraightLinePathValid() const;
bool fixInvalidInputStates(double distStart, double distGoal, unsigned int attempts);
bool hasSolution() const;
bool hasExactSolution() const
{
return this->hasSolution() && !this->hasApproximateSolution();
}
bool hasApproximateSolution() const;
double getSolutionDifference() const;
bool hasOptimizedSolution() const;
PathPtr getSolutionPath() const;
bool getSolution(PlannerSolution &solution) const;
void addSolutionPath(const PathPtr &path, bool approximate = false, double difference = -1.0,
const std::string &plannerName = "Unknown") const;
void addSolutionPath(const PlannerSolution &sol) const;
std::size_t getSolutionCount() const;
std::vector<PlannerSolution> getSolutions() const;
void clearSolutionPaths() const;
bool hasSolutionNonExistenceProof() const;
void clearSolutionNonExistenceProof();
const SolutionNonExistenceProofPtr &getSolutionNonExistenceProof() const;
void setSolutionNonExistenceProof(const SolutionNonExistenceProofPtr &nonExistenceProof);
void print(std::ostream &out = std::cout) const;
protected:
bool fixInvalidInputState(State *state, double dist, bool start, unsigned int attempts);
SpaceInformationPtr si_;
std::vector<State *> startStates_;
GoalPtr goal_;
SolutionNonExistenceProofPtr nonExistenceProof_;
OptimizationObjectivePtr optimizationObjective_;
ReportIntermediateSolutionFn intermediateSolutionCallback_;
private:
OMPL_CLASS_FORWARD(PlannerSolutionSet);
PlannerSolutionSetPtr solutions_;
};
}
}
#endif