37 #ifndef OMPL_BASE_PLANNER_
38 #define OMPL_BASE_PLANNER_
40 #include "ompl/base/SpaceInformation.h"
41 #include "ompl/base/ProblemDefinition.h"
42 #include "ompl/base/PlannerData.h"
43 #include "ompl/base/PlannerStatus.h"
44 #include "ompl/base/PlannerTerminationCondition.h"
45 #include "ompl/base/GenericParam.h"
47 #include "ompl/util/Time.h"
48 #include "ompl/util/ClassForward.h"
49 #include <boost/function.hpp>
50 #include <boost/concept_check.hpp>
51 #include <boost/noncopyable.hpp>
52 #include <boost/lexical_cast.hpp>
182 return addedStartStates_;
188 return sampledGoalsCount_;
195 unsigned int addedStartStates_;
196 unsigned int sampledGoalsCount_;
250 BOOST_CONCEPT_ASSERT((boost::Convertible<T*, Planner*>));
252 return static_cast<T*
>(
this);
257 const T*
as(
void)
const
260 BOOST_CONCEPT_ASSERT((boost::Convertible<T*, Planner*>));
262 return static_cast<const T*
>(
this);
306 virtual void clear(
void);
317 const std::string&
getName(
void)
const;
320 void setName(
const std::string &name);
329 virtual void setup(
void);
361 template<
typename T,
typename PlannerType,
typename SetterType,
typename GetterType>
362 void declareParam(
const std::string &name,
const PlannerType &planner,
const SetterType& setter,
const GetterType& getter)
364 params_.
declareParam<T>(name, boost::bind(setter, planner, _1), boost::bind(getter, planner));
368 template<
typename T,
typename PlannerType,
typename SetterType>
369 void declareParam(
const std::string &name,
const PlannerType &planner,
const SetterType& setter)