37#include "KoulesSetup.h"
38#include "KoulesGoal.h"
39#include "KoulesStateSpace.h"
40#include "KoulesControlSpace.h"
41#include "KoulesStatePropagator.h"
42#include "KoulesDirectedControlSampler.h"
43#include "KoulesDecomposition.h"
44#include <ompl/base/spaces/RealVectorStateSpace.h>
45#include <ompl/control/planners/rrt/RRT.h>
46#include <ompl/control/planners/kpiece/KPIECE1.h>
47#include <ompl/control/planners/est/EST.h>
48#include <ompl/control/planners/pdst/PDST.h>
49#include <ompl/control/planners/sst/SST.h>
50#include <ompl/control/planners/syclop/SyclopRRT.h>
51#include <ompl/control/planners/syclop/SyclopEST.h>
60 KoulesStateValidityChecker(
const ompl::base::SpaceInformationPtr &si) : ompl::base::StateValidityChecker(si)
64 bool isValid(
const ob::State *state)
const override
66 return si_->satisfiesBounds(state);
71ompl::control::DirectedControlSamplerPtr KoulesDirectedControlSamplerAllocator(
74 return std::make_shared<KoulesDirectedControlSampler>(si, goal, propagateMax);
77KoulesSetup::KoulesSetup(
unsigned int numKoules,
const std::string &plannerName,
const std::vector<double> &stateVec)
80 initialize(numKoules, plannerName, stateVec);
83KoulesSetup::KoulesSetup(
unsigned int numKoules,
const std::string &plannerName,
double kouleVel)
86 initialize(numKoules, plannerName);
87 double *state = getProblemDefinition()->getStartState(0)->as<KoulesStateSpace::StateType>()->values;
90 for (
unsigned int i = 0; i < numKoules; ++i)
92 theta = rng.
uniformReal(0., 2. * boost::math::constants::pi<double>());
93 state[4 * i + 7] = kouleVel * cos(theta);
94 state[4 * i + 8] = kouleVel * sin(theta);
98void KoulesSetup::initialize(
unsigned int numKoules,
const std::string &plannerName,
99 const std::vector<double> &stateVec)
101 const ob::StateSpacePtr &space = getStateSpace();
105 if (stateVec.size() == space->getDimension())
106 space->copyFromReals(start.get(), stateVec);
112 std::vector<double> startVec(space->getDimension(), 0.);
113 double r, theta = boost::math::constants::pi<double>(), delta = 2. * theta / numKoules;
114 startVec[0] = .5 * sideLength;
115 startVec[1] = .5 * sideLength;
116 startVec[4] = .5 * delta;
117 for (
unsigned int i = 0; i < numKoules; ++i, theta += delta)
119 r = .1 + i * .1 / numKoules;
120 startVec[4 * i + 5] = .5 * sideLength + r * cos(theta);
121 startVec[4 * i + 6] = .5 * sideLength + r * sin(theta);
123 space->copyFromReals(start.get(), startVec);
125 setStartState(start);
127 setGoal(std::make_shared<KoulesGoal>(si_));
129 si_->setPropagationStepSize(propagationStepSize);
131 si_->setMinMaxControlDuration(propagationMinSteps, propagationMaxSteps);
133 bool isPDST = plannerName ==
"pdst";
134 const ompl::base::GoalPtr &goal = getGoal();
136 {
return KoulesDirectedControlSamplerAllocator(si, goal, isPDST); });
138 setPlanner(getConfiguredPlannerInstance(plannerName));
140 setStateValidityChecker(std::make_shared<KoulesStateValidityChecker>(si_));
142 setStatePropagator(std::make_shared<KoulesStatePropagator>(si_));
145ob::PlannerPtr KoulesSetup::getConfiguredPlannerInstance(
const std::string &plannerName)
147 if (plannerName ==
"rrt")
149 auto rrtplanner(std::make_shared<oc::RRT>(si_));
150 rrtplanner->setIntermediateStates(
true);
153 if (plannerName ==
"est")
154 return std::make_shared<oc::EST>(si_);
155 if (plannerName ==
"kpiece")
156 return std::make_shared<oc::KPIECE1>(si_);
157 if (plannerName ==
"sst")
159 auto sstplanner(std::make_shared<oc::SST>(si_));
160 sstplanner->setSelectionRadius(0.05);
161 sstplanner->setPruningRadius(0.001);
164 if (plannerName ==
"sycloprrt")
165 return std::make_shared<oc::SyclopRRT>(si_, std::make_shared<KoulesDecomposition>(getStateSpace()));
166 if (plannerName ==
"syclopest")
167 return std::make_shared<oc::SyclopEST>(si_, std::make_shared<KoulesDecomposition>(getStateSpace()));
169 auto pdstplanner(std::make_shared<oc::PDST>(si_));
170 pdstplanner->setProjectionEvaluator(si_->getStateSpace()->getProjection(
"PDSTProjection"));
Random number generation. An instance of this class cannot be used by multiple threads at once (membe...
double uniformReal(double lower_bound, double upper_bound)
Generate a random real within given bounds: [lower_bound, upper_bound).
Definition of a scoped state.
Abstract definition for a class checking the validity of states. The implementation of this class mus...
virtual bool isValid(const State *state) const =0
Return true if the state state is valid. Usually, this means at least collision checking....
This namespace contains sampling based planning routines shared by both planning under geometric cons...
This namespace contains sampling based planning routines used by planning under differential constrai...
Main namespace. Contains everything in this library.