Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
smoother.hpp
1 // Copyright (c) 2021 RoboTech Vision
2 // Copyright (c) 2020, Samsung Research America
3 //
4 // Licensed under the Apache License, Version 2.0 (the "License");
5 // you may not use this file except in compliance with the License.
6 // You may obtain a copy of the License at
7 //
8 // http://www.apache.org/licenses/LICENSE-2.0
9 //
10 // Unless required by applicable law or agreed to in writing, software
11 // distributed under the License is distributed on an "AS IS" BASIS,
12 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 // See the License for the specific language governing permissions and
14 // limitations under the License. Reserved.
15 
16 #ifndef NAV2_CONSTRAINED_SMOOTHER__SMOOTHER_HPP_
17 #define NAV2_CONSTRAINED_SMOOTHER__SMOOTHER_HPP_
18 
19 #include <cmath>
20 #include <vector>
21 #include <iostream>
22 #include <memory>
23 #include <queue>
24 #include <utility>
25 #include <deque>
26 #include <limits>
27 #include <algorithm>
28 
29 #include "nav2_constrained_smoother/smoother_cost_function.hpp"
30 #include "nav2_constrained_smoother/utils.hpp"
31 
32 #include "ceres/ceres.h"
33 #include "Eigen/Core"
34 
35 namespace nav2_constrained_smoother
36 {
37 
42 class Smoother
43 {
44 public:
48  Smoother() {}
49 
53  ~Smoother() {}
54 
59  void initialize(const OptimizerParams params)
60  {
61  debug_ = params.debug;
62 
63  options_.linear_solver_type = params.solver_types.at(params.linear_solver_type);
64 
65  options_.max_num_iterations = params.max_iterations;
66 
67  options_.function_tolerance = params.fn_tol;
68  options_.gradient_tolerance = params.gradient_tol;
69  options_.parameter_tolerance = params.param_tol;
70 
71  if (debug_) {
72  options_.minimizer_progress_to_stdout = true;
73  options_.logging_type = ceres::LoggingType::PER_MINIMIZER_ITERATION;
74  } else {
75  options_.logging_type = ceres::SILENT;
76  }
77  }
78 
88  bool smooth(
89  std::vector<Eigen::Vector3d> & path,
90  const Eigen::Vector2d & start_dir,
91  const Eigen::Vector2d & end_dir,
92  const nav2_costmap_2d::Costmap2D * costmap,
93  const SmootherParams & params)
94  {
95  // Path has always at least 2 points
96  if (path.size() < 2) {
97  throw std::runtime_error("Constrained smoother: Path must have at least 2 points");
98  }
99 
100  options_.max_solver_time_in_seconds = params.max_time;
101 
102  ceres::Problem problem;
103  std::vector<Eigen::Vector3d> path_optim;
104  std::vector<bool> optimized;
105  if (buildProblem(path, costmap, params, problem, path_optim, optimized)) {
106  // solve the problem
107  ceres::Solver::Summary summary;
108  ceres::Solve(options_, &problem, &summary);
109  if (debug_) {
110  RCLCPP_INFO(rclcpp::get_logger("smoother_server"), "%s", summary.FullReport().c_str());
111  }
112  if (!summary.IsSolutionUsable() || summary.initial_cost - summary.final_cost < 0.0) {
113  return false;
114  }
115  } else {
116  RCLCPP_INFO(rclcpp::get_logger("smoother_server"), "Path too short to optimize");
117  }
118 
119  upsampleAndPopulate(path_optim, optimized, start_dir, end_dir, params, path);
120 
121  return true;
122  }
123 
124 private:
135  bool buildProblem(
136  const std::vector<Eigen::Vector3d> & path,
137  const nav2_costmap_2d::Costmap2D * costmap,
138  const SmootherParams & params,
139  ceres::Problem & problem,
140  std::vector<Eigen::Vector3d> & path_optim,
141  std::vector<bool> & optimized)
142  {
143  // Create costmap grid
144  costmap_grid_ = std::make_shared<ceres::Grid2D<u_char>>(
145  costmap->getCharMap(), 0, costmap->getSizeInCellsY(), 0, costmap->getSizeInCellsX());
146  auto costmap_interpolator = std::make_shared<ceres::BiCubicInterpolator<ceres::Grid2D<u_char>>>(
147  *costmap_grid_);
148 
149  // Create residual blocks
150  const double cusp_half_length = params.cusp_zone_length / 2;
151  ceres::LossFunction * loss_function = NULL;
152  path_optim = path;
153  optimized = std::vector<bool>(path.size());
154  optimized[0] = true;
155  int prelast_i = -1;
156  int last_i = 0;
157  double last_direction = path_optim[0][2];
158  bool last_was_cusp = false;
159  bool last_is_reversing = false;
160  std::deque<std::pair<double, SmootherCostFunction *>> potential_cusp_funcs;
161  double last_segment_len = EPSILON;
162  double potential_cusp_funcs_len = 0;
163  double len_since_cusp = std::numeric_limits<double>::infinity();
164 
165  for (size_t i = 1; i < path_optim.size(); i++) {
166  auto & pt = path_optim[i];
167  bool is_cusp = false;
168  if (i != path_optim.size() - 1) {
169  is_cusp = pt[2] * last_direction < 0;
170  last_direction = pt[2];
171 
172  // skip to downsample if can be skipped (no forward/reverse direction change)
173  if (!is_cusp &&
174  i > (params.keep_start_orientation ? 1 : 0) &&
175  i < path_optim.size() - (params.keep_goal_orientation ? 2 : 1) &&
176  static_cast<int>(i - last_i) < params.path_downsampling_factor)
177  {
178  continue;
179  }
180  }
181 
182  // keep distance inequalities between poses
183  // (some might have been downsampled while others might not)
184  double current_segment_len = (path_optim[i] - path_optim[last_i]).block<2, 1>(0, 0).norm();
185 
186  // forget cost functions which don't have chance to be part of a cusp zone
187  potential_cusp_funcs_len += current_segment_len;
188  while (!potential_cusp_funcs.empty() && potential_cusp_funcs_len > cusp_half_length) {
189  potential_cusp_funcs_len -= potential_cusp_funcs.front().first;
190  potential_cusp_funcs.pop_front();
191  }
192 
193  // update cusp zone costmap weights
194  if (is_cusp) {
195  double len_to_cusp = current_segment_len;
196  for (int i = potential_cusp_funcs.size() - 1; i >= 0; i--) {
197  auto & f = potential_cusp_funcs[i];
198  double new_weight =
199  params.cusp_costmap_weight * (1.0 - len_to_cusp / cusp_half_length) +
200  params.costmap_weight * len_to_cusp / cusp_half_length;
201  if (std::abs(new_weight - params.cusp_costmap_weight) <
202  std::abs(f.second->getCostmapWeight() - params.cusp_costmap_weight))
203  {
204  f.second->setCostmapWeight(new_weight);
205  }
206  len_to_cusp += f.first;
207  }
208  potential_cusp_funcs_len = 0;
209  potential_cusp_funcs.clear();
210  len_since_cusp = 0;
211  }
212 
213  // add cost function
214  optimized[i] = true;
215  if (prelast_i != -1) {
216  double costmap_weight = params.costmap_weight;
217  if (len_since_cusp <= cusp_half_length) {
218  costmap_weight =
219  params.cusp_costmap_weight * (1.0 - len_since_cusp / cusp_half_length) +
220  params.costmap_weight * len_since_cusp / cusp_half_length;
221  }
222  SmootherCostFunction * cost_function = new SmootherCostFunction(
223  path[last_i].template block<2, 1>(
224  0,
225  0),
226  (last_was_cusp ? -1 : 1) * last_segment_len / current_segment_len,
227  last_is_reversing,
228  costmap,
229  costmap_interpolator,
230  params,
231  costmap_weight
232  );
233  problem.AddResidualBlock(
234  cost_function->AutoDiff(), loss_function,
235  path_optim[last_i].data(), pt.data(), path_optim[prelast_i].data());
236 
237  potential_cusp_funcs.emplace_back(current_segment_len, cost_function);
238  }
239 
240  // shift current to last and last to pre-last
241  last_was_cusp = is_cusp;
242  last_is_reversing = last_direction < 0;
243  prelast_i = last_i;
244  last_i = i;
245  len_since_cusp += current_segment_len;
246  last_segment_len = std::max(EPSILON, current_segment_len);
247  }
248 
249  int posesToOptimize = problem.NumParameterBlocks() - 2; // minus start and goal
250  if (params.keep_goal_orientation) {
251  posesToOptimize -= 1; // minus goal orientation holder
252  }
253  if (params.keep_start_orientation) {
254  posesToOptimize -= 1; // minus start orientation holder
255  }
256  if (posesToOptimize <= 0) {
257  return false; // nothing to optimize
258  }
259  // first two and last two points are constant (to keep start and end direction)
260  problem.SetParameterBlockConstant(path_optim.front().data());
261  if (params.keep_start_orientation) {
262  problem.SetParameterBlockConstant(path_optim[1].data());
263  }
264  if (params.keep_goal_orientation) {
265  problem.SetParameterBlockConstant(path_optim[path_optim.size() - 2].data());
266  }
267  problem.SetParameterBlockConstant(path_optim.back().data());
268  return true;
269  }
270 
280  void upsampleAndPopulate(
281  const std::vector<Eigen::Vector3d> & path_optim,
282  const std::vector<bool> & optimized,
283  const Eigen::Vector2d & start_dir,
284  const Eigen::Vector2d & end_dir,
285  const SmootherParams & params,
286  std::vector<Eigen::Vector3d> & path)
287  {
288  // Populate path, assign orientations, interpolate skipped/upsampled poses
289  path.clear();
290  if (params.path_upsampling_factor > 1) {
291  path.reserve(params.path_upsampling_factor * (path_optim.size() - 1) + 1);
292  }
293  int last_i = 0;
294  int prelast_i = -1;
295  Eigen::Vector2d prelast_dir;
296  for (int i = 1; i <= static_cast<int>(path_optim.size()); i++) {
297  if (i == static_cast<int>(path_optim.size()) || optimized[i]) {
298  if (prelast_i != -1) {
299  Eigen::Vector2d last_dir;
300  auto & prelast = path_optim[prelast_i];
301  auto & last = path_optim[last_i];
302 
303  // Compute orientation of last
304  if (i < static_cast<int>(path_optim.size())) {
305  auto & current = path_optim[i];
306  Eigen::Vector2d tangent_dir = tangentDir<double>(
307  prelast.block<2, 1>(0, 0),
308  last.block<2, 1>(0, 0),
309  current.block<2, 1>(0, 0),
310  prelast[2] * last[2] < 0);
311 
312  last_dir =
313  tangent_dir.dot((current - last).block<2, 1>(0, 0) * last[2]) >= 0 ?
314  tangent_dir :
315  -tangent_dir;
316  last_dir.normalize();
317  } else if (params.keep_goal_orientation) {
318  last_dir = end_dir;
319  } else {
320  last_dir = (last - prelast).block<2, 1>(0, 0) * last[2];
321  last_dir.normalize();
322  }
323  double last_angle = atan2(last_dir[1], last_dir[0]);
324 
325  // Interpolate poses between prelast and last
326  int interp_cnt = (last_i - prelast_i) * params.path_upsampling_factor - 1;
327  if (interp_cnt > 0) {
328  Eigen::Vector2d last_pt = last.block<2, 1>(0, 0);
329  Eigen::Vector2d prelast_pt = prelast.block<2, 1>(0, 0);
330  double dist = (last_pt - prelast_pt).norm();
331  Eigen::Vector2d pt1 = prelast_pt + prelast_dir * dist * 0.4 * prelast[2];
332  Eigen::Vector2d pt2 = last_pt - last_dir * dist * 0.4 * prelast[2];
333  for (int j = 1; j <= interp_cnt; j++) {
334  double interp = j / static_cast<double>(interp_cnt + 1);
335  Eigen::Vector2d pt = cubicBezier(prelast_pt, pt1, pt2, last_pt, interp);
336  path.emplace_back(pt[0], pt[1], 0.0);
337  }
338  }
339  path.emplace_back(last[0], last[1], last_angle);
340 
341  // Assign orientations to interpolated points
342  for (size_t j = path.size() - 1 - interp_cnt; j < path.size() - 1; j++) {
343  Eigen::Vector2d tangent_dir = tangentDir<double>(
344  path[j - 1].block<2, 1>(0, 0),
345  path[j].block<2, 1>(0, 0),
346  path[j + 1].block<2, 1>(0, 0),
347  false);
348  tangent_dir =
349  tangent_dir.dot((path[j + 1] - path[j]).block<2, 1>(0, 0) * prelast[2]) >= 0 ?
350  tangent_dir :
351  -tangent_dir;
352  path[j][2] = atan2(tangent_dir[1], tangent_dir[0]);
353  }
354 
355  prelast_dir = last_dir;
356  } else { // start pose
357  auto & start = path_optim[0];
358  Eigen::Vector2d dir = params.keep_start_orientation ?
359  start_dir :
360  ((path_optim[i] - start).block<2, 1>(0, 0) * start[2]).normalized();
361  path.emplace_back(start[0], start[1], atan2(dir[1], dir[0]));
362  prelast_dir = dir;
363  }
364  prelast_i = last_i;
365  last_i = i;
366  }
367  }
368  }
369 
370  /*
371  Piecewise cubic bezier curve as defined by Adobe in Postscript
372  The two end points are pt0 and pt3
373  Their associated control points are pt1 and pt2
374  */
375  static Eigen::Vector2d cubicBezier(
376  Eigen::Vector2d & pt0, Eigen::Vector2d & pt1,
377  Eigen::Vector2d & pt2, Eigen::Vector2d & pt3, double mu)
378  {
379  Eigen::Vector2d a, b, c, pt;
380 
381  c[0] = 3 * (pt1[0] - pt0[0]);
382  c[1] = 3 * (pt1[1] - pt0[1]);
383  b[0] = 3 * (pt2[0] - pt1[0]) - c[0];
384  b[1] = 3 * (pt2[1] - pt1[1]) - c[1];
385  a[0] = pt3[0] - pt0[0] - c[0] - b[0];
386  a[1] = pt3[1] - pt0[1] - c[1] - b[1];
387 
388  pt[0] = a[0] * mu * mu * mu + b[0] * mu * mu + c[0] * mu + pt0[0];
389  pt[1] = a[1] * mu * mu * mu + b[1] * mu * mu + c[1] * mu + pt0[1];
390 
391  return pt;
392  }
393 
394  bool debug_;
395  ceres::Solver::Options options_;
396  std::shared_ptr<ceres::Grid2D<u_char>> costmap_grid_;
397 };
398 
399 } // namespace nav2_constrained_smoother
400 
401 #endif // NAV2_CONSTRAINED_SMOOTHER__SMOOTHER_HPP_
Smoother()
A constructor for nav2_smac_planner::Smoother.
Definition: smoother.hpp:48
bool smooth(std::vector< Eigen::Vector3d > &path, const Eigen::Vector2d &start_dir, const Eigen::Vector2d &end_dir, const nav2_costmap_2d::Costmap2D *costmap, const SmootherParams &params)
Smoother method.
Definition: smoother.hpp:88
void initialize(const OptimizerParams params)
Initialization of the smoother.
Definition: smoother.hpp:59
~Smoother()
A destructor for nav2_smac_planner::Smoother.
Definition: smoother.hpp:53
A 2D costmap provides a mapping between points in the world and their associated "costs".
Definition: costmap_2d.hpp:68
unsigned char * getCharMap() const
Will return a pointer to the underlying unsigned char array used as the costmap.
Definition: costmap_2d.cpp:261
unsigned int getSizeInCellsX() const
Accessor for the x size of the costmap in cells.
Definition: costmap_2d.cpp:501
unsigned int getSizeInCellsY() const
Accessor for the y size of the costmap in cells.
Definition: costmap_2d.cpp:506