Exotica
ompl_control_solver.h
Go to the documentation of this file.
1 //
2 // Copyright (c) 2019, University of Edinburgh
3 // All rights reserved.
4 //
5 // Redistribution and use in source and binary forms, with or without
6 // modification, are permitted provided that the following conditions are met:
7 //
8 // * Redistributions of source code must retain the above copyright notice,
9 // this list of conditions and the following disclaimer.
10 // * Redistributions in binary form must reproduce the above copyright
11 // notice, this list of conditions and the following disclaimer in the
12 // documentation and/or other materials provided with the distribution.
13 // * Neither the name of nor the names of its contributors may be used to
14 // endorse or promote products derived from this software without specific
15 // prior written permission.
16 //
17 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20 // ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21 // LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22 // CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23 // SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24 // INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25 // CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26 // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27 // POSSIBILITY OF SUCH DAMAGE.
28 //
29 
30 #ifndef EXOTICA_OMPL_CONTROL_SOLVER_OMPL_CONTROL_SOLVER_H_
31 #define EXOTICA_OMPL_CONTROL_SOLVER_OMPL_CONTROL_SOLVER_H_
32 
33 // #include <exotica_core/feedback_motion_solver.h>
36 
37 #include <exotica_ompl_control_solver/ompl_control_solver_initializer.h>
38 
39 // TODO: Remove unused includes
40 #include <ompl/base/goals/GoalState.h>
41 #include <ompl/base/spaces/SE2StateSpace.h>
42 #include <ompl/control/SimpleSetup.h>
43 #include <ompl/control/SpaceInformation.h>
44 #include <ompl/control/spaces/RealVectorControlSpace.h>
45 
46 namespace ob = ompl::base;
47 namespace oc = ompl::control;
48 
49 typedef std::function<ob::PlannerPtr(const oc::SpaceInformationPtr &si)> ConfiguredPlannerAllocator;
50 
51 namespace exotica
52 {
53 class OMPLStatePropagator : public oc::StatePropagator
54 {
55 public:
57  oc::SpaceInformationPtr si,
59  void propagate(
60  const ob::State *state,
61  const oc::Control *control,
62  const double duration,
63  ob::State *result) const override
64  {
65  double t = 0;
66  space_->copyState(result, state);
67 
68  while (t < duration)
69  {
70  Integrate(result, control, timeStep_);
71  t += timeStep_;
72  }
73  }
74 
75  void setIntegrationTimeStep(double timeStep)
76  {
77  timeStep_ = timeStep;
78  }
79 
80  double getIntegrationTimeStep() const
81  {
82  return timeStep_;
83  }
84 
85 private:
86  double timeStep_ = 0.0;
87  oc::SpaceInformationPtr space_;
89 
90  void Integrate(ob::State *ob_x, const oc::Control *oc_u, double dt) const
91  {
92  const int NU = dynamics_solver_->get_num_controls();
93  const int NX = dynamics_solver_->get_num_positions() + dynamics_solver_->get_num_velocities();
94 
95  double *x = ob_x->as<ob::RealVectorStateSpace::StateType>()->values;
96  double *u = oc_u->as<oc::RealVectorControlSpace::ControlType>()->values;
97 
98  Eigen::VectorXd eig_x = Eigen::Map<Eigen::VectorXd>(x, NX);
99  Eigen::VectorXd eig_u = Eigen::Map<Eigen::VectorXd>(u, NU);
100 
101  Eigen::VectorXd x_new = dynamics_solver_->Simulate(eig_x, eig_u, dt);
102  std::memcpy(x, x_new.data(), NX * sizeof(double));
103  }
104 };
105 
107 {
108 public:
111  void Solve(Eigen::MatrixXd &solution) override;
112 
116  void SpecifyProblem(PlanningProblemPtr pointer) override;
117 
118 protected:
119  template <typename PlannerType>
120  static ob::PlannerPtr AllocatePlanner(const oc::SpaceInformationPtr &si)
121  {
122  ob::PlannerPtr planner(new PlannerType(si));
123  return planner;
124  }
125 
128 
129  OMPLControlSolverInitializer init_;
130 
131  std::unique_ptr<oc::SimpleSetup> setup_;
132  std::string algorithm_;
134 
135  void Setup();
136 
137  bool isStateValid(const oc::SpaceInformationPtr si, const ob::State *state)
138  {
139  return true;
140  }
141 };
142 
143 } // namespace exotica
144 
145 #endif // EXOTICA_OMPL_CONTROL_SOLVER_OMPL_CONTROL_SOLVER_H_
dynamic_time_indexed_shooting_problem.h
exotica::OMPLControlSolver::isStateValid
bool isStateValid(const oc::SpaceInformationPtr si, const ob::State *state)
Definition: ompl_control_solver.h:137
exotica::OMPLStatePropagator::propagate
void propagate(const ob::State *state, const oc::Control *control, const double duration, ob::State *result) const override
Definition: ompl_control_solver.h:59
exotica::OMPLControlSolver::Setup
void Setup()
exotica::OMPLStatePropagator::Integrate
void Integrate(ob::State *ob_x, const oc::Control *oc_u, double dt) const
Definition: ompl_control_solver.h:90
exotica::OMPLControlSolver::dynamics_solver_
DynamicsSolverPtr dynamics_solver_
!< Shared pointer to the planning problem.
Definition: ompl_control_solver.h:127
exotica::OMPLStatePropagator::OMPLStatePropagator
OMPLStatePropagator(oc::SpaceInformationPtr si, DynamicsSolverPtr dynamics_solver_)
Definition: ompl_control_solver.h:56
exotica::OMPLStatePropagator::timeStep_
double timeStep_
Definition: ompl_control_solver.h:86
exotica::OMPLControlSolver::planner_allocator_
ConfiguredPlannerAllocator planner_allocator_
Definition: ompl_control_solver.h:133
exotica::OMPLStatePropagator::setIntegrationTimeStep
void setIntegrationTimeStep(double timeStep)
Definition: ompl_control_solver.h:75
exotica::OMPLStatePropagator::space_
oc::SpaceInformationPtr space_
Definition: ompl_control_solver.h:87
exotica::OMPLControlSolver
Definition: ompl_control_solver.h:106
exotica::DynamicsSolverPtr
std::shared_ptr< exotica::DynamicsSolver > DynamicsSolverPtr
Definition: dynamics_solver.h:269
exotica
Definition: cartpole_dynamics_solver.h:38
exotica::OMPLControlSolver::algorithm_
std::string algorithm_
Definition: ompl_control_solver.h:132
exotica::OMPLControlSolver::Solve
void Solve(Eigen::MatrixXd &solution) override
Solves the problem.
exotica::ConfiguredPlannerAllocator
boost::function< ompl::base::PlannerPtr(const ompl::base::SpaceInformationPtr &si, const std::string &name)> ConfiguredPlannerAllocator
Definition: time_indexed_rrt_connect.h:104
exotica::OMPLControlSolver::SpecifyProblem
void SpecifyProblem(PlanningProblemPtr pointer) override
Binds the solver to a specific problem which must be pre-initalised.
exotica::DynamicTimeIndexedShootingProblemPtr
std::shared_ptr< exotica::DynamicTimeIndexedShootingProblem > DynamicTimeIndexedShootingProblemPtr
Definition: dynamic_time_indexed_shooting_problem.h:231
exotica::OMPLStatePropagator::dynamics_solver_
DynamicsSolverPtr dynamics_solver_
Definition: ompl_control_solver.h:88
motion_solver.h
exotica::OMPLStatePropagator::getIntegrationTimeStep
double getIntegrationTimeStep() const
Definition: ompl_control_solver.h:80
exotica::MotionSolver
Definition: motion_solver.h:42
exotica::PlanningProblemPtr
std::shared_ptr< PlanningProblem > PlanningProblemPtr
Definition: planning_problem.h:116
exotica::OMPLControlSolver::setup_
std::unique_ptr< oc::SimpleSetup > setup_
Definition: ompl_control_solver.h:131
exotica::OMPLControlSolver::AllocatePlanner
static ob::PlannerPtr AllocatePlanner(const oc::SpaceInformationPtr &si)
Definition: ompl_control_solver.h:120
exotica::OMPLControlSolver::prob_
DynamicTimeIndexedShootingProblemPtr prob_
Definition: ompl_control_solver.h:126
ConfiguredPlannerAllocator
std::function< ob::PlannerPtr(const oc::SpaceInformationPtr &si)> ConfiguredPlannerAllocator
Definition: ompl_control_solver.h:49
exotica::OMPLStatePropagator
Definition: ompl_control_solver.h:53
exotica::OMPLControlSolver::init_
OMPLControlSolverInitializer init_
!< Shared pointer to the dynamics solver.
Definition: ompl_control_solver.h:129