00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #ifndef OMPL_BASE_PROBLEM_DEFINITION_
00038 #define OMPL_BASE_PROBLEM_DEFINITION_
00039
00040 #include "ompl/base/State.h"
00041 #include "ompl/base/Goal.h"
00042 #include "ompl/base/SpaceInformation.h"
00043 #include "ompl/util/Console.h"
00044 #include "ompl/util/ClassForward.h"
00045 #include "ompl/base/ScopedState.h"
00046
00047 #include <vector>
00048 #include <cstdlib>
00049 #include <iostream>
00050 #include <limits>
00051
00052 #include <boost/noncopyable.hpp>
00053
00054 namespace ompl
00055 {
00056 namespace base
00057 {
00058
00060 ClassForward(ProblemDefinition);
00061
00067 class ProblemDefinition : private boost::noncopyable
00068 {
00069 public:
00070
00072 ProblemDefinition(const SpaceInformationPtr &si) : si_(si)
00073 {
00074 }
00075
00076 virtual ~ProblemDefinition(void)
00077 {
00078 clearStartStates();
00079 }
00080
00082 void addStartState(const State *state)
00083 {
00084 startStates_.push_back(si_->cloneState(state));
00085 }
00086
00088 void addStartState(const ScopedState<> &state)
00089 {
00090 startStates_.push_back(si_->cloneState(state.get()));
00091 }
00092
00096 bool hasStartState(const State *state, unsigned int *startIndex = NULL);
00097
00099 void clearStartStates(void)
00100 {
00101 for (unsigned int i = 0 ; i < startStates_.size() ; ++i)
00102 si_->freeState(startStates_[i]);
00103 startStates_.clear();
00104 }
00105
00107 unsigned int getStartStateCount(void) const
00108 {
00109 return startStates_.size();
00110 }
00111
00113 const State* getStartState(unsigned int index) const
00114 {
00115 return startStates_[index];
00116 }
00117
00119 State* getStartState(unsigned int index)
00120 {
00121 return startStates_[index];
00122 }
00123
00125 void setGoal(const GoalPtr &goal)
00126 {
00127 goal_ = goal;
00128 }
00129
00131 void clearGoal(void)
00132 {
00133 goal_.reset();
00134 }
00135
00137 const GoalPtr& getGoal(void) const
00138 {
00139 return goal_;
00140 }
00141
00146 void getInputStates(std::vector<const State*> &states) const;
00147
00155 void setStartAndGoalStates(const State *start, const State *goal, const double threshold = std::numeric_limits<double>::epsilon());
00156
00158 void setGoalState(const State *goal, const double threshold = std::numeric_limits<double>::epsilon());
00159
00161 void setStartAndGoalStates(const ScopedState<> &start, const ScopedState<> &goal, const double threshold = std::numeric_limits<double>::epsilon())
00162 {
00163 setStartAndGoalStates(start.get(), goal.get(), threshold);
00164 }
00165
00167 void setGoalState(const ScopedState<> &goal, const double threshold = std::numeric_limits<double>::epsilon())
00168 {
00169 setGoalState(goal.get(), threshold);
00170 }
00171
00177 bool isTrivial(unsigned int *startIndex = NULL, double *distance = NULL) const;
00178
00183 bool fixInvalidInputStates(double distStart, double distGoal, unsigned int attempts);
00184
00186 void print(std::ostream &out = std::cout) const;
00187
00188 protected:
00189
00191 bool fixInvalidInputState(State *state, double dist, bool start, unsigned int attempts);
00192
00194 SpaceInformationPtr si_;
00195
00197 std::vector<State*> startStates_;
00198
00200 GoalPtr goal_;
00201
00203 msg::Interface msg_;
00204 };
00205 }
00206 }
00207
00208 #endif