Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
motion_models.hpp
1 // Copyright (c) 2022 Samsung Research America, @artofnothingness Alexey Budyakov
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #ifndef NAV2_MPPI_CONTROLLER__MOTION_MODELS_HPP_
16 #define NAV2_MPPI_CONTROLLER__MOTION_MODELS_HPP_
17 
18 #include <cstdint>
19 #include <string>
20 
21 #include "nav2_mppi_controller/models/control_sequence.hpp"
22 #include "nav2_mppi_controller/models/state.hpp"
23 #include <xtensor/xmath.hpp>
24 #include <xtensor/xmasked_view.hpp>
25 #include <xtensor/xview.hpp>
26 #include <xtensor/xnoalias.hpp>
27 
28 #include "nav2_mppi_controller/tools/parameters_handler.hpp"
29 
30 namespace mppi
31 {
32 
38 {
39 public:
43  MotionModel() = default;
44 
48  virtual ~MotionModel() = default;
49 
54  virtual void predict(models::State & state)
55  {
56  using namespace xt::placeholders; // NOLINT
57  xt::noalias(xt::view(state.vx, xt::all(), xt::range(1, _))) =
58  xt::view(state.cvx, xt::all(), xt::range(0, -1));
59 
60  xt::noalias(xt::view(state.wz, xt::all(), xt::range(1, _))) =
61  xt::view(state.cwz, xt::all(), xt::range(0, -1));
62 
63  if (isHolonomic()) {
64  xt::noalias(xt::view(state.vy, xt::all(), xt::range(1, _))) =
65  xt::view(state.cvy, xt::all(), xt::range(0, -1));
66  }
67  }
68 
73  virtual bool isHolonomic() = 0;
74 
79  virtual void applyConstraints(models::ControlSequence & /*control_sequence*/) {}
80 };
81 
87 {
88 public:
92  explicit AckermannMotionModel(ParametersHandler * param_handler, const std::string & name)
93  {
94  auto getParam = param_handler->getParamGetter(name + ".AckermannConstraints");
95  getParam(min_turning_r_, "min_turning_r", 0.2);
96  }
97 
102  bool isHolonomic() override
103  {
104  return false;
105  }
106 
111  void applyConstraints(models::ControlSequence & control_sequence) override
112  {
113  auto & vx = control_sequence.vx;
114  auto & wz = control_sequence.wz;
115 
116  auto view = xt::masked_view(wz, (xt::fabs(vx) / xt::fabs(wz)) < min_turning_r_);
117  view = xt::sign(wz) * xt::fabs(vx) / min_turning_r_;
118  }
119 
124  float getMinTurningRadius() {return min_turning_r_;}
125 
126 private:
127  float min_turning_r_{0};
128 };
129 
135 {
136 public:
140  DiffDriveMotionModel() = default;
141 
146  bool isHolonomic() override
147  {
148  return false;
149  }
150 };
151 
157 {
158 public:
162  OmniMotionModel() = default;
163 
168  bool isHolonomic() override
169  {
170  return true;
171  }
172 };
173 
174 } // namespace mppi
175 
176 #endif // NAV2_MPPI_CONTROLLER__MOTION_MODELS_HPP_
Ackermann motion model.
float getMinTurningRadius()
Get minimum turning radius of ackermann drive.
void applyConstraints(models::ControlSequence &control_sequence) override
Apply hard vehicle constraints to a control sequence.
bool isHolonomic() override
Whether the motion model is holonomic, using Y axis.
AckermannMotionModel(ParametersHandler *param_handler, const std::string &name)
Constructor for mppi::AckermannMotionModel.
Differential drive motion model.
DiffDriveMotionModel()=default
Constructor for mppi::DiffDriveMotionModel.
bool isHolonomic() override
Whether the motion model is holonomic, using Y axis.
Abstract motion model for modeling a vehicle.
virtual void predict(models::State &state)
With input velocities, find the vehicle's output velocities.
virtual void applyConstraints(models::ControlSequence &)
Apply hard vehicle constraints to a control sequence.
MotionModel()=default
Constructor for mppi::MotionModel.
virtual bool isHolonomic()=0
Whether the motion model is holonomic, using Y axis.
virtual ~MotionModel()=default
Destructor for mppi::MotionModel.
Omnidirectional motion model.
OmniMotionModel()=default
Constructor for mppi::OmniMotionModel.
bool isHolonomic() override
Whether the motion model is holonomic, using Y axis.
Handles getting parameters and dynamic parmaeter changes.
auto getParamGetter(const std::string &ns)
Get an object to retreive parameters.
A control sequence over time (e.g. trajectory)
State information: velocities, controls, poses, speed.
Definition: state.hpp:31