Loading...
Searching...
No Matches
KoulesSetup.cpp
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2013, Rice University
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of the Rice University nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34
35/* Author: Beck Chen, Mark Moll */
36
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>
52
53namespace ob = ompl::base;
54namespace oc = ompl::control;
55
57class KoulesStateValidityChecker : public ompl::base::StateValidityChecker
58{
59public:
60 KoulesStateValidityChecker(const ompl::base::SpaceInformationPtr &si) : ompl::base::StateValidityChecker(si)
61 {
62 }
63
64 bool isValid(const ob::State *state) const override
65 {
66 return si_->satisfiesBounds(state);
67 }
68};
70
71ompl::control::DirectedControlSamplerPtr KoulesDirectedControlSamplerAllocator(
72 const ompl::control::SpaceInformation *si, const ompl::base::GoalPtr &goal, bool propagateMax)
73{
74 return std::make_shared<KoulesDirectedControlSampler>(si, goal, propagateMax);
75}
76
77KoulesSetup::KoulesSetup(unsigned int numKoules, const std::string &plannerName, const std::vector<double> &stateVec)
78 : ompl::control::SimpleSetup(std::make_shared<KoulesControlSpace>(numKoules))
79{
80 initialize(numKoules, plannerName, stateVec);
81}
82
83KoulesSetup::KoulesSetup(unsigned int numKoules, const std::string &plannerName, double kouleVel)
84 : ompl::control::SimpleSetup(std::make_shared<KoulesControlSpace>(numKoules))
85{
86 initialize(numKoules, plannerName);
87 double *state = getProblemDefinition()->getStartState(0)->as<KoulesStateSpace::StateType>()->values;
88 double theta;
89 ompl::RNG rng;
90 for (unsigned int i = 0; i < numKoules; ++i)
91 {
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);
95 }
96}
97
98void KoulesSetup::initialize(unsigned int numKoules, const std::string &plannerName,
99 const std::vector<double> &stateVec)
100{
101 const ob::StateSpacePtr &space = getStateSpace();
102 space->setup();
103 // setup start state
104 ob::ScopedState<> start(space);
105 if (stateVec.size() == space->getDimension())
106 space->copyFromReals(start.get(), stateVec);
107 else
108 {
109 // Pick koule positions evenly radially distributed, but at a linearly
110 // increasing distance from the center. The ship's initial position is
111 // at the center. Initial velocities are 0.
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)
118 {
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);
122 }
123 space->copyFromReals(start.get(), startVec);
124 }
125 setStartState(start);
126 // set goal
127 setGoal(std::make_shared<KoulesGoal>(si_));
128 // set propagation step size
129 si_->setPropagationStepSize(propagationStepSize);
130 // set min/max propagation steps
131 si_->setMinMaxControlDuration(propagationMinSteps, propagationMaxSteps);
132 // set directed control sampler; when using the PDST planner, propagate as long as possible
133 bool isPDST = plannerName == "pdst";
134 const ompl::base::GoalPtr &goal = getGoal();
135 si_->setDirectedControlSamplerAllocator([&goal, isPDST](const ompl::control::SpaceInformation *si)
136 { return KoulesDirectedControlSamplerAllocator(si, goal, isPDST); });
137 // set planner
138 setPlanner(getConfiguredPlannerInstance(plannerName));
139 // set validity checker
140 setStateValidityChecker(std::make_shared<KoulesStateValidityChecker>(si_));
141 // set state propagator
142 setStatePropagator(std::make_shared<KoulesStatePropagator>(si_));
143}
144
145ob::PlannerPtr KoulesSetup::getConfiguredPlannerInstance(const std::string &plannerName)
146{
147 if (plannerName == "rrt")
148 {
149 auto rrtplanner(std::make_shared<oc::RRT>(si_));
150 rrtplanner->setIntermediateStates(true);
151 return rrtplanner;
152 }
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")
158 {
159 auto sstplanner(std::make_shared<oc::SST>(si_));
160 sstplanner->setSelectionRadius(0.05);
161 sstplanner->setPruningRadius(0.001);
162 return sstplanner;
163 }
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()));
168
169 auto pdstplanner(std::make_shared<oc::PDST>(si_));
170 pdstplanner->setProjectionEvaluator(si_->getStateSpace()->getProjection("PDSTProjection"));
171 return pdstplanner;
172}
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.
Definition ScopedState.h:57
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....
Space information containing necessary information for planning with controls. setup() needs to be ca...
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...
Definition Control.h:45
Main namespace. Contains everything in this library.
STL namespace.