Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
optimizer.cpp
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 #include "nav2_mppi_controller/optimizer.hpp"
16 
17 #include <limits>
18 #include <memory>
19 #include <stdexcept>
20 #include <string>
21 #include <vector>
22 #include <cmath>
23 #include <xtensor/xmath.hpp>
24 #include <xtensor/xrandom.hpp>
25 #include <xtensor/xnoalias.hpp>
26 
27 #include "nav2_costmap_2d/costmap_filters/filter_values.hpp"
28 
29 namespace mppi
30 {
31 
32 using namespace xt::placeholders; // NOLINT
33 using xt::evaluation_strategy::immediate;
34 
36  rclcpp_lifecycle::LifecycleNode::WeakPtr parent, const std::string & name,
37  std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros,
38  ParametersHandler * param_handler)
39 {
40  parent_ = parent;
41  name_ = name;
42  costmap_ros_ = costmap_ros;
43  costmap_ = costmap_ros_->getCostmap();
44  parameters_handler_ = param_handler;
45 
46  auto node = parent_.lock();
47  logger_ = node->get_logger();
48 
49  getParams();
50 
51  critic_manager_.on_configure(parent_, name_, costmap_ros_, parameters_handler_);
52  noise_generator_.initialize(settings_, isHolonomic(), name_, parameters_handler_);
53 
54  reset();
55 }
56 
58 {
59  noise_generator_.shutdown();
60 }
61 
63 {
64  std::string motion_model_name;
65 
66  auto & s = settings_;
67  auto getParam = parameters_handler_->getParamGetter(name_);
68  auto getParentParam = parameters_handler_->getParamGetter("");
69  getParam(s.model_dt, "model_dt", 0.05f);
70  getParam(s.time_steps, "time_steps", 56);
71  getParam(s.batch_size, "batch_size", 1000);
72  getParam(s.iteration_count, "iteration_count", 1);
73  getParam(s.temperature, "temperature", 0.3f);
74  getParam(s.gamma, "gamma", 0.015f);
75  getParam(s.base_constraints.vx_max, "vx_max", 0.5);
76  getParam(s.base_constraints.vx_min, "vx_min", -0.35);
77  getParam(s.base_constraints.vy, "vy_max", 0.5);
78  getParam(s.base_constraints.wz, "wz_max", 1.9);
79  getParam(s.sampling_std.vx, "vx_std", 0.2);
80  getParam(s.sampling_std.vy, "vy_std", 0.2);
81  getParam(s.sampling_std.wz, "wz_std", 0.4);
82  getParam(s.retry_attempt_limit, "retry_attempt_limit", 1);
83 
84  getParam(motion_model_name, "motion_model", std::string("DiffDrive"));
85 
86  s.constraints = s.base_constraints;
87  setMotionModel(motion_model_name);
88  parameters_handler_->addPostCallback([this]() {reset();});
89 
90  double controller_frequency;
91  getParentParam(controller_frequency, "controller_frequency", 0.0, ParameterType::Static);
92  setOffset(controller_frequency);
93 }
94 
95 void Optimizer::setOffset(double controller_frequency)
96 {
97  const double controller_period = 1.0 / controller_frequency;
98  constexpr double eps = 1e-6;
99 
100  if ((controller_period + eps) < settings_.model_dt) {
101  RCLCPP_WARN(
102  logger_,
103  "Controller period is less then model dt, consider setting it equal");
104  } else if (abs(controller_period - settings_.model_dt) < eps) {
105  RCLCPP_INFO(
106  logger_,
107  "Controller period is equal to model dt. Control sequence "
108  "shifting is ON");
109  settings_.shift_control_sequence = true;
110  } else {
111  throw std::runtime_error(
112  "Controller period more then model dt, set it equal to model dt");
113  }
114 }
115 
117 {
118  state_.reset(settings_.batch_size, settings_.time_steps);
119  control_sequence_.reset(settings_.time_steps);
120  control_history_[0] = {0.0, 0.0, 0.0};
121  control_history_[1] = {0.0, 0.0, 0.0};
122  control_history_[2] = {0.0, 0.0, 0.0};
123  control_history_[3] = {0.0, 0.0, 0.0};
124 
125  settings_.constraints = settings_.base_constraints;
126 
127  costs_ = xt::zeros<float>({settings_.batch_size});
128  generated_trajectories_.reset(settings_.batch_size, settings_.time_steps);
129 
130  noise_generator_.reset(settings_, isHolonomic());
131  RCLCPP_INFO(logger_, "Optimizer reset");
132 }
133 
134 geometry_msgs::msg::TwistStamped Optimizer::evalControl(
135  const geometry_msgs::msg::PoseStamped & robot_pose,
136  const geometry_msgs::msg::Twist & robot_speed,
137  const nav_msgs::msg::Path & plan,
138  const geometry_msgs::msg::Pose & goal,
139  nav2_core::GoalChecker * goal_checker)
140 {
141  prepare(robot_pose, robot_speed, plan, goal, goal_checker);
142 
143  do {
144  optimize();
145  } while (fallback(critics_data_.fail_flag));
146 
147  utils::savitskyGolayFilter(control_sequence_, control_history_, settings_);
148  auto control = getControlFromSequenceAsTwist(plan.header.stamp);
149 
150  if (settings_.shift_control_sequence) {
151  shiftControlSequence();
152  }
153 
154  return control;
155 }
156 
158 {
159  for (size_t i = 0; i < settings_.iteration_count; ++i) {
160  generateNoisedTrajectories();
161  critic_manager_.evalTrajectoriesScores(critics_data_);
162  updateControlSequence();
163  }
164 }
165 
166 bool Optimizer::fallback(bool fail)
167 {
168  static size_t counter = 0;
169 
170  if (!fail) {
171  counter = 0;
172  return false;
173  }
174 
175  reset();
176 
177  if (++counter > settings_.retry_attempt_limit) {
178  counter = 0;
179  throw std::runtime_error("Optimizer fail to compute path");
180  }
181 
182  return true;
183 }
184 
186  const geometry_msgs::msg::PoseStamped & robot_pose,
187  const geometry_msgs::msg::Twist & robot_speed,
188  const nav_msgs::msg::Path & plan,
189  const geometry_msgs::msg::Pose & goal,
190  nav2_core::GoalChecker * goal_checker)
191 {
192  state_.pose = robot_pose;
193  state_.speed = robot_speed;
194  path_ = utils::toTensor(plan);
195  goal_ = goal;
196 
197  costs_.fill(0);
198 
199  critics_data_.fail_flag = false;
200  critics_data_.goal_checker = goal_checker;
201  critics_data_.motion_model = motion_model_;
202  critics_data_.furthest_reached_path_point.reset();
203  critics_data_.path_pts_valid.reset();
204 }
205 
207 {
208  using namespace xt::placeholders; // NOLINT
209  control_sequence_.vx = xt::roll(control_sequence_.vx, -1);
210  control_sequence_.wz = xt::roll(control_sequence_.wz, -1);
211 
212 
213  xt::view(control_sequence_.vx, -1) =
214  xt::view(control_sequence_.vx, -2);
215 
216  xt::view(control_sequence_.wz, -1) =
217  xt::view(control_sequence_.wz, -2);
218 
219 
220  if (isHolonomic()) {
221  control_sequence_.vy = xt::roll(control_sequence_.vy, -1);
222  xt::view(control_sequence_.vy, -1) =
223  xt::view(control_sequence_.vy, -2);
224  }
225 }
226 
228 {
229  noise_generator_.setNoisedControls(state_, control_sequence_);
230  noise_generator_.generateNextNoises();
231  updateStateVelocities(state_);
232  integrateStateVelocities(generated_trajectories_, state_);
233 }
234 
235 bool Optimizer::isHolonomic() const {return motion_model_->isHolonomic();}
236 
238 {
239  auto & s = settings_;
240 
241  if (isHolonomic()) {
242  control_sequence_.vy = xt::clip(control_sequence_.vy, -s.constraints.vy, s.constraints.vy);
243  }
244 
245  control_sequence_.vx = xt::clip(control_sequence_.vx, s.constraints.vx_min, s.constraints.vx_max);
246  control_sequence_.wz = xt::clip(control_sequence_.wz, -s.constraints.wz, s.constraints.wz);
247 
248  motion_model_->applyConstraints(control_sequence_);
249 }
250 
252  models::State & state) const
253 {
254  updateInitialStateVelocities(state);
255  propagateStateVelocitiesFromInitials(state);
256 }
257 
259  models::State & state) const
260 {
261  xt::noalias(xt::view(state.vx, xt::all(), 0)) = state.speed.linear.x;
262  xt::noalias(xt::view(state.wz, xt::all(), 0)) = state.speed.angular.z;
263 
264  if (isHolonomic()) {
265  xt::noalias(xt::view(state.vy, xt::all(), 0)) = state.speed.linear.y;
266  }
267 }
268 
270  models::State & state) const
271 {
272  motion_model_->predict(state);
273 }
274 
276  xt::xtensor<float, 2> & trajectory,
277  const xt::xtensor<float, 2> & sequence) const
278 {
279  float initial_yaw = tf2::getYaw(state_.pose.pose.orientation);
280 
281  const auto vx = xt::view(sequence, xt::all(), 0);
282  const auto vy = xt::view(sequence, xt::all(), 2);
283  const auto wz = xt::view(sequence, xt::all(), 1);
284 
285  auto traj_x = xt::view(trajectory, xt::all(), 0);
286  auto traj_y = xt::view(trajectory, xt::all(), 1);
287  auto traj_yaws = xt::view(trajectory, xt::all(), 2);
288 
289  xt::noalias(traj_yaws) = xt::cumsum(wz * settings_.model_dt, 0) + initial_yaw;
290 
291  auto && yaw_cos = xt::xtensor<float, 1>::from_shape(traj_yaws.shape());
292  auto && yaw_sin = xt::xtensor<float, 1>::from_shape(traj_yaws.shape());
293 
294  const auto yaw_offseted = xt::view(traj_yaws, xt::range(1, _));
295 
296  xt::noalias(xt::view(yaw_cos, 0)) = cosf(initial_yaw);
297  xt::noalias(xt::view(yaw_sin, 0)) = sinf(initial_yaw);
298  xt::noalias(xt::view(yaw_cos, xt::range(1, _))) = xt::cos(yaw_offseted);
299  xt::noalias(xt::view(yaw_sin, xt::range(1, _))) = xt::sin(yaw_offseted);
300 
301  auto && dx = xt::eval(vx * yaw_cos);
302  auto && dy = xt::eval(vx * yaw_sin);
303 
304  if (isHolonomic()) {
305  dx = dx - vy * yaw_sin;
306  dy = dy + vy * yaw_cos;
307  }
308 
309  xt::noalias(traj_x) = state_.pose.pose.position.x + xt::cumsum(dx * settings_.model_dt, 0);
310  xt::noalias(traj_y) = state_.pose.pose.position.y + xt::cumsum(dy * settings_.model_dt, 0);
311 }
312 
314  models::Trajectories & trajectories,
315  const models::State & state) const
316 {
317  const float initial_yaw = tf2::getYaw(state.pose.pose.orientation);
318 
319  xt::noalias(trajectories.yaws) =
320  xt::cumsum(state.wz * settings_.model_dt, 1) + initial_yaw;
321 
322  const auto yaws_cutted = xt::view(trajectories.yaws, xt::all(), xt::range(0, -1));
323 
324  auto && yaw_cos = xt::xtensor<float, 2>::from_shape(trajectories.yaws.shape());
325  auto && yaw_sin = xt::xtensor<float, 2>::from_shape(trajectories.yaws.shape());
326  xt::noalias(xt::view(yaw_cos, xt::all(), 0)) = cosf(initial_yaw);
327  xt::noalias(xt::view(yaw_sin, xt::all(), 0)) = sinf(initial_yaw);
328  xt::noalias(xt::view(yaw_cos, xt::all(), xt::range(1, _))) = xt::cos(yaws_cutted);
329  xt::noalias(xt::view(yaw_sin, xt::all(), xt::range(1, _))) = xt::sin(yaws_cutted);
330 
331  auto && dx = xt::eval(state.vx * yaw_cos);
332  auto && dy = xt::eval(state.vx * yaw_sin);
333 
334  if (isHolonomic()) {
335  dx = dx - state.vy * yaw_sin;
336  dy = dy + state.vy * yaw_cos;
337  }
338 
339  xt::noalias(trajectories.x) = state.pose.pose.position.x +
340  xt::cumsum(dx * settings_.model_dt, 1);
341  xt::noalias(trajectories.y) = state.pose.pose.position.y +
342  xt::cumsum(dy * settings_.model_dt, 1);
343 }
344 
345 xt::xtensor<float, 2> Optimizer::getOptimizedTrajectory()
346 {
347  auto && sequence =
348  xt::xtensor<float, 2>::from_shape({settings_.time_steps, isHolonomic() ? 3u : 2u});
349  auto && trajectories = xt::xtensor<float, 2>::from_shape({settings_.time_steps, 3});
350 
351  xt::noalias(xt::view(sequence, xt::all(), 0)) = control_sequence_.vx;
352  xt::noalias(xt::view(sequence, xt::all(), 1)) = control_sequence_.wz;
353 
354  if (isHolonomic()) {
355  xt::noalias(xt::view(sequence, xt::all(), 2)) = control_sequence_.vy;
356  }
357 
358  integrateStateVelocities(trajectories, sequence);
359  return std::move(trajectories);
360 }
361 
363 {
364  auto & s = settings_;
365  auto bounded_noises_vx = state_.cvx - control_sequence_.vx;
366  auto bounded_noises_wz = state_.cwz - control_sequence_.wz;
367  xt::noalias(costs_) +=
368  s.gamma / powf(s.sampling_std.vx, 2) * xt::sum(
369  xt::view(control_sequence_.vx, xt::newaxis(), xt::all()) * bounded_noises_vx, 1, immediate);
370  xt::noalias(costs_) +=
371  s.gamma / powf(s.sampling_std.wz, 2) * xt::sum(
372  xt::view(control_sequence_.wz, xt::newaxis(), xt::all()) * bounded_noises_wz, 1, immediate);
373 
374  if (isHolonomic()) {
375  auto bounded_noises_vy = state_.cvy - control_sequence_.vy;
376  xt::noalias(costs_) +=
377  s.gamma / powf(s.sampling_std.vy, 2) * xt::sum(
378  xt::view(control_sequence_.vy, xt::newaxis(), xt::all()) * bounded_noises_vy,
379  1, immediate);
380  }
381 
382  auto && costs_normalized = costs_ - xt::amin(costs_, immediate);
383  auto && exponents = xt::eval(xt::exp(-1 / settings_.temperature * costs_normalized));
384  auto && softmaxes = xt::eval(exponents / xt::sum(exponents, immediate));
385  auto && softmaxes_extened = xt::eval(xt::view(softmaxes, xt::all(), xt::newaxis()));
386 
387  xt::noalias(control_sequence_.vx) = xt::sum(state_.cvx * softmaxes_extened, 0, immediate);
388  xt::noalias(control_sequence_.wz) = xt::sum(state_.cwz * softmaxes_extened, 0, immediate);
389  if (isHolonomic()) {
390  xt::noalias(control_sequence_.vy) = xt::sum(state_.cvy * softmaxes_extened, 0, immediate);
391  }
392 
393  applyControlSequenceConstraints();
394 }
395 
396 geometry_msgs::msg::TwistStamped Optimizer::getControlFromSequenceAsTwist(
397  const builtin_interfaces::msg::Time & stamp)
398 {
399  unsigned int offset = settings_.shift_control_sequence ? 1 : 0;
400 
401  auto vx = control_sequence_.vx(offset);
402  auto wz = control_sequence_.wz(offset);
403 
404  if (isHolonomic()) {
405  auto vy = control_sequence_.vy(offset);
406  return utils::toTwistStamped(vx, vy, wz, stamp, costmap_ros_->getBaseFrameID());
407  }
408 
409  return utils::toTwistStamped(vx, wz, stamp, costmap_ros_->getBaseFrameID());
410 }
411 
412 void Optimizer::setMotionModel(const std::string & model)
413 {
414  if (model == "DiffDrive") {
415  motion_model_ = std::make_shared<DiffDriveMotionModel>();
416  } else if (model == "Omni") {
417  motion_model_ = std::make_shared<OmniMotionModel>();
418  } else if (model == "Ackermann") {
419  motion_model_ = std::make_shared<AckermannMotionModel>(parameters_handler_, name_);
420  } else {
421  throw std::runtime_error(
422  std::string(
423  "Model " + model + " is not valid! Valid options are DiffDrive, Omni, "
424  "or Ackermann"));
425  }
426 }
427 
428 void Optimizer::setSpeedLimit(double speed_limit, bool percentage)
429 {
430  auto & s = settings_;
431  if (speed_limit == nav2_costmap_2d::NO_SPEED_LIMIT) {
432  s.constraints.vx_max = s.base_constraints.vx_max;
433  s.constraints.vx_min = s.base_constraints.vx_min;
434  s.constraints.vy = s.base_constraints.vy;
435  s.constraints.wz = s.base_constraints.wz;
436  } else {
437  if (percentage) {
438  // Speed limit is expressed in % from maximum speed of robot
439  double ratio = speed_limit / 100.0;
440  s.constraints.vx_max = s.base_constraints.vx_max * ratio;
441  s.constraints.vx_min = s.base_constraints.vx_min * ratio;
442  s.constraints.vy = s.base_constraints.vy * ratio;
443  s.constraints.wz = s.base_constraints.wz * ratio;
444  } else {
445  // Speed limit is expressed in absolute value
446  double ratio = speed_limit / s.base_constraints.vx_max;
447  s.constraints.vx_max = s.base_constraints.vx_max * ratio;
448  s.constraints.vx_min = s.base_constraints.vx_min * ratio;
449  s.constraints.vy = s.base_constraints.vy * ratio;
450  s.constraints.wz = s.base_constraints.wz * ratio;
451  }
452  }
453 }
454 
456 {
457  return generated_trajectories_;
458 }
459 
460 } // namespace mppi
geometry_msgs::msg::TwistStamped evalControl(const geometry_msgs::msg::PoseStamped &robot_pose, const geometry_msgs::msg::Twist &robot_speed, const nav_msgs::msg::Path &plan, const geometry_msgs::msg::Pose &goal, nav2_core::GoalChecker *goal_checker)
Compute control using MPPI algorithm.
Definition: optimizer.cpp:134
void updateStateVelocities(models::State &state) const
Update velocities in state.
Definition: optimizer.cpp:251
void setMotionModel(const std::string &model)
Set the motion model of the vehicle platform.
Definition: optimizer.cpp:412
void setOffset(double controller_frequency)
Using control frequence and time step size, determine if trajectory offset should be used to populate...
Definition: optimizer.cpp:95
void prepare(const geometry_msgs::msg::PoseStamped &robot_pose, const geometry_msgs::msg::Twist &robot_speed, const nav_msgs::msg::Path &plan, const geometry_msgs::msg::Pose &goal, nav2_core::GoalChecker *goal_checker)
Prepare state information on new request for trajectory rollouts.
Definition: optimizer.cpp:185
void integrateStateVelocities(models::Trajectories &trajectories, const models::State &state) const
Rollout velocities in state to poses.
Definition: optimizer.cpp:313
void updateControlSequence()
Update control sequence with state controls weighted by costs using softmax function.
Definition: optimizer.cpp:362
void generateNoisedTrajectories()
updates generated trajectories with noised trajectories from the last cycle's optimal control
Definition: optimizer.cpp:227
bool fallback(bool fail)
Perform fallback behavior to try to recover from a set of trajectories in collision.
Definition: optimizer.cpp:166
bool isHolonomic() const
Whether the motion model is holonomic.
Definition: optimizer.cpp:235
models::Trajectories & getGeneratedTrajectories()
Get the trajectories generated in a cycle for visualization.
Definition: optimizer.cpp:455
void updateInitialStateVelocities(models::State &state) const
Update initial velocity in state.
Definition: optimizer.cpp:258
xt::xtensor< float, 2 > getOptimizedTrajectory()
Get the optimal trajectory for a cycle for visualization.
Definition: optimizer.cpp:345
void shutdown()
Shutdown for optimizer at process end.
Definition: optimizer.cpp:57
void optimize()
Main function to generate, score, and return trajectories.
Definition: optimizer.cpp:157
void reset()
Reset the optimization problem to initial conditions.
Definition: optimizer.cpp:116
void setSpeedLimit(double speed_limit, bool percentage)
Set the maximum speed based on the speed limits callback.
Definition: optimizer.cpp:428
void shiftControlSequence()
Shift the optimal control sequence after processing for next iterations initial conditions after exec...
Definition: optimizer.cpp:206
void applyControlSequenceConstraints()
Apply hard vehicle constraints on control sequence.
Definition: optimizer.cpp:237
void getParams()
Obtain the main controller's parameters.
Definition: optimizer.cpp:62
void propagateStateVelocitiesFromInitials(models::State &state) const
predict velocities in state using model for time horizon equal to timesteps
Definition: optimizer.cpp:269
void initialize(rclcpp_lifecycle::LifecycleNode::WeakPtr parent, const std::string &name, std::shared_ptr< nav2_costmap_2d::Costmap2DROS > costmap_ros, ParametersHandler *dynamic_parameters_handler)
Initializes optimizer on startup.
Definition: optimizer.cpp:35
geometry_msgs::msg::TwistStamped getControlFromSequenceAsTwist(const builtin_interfaces::msg::Time &stamp)
Convert control sequence to a twist commant.
Definition: optimizer.cpp:396
Handles getting parameters and dynamic parmaeter changes.
Function-object for checking whether a goal has been reached.
State information: velocities, controls, poses, speed.
Definition: state.hpp:31
Candidate Trajectories.