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 <ompl/base/spaces/RealVectorStateSpace.h>
44 #include <ompl/control/planners/rrt/RRT.h>
45 #include <ompl/control/planners/kpiece/KPIECE1.h>
46 #include <ompl/control/planners/est/EST.h>
47 #include <ompl/control/planners/pdst/PDST.h>
48 
49 namespace ob = ompl::base;
50 namespace oc = ompl::control;
51 
53 class KoulesStateValidityChecker : public ompl::base::StateValidityChecker
54 {
55 public:
56  KoulesStateValidityChecker(const ompl::base::SpaceInformationPtr &si) : ompl::base::StateValidityChecker(si)
57  {
58  }
59 
60  bool isValid(const ob::State *state) const override
61  {
62  return si_->satisfiesBounds(state);
63  }
64 };
66 
67 ompl::control::DirectedControlSamplerPtr KoulesDirectedControlSamplerAllocator(
68  const ompl::control::SpaceInformation *si, const ompl::base::GoalPtr &goal, bool propagateMax)
69 {
70  return std::make_shared<KoulesDirectedControlSampler>(si, goal, propagateMax);
71 }
72 
73 
74 KoulesSetup::KoulesSetup(unsigned int numKoules, const std::string& plannerName,
75  const std::vector<double>& stateVec)
76  : ompl::control::SimpleSetup(std::make_shared<KoulesControlSpace>(numKoules))
77 {
78  initialize(numKoules, plannerName, stateVec);
79 }
80 
81 KoulesSetup::KoulesSetup(unsigned int numKoules, const std::string& plannerName, double kouleVel)
82  : ompl::control::SimpleSetup(std::make_shared<KoulesControlSpace>(numKoules))
83 {
84  initialize(numKoules, plannerName);
85  double* state = getProblemDefinition()->getStartState(0)->as<KoulesStateSpace::StateType>()->values;
86  double theta;
87  ompl::RNG rng;
88  for (unsigned int i = 0; i < numKoules; ++i)
89  {
90  theta = rng.uniformReal(0., 2. * boost::math::constants::pi<double>());
91  state[4 * i + 7] = kouleVel * cos(theta);
92  state[4 * i + 8] = kouleVel * sin(theta);
93  }
94 }
95 
96 void KoulesSetup::initialize(unsigned int numKoules, const std::string& plannerName,
97  const std::vector<double>& stateVec)
98 {
99  const ob::StateSpacePtr& space = getStateSpace();
100  space->setup();
101  // setup start state
102  ob::ScopedState<> start(space);
103  if (stateVec.size() == space->getDimension())
104  space->copyFromReals(start.get(), stateVec);
105  else
106  {
107  // Pick koule positions evenly radially distributed, but at a linearly
108  // increasing distance from the center. The ship's initial position is
109  // at the center. Initial velocities are 0.
110  std::vector<double> startVec(space->getDimension(), 0.);
111  double r, theta = boost::math::constants::pi<double>(), delta = 2.*theta / numKoules;
112  startVec[0] = .5 * sideLength;
113  startVec[1] = .5 * sideLength;
114  startVec[4] = .5 * delta;
115  for (unsigned int i = 0; i < numKoules; ++i, theta += delta)
116  {
117  r = .1 + i * .1 / numKoules;
118  startVec[4 * i + 5] = .5 * sideLength + r * cos(theta);
119  startVec[4 * i + 6] = .5 * sideLength + r * sin(theta);
120  }
121  space->copyFromReals(start.get(), startVec);
122  }
123  setStartState(start);
124  // set goal
125  setGoal(std::make_shared<KoulesGoal>(si_));
126  // set propagation step size
127  si_->setPropagationStepSize(propagationStepSize);
128  // set min/max propagation steps
129  si_->setMinMaxControlDuration(propagationMinSteps, propagationMaxSteps);
130  // set directed control sampler; when using the PDST planner, propagate as long as possible
131  bool isPDST = plannerName == "pdst";
132  const ompl::base::GoalPtr& goal = getGoal();
133  si_->setDirectedControlSamplerAllocator(
134  [&goal, isPDST](const ompl::control::SpaceInformation *si)
135  {
136  return KoulesDirectedControlSamplerAllocator(si, goal, isPDST);
137  });
138  // set planner
139  setPlanner(getConfiguredPlannerInstance(plannerName));
140  // set validity checker
141  setStateValidityChecker(std::make_shared<KoulesStateValidityChecker>(si_));
142  // set state propagator
143  setStatePropagator(std::make_shared<KoulesStatePropagator>(si_));
144 }
145 
146 ob::PlannerPtr KoulesSetup::getConfiguredPlannerInstance(const std::string& plannerName)
147 {
148  if (plannerName == "rrt")
149  {
150  auto rrtplanner(std::make_shared<oc::RRT>(si_));
151  rrtplanner->setIntermediateStates(true);
152  return rrtplanner;
153  }
154  else if (plannerName == "est")
155  return std::make_shared<oc::EST>(si_);
156  else if (plannerName == "kpiece")
157  return std::make_shared<oc::KPIECE1>(si_);
158  else
159  {
160  auto pdstplanner(std::make_shared<oc::PDST>(si_));
161  pdstplanner->setProjectionEvaluator(
162  si_->getStateSpace()->getProjection("PDSTProjection"));
163  return pdstplanner;
164  }
165 }
Definition of a scoped state.
Definition: ScopedState.h:56
This namespace contains sampling based planning routines used by planning under differential constrai...
Definition: Control.h:44
A shared pointer wrapper for ompl::base::StateSpace.
STL namespace.
Main namespace. Contains everything in this library.
Definition: AppBase.h:21
A shared pointer wrapper for ompl::base::Planner.
Random number generation. An instance of this class cannot be used by multiple threads at once (membe...
Definition: RandomNumbers.h:58
A shared pointer wrapper for ompl::control::DirectedControlSampler.
Abstract definition for a class checking the validity of states. The implementation of this class mus...
double uniformReal(double lower_bound, double upper_bound)
Generate a random real within given bounds: [lower_bound, upper_bound)
Definition: RandomNumbers.h:74
A shared pointer wrapper for ompl::base::SpaceInformation.
Definition of an abstract state.
Definition: State.h:49
This namespace contains sampling based planning routines shared by both planning under geometric cons...
Definition: Cost.h:44
virtual bool isValid(const State *state) const =0
Return true if the state state is valid. Usually, this means at least collision checking. If it is possible that ompl::base::StateSpace::interpolate() or ompl::control::ControlSpace::propagate() return states that are outside of bounds, this function should also make a call to ompl::base::SpaceInformation::satisfiesBounds().
A shared pointer wrapper for ompl::base::Goal.
Space information containing necessary information for planning with controls. setup() needs to be ca...