Nav2 Navigation Stack - kilted  kilted
ROS 2 Navigation Stack
smoother_cost_function.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_COST_FUNCTION_HPP_
17 #define NAV2_CONSTRAINED_SMOOTHER__SMOOTHER_COST_FUNCTION_HPP_
18 
19 #include <cmath>
20 #include <vector>
21 #include <iostream>
22 #include <unordered_map>
23 #include <memory>
24 #include <queue>
25 #include <utility>
26 
27 #include "ceres/ceres.h"
28 #include "ceres/cubic_interpolation.h"
29 #include "Eigen/Core"
30 #include "nav2_costmap_2d/costmap_2d.hpp"
31 #include "nav2_constrained_smoother/options.hpp"
32 #include "nav2_constrained_smoother/utils.hpp"
33 
34 namespace nav2_constrained_smoother
35 {
36 
43 {
44 public:
56  const Eigen::Vector2d & original_pos,
57  double next_to_last_length_ratio,
58  bool reversing,
59  const nav2_costmap_2d::Costmap2D * costmap,
60  const std::shared_ptr<ceres::BiCubicInterpolator<ceres::Grid2D<unsigned char>>> &
61  costmap_interpolator,
62  const SmootherParams & params,
63  double costmap_weight)
64  : original_pos_(original_pos),
65  next_to_last_length_ratio_(next_to_last_length_ratio),
66  reversing_(reversing),
67  params_(params),
68  costmap_weight_(costmap_weight),
69  costmap_origin_(costmap->getOriginX(), costmap->getOriginY()),
70  costmap_resolution_(costmap->getResolution()),
71  costmap_interpolator_(costmap_interpolator)
72  {
73  }
74 
75  ceres::CostFunction * AutoDiff()
76  {
77  return new ceres::AutoDiffCostFunction<SmootherCostFunction, 4, 2, 2, 2>(this);
78  }
79 
80  void setCostmapWeight(double costmap_weight)
81  {
82  costmap_weight_ = costmap_weight;
83  }
84 
85  double getCostmapWeight()
86  {
87  return costmap_weight_;
88  }
89 
98  template<typename T>
99  bool operator()(
100  const T * const pt, const T * const pt_next, const T * const pt_prev,
101  T * pt_residual) const
102  {
103  Eigen::Map<const Eigen::Matrix<T, 2, 1>> xi(pt);
104  Eigen::Map<const Eigen::Matrix<T, 2, 1>> xi_next(pt_next);
105  Eigen::Map<const Eigen::Matrix<T, 2, 1>> xi_prev(pt_prev);
106  Eigen::Map<Eigen::Matrix<T, 4, 1>> residual(pt_residual);
107  residual.setZero();
108 
109  // compute cost
110  addSmoothingResidual<T>(params_.smooth_weight, xi, xi_next, xi_prev, residual[0]);
111  addCurvatureResidual<T>(params_.curvature_weight, xi, xi_next, xi_prev, residual[1]);
112  addDistanceResidual<T>(
113  params_.distance_weight, xi,
114  original_pos_.template cast<T>(), residual[2]);
115  addCostResidual<T>(costmap_weight_, xi, xi_next, xi_prev, residual[3]);
116 
117  return true;
118  }
119 
120 protected:
129  template<typename T>
130  inline void addSmoothingResidual(
131  const double & weight,
132  const Eigen::Matrix<T, 2, 1> & pt,
133  const Eigen::Matrix<T, 2, 1> & pt_next,
134  const Eigen::Matrix<T, 2, 1> & pt_prev,
135  T & r) const
136  {
137  Eigen::Matrix<T, 2, 1> d_next = pt_next - pt;
138  Eigen::Matrix<T, 2, 1> d_prev = pt - pt_prev;
139  Eigen::Matrix<T, 2, 1> d_diff = next_to_last_length_ratio_ * d_next - d_prev;
140  r += (T)weight * d_diff.dot(d_diff); // objective function value
141  }
142 
152  template<typename T>
153  inline void addCurvatureResidual(
154  const double & weight,
155  const Eigen::Matrix<T, 2, 1> & pt,
156  const Eigen::Matrix<T, 2, 1> & pt_next,
157  const Eigen::Matrix<T, 2, 1> & pt_prev,
158  T & r) const
159  {
160  Eigen::Matrix<T, 2, 1> center = arcCenter(
161  pt_prev, pt, pt_next,
162  next_to_last_length_ratio_ < 0);
163  if (CERES_ISINF(center[0])) {
164  return;
165  }
166  T turning_rad = (pt - center).norm();
167  T ki_minus_kmax = (T)1.0 / turning_rad - params_.max_curvature;
168 
169  if (ki_minus_kmax <= (T)EPSILON) {
170  return;
171  }
172 
173  r += (T)weight * ki_minus_kmax * ki_minus_kmax; // objective function value
174  }
175 
183  template<typename T>
184  inline void addDistanceResidual(
185  const double & weight,
186  const Eigen::Matrix<T, 2, 1> & xi,
187  const Eigen::Matrix<T, 2, 1> & xi_original,
188  T & r) const
189  {
190  r += (T)weight * (xi - xi_original).squaredNorm(); // objective function value
191  }
192 
200  template<typename T>
201  inline void addCostResidual(
202  const double & weight,
203  const Eigen::Matrix<T, 2, 1> & pt,
204  const Eigen::Matrix<T, 2, 1> & pt_next,
205  const Eigen::Matrix<T, 2, 1> & pt_prev,
206  T & r) const
207  {
208  if (params_.cost_check_points.empty()) {
209  Eigen::Matrix<T, 2, 1> interp_pos =
210  (pt - costmap_origin_.template cast<T>()) / (T)costmap_resolution_;
211  T value;
212  costmap_interpolator_->Evaluate(interp_pos[1] - (T)0.5, interp_pos[0] - (T)0.5, &value);
213  r += (T)weight * value * value; // objective function value
214  } else {
215  Eigen::Matrix<T, 2, 1> dir = tangentDir(
216  pt_prev, pt, pt_next,
217  next_to_last_length_ratio_ < 0);
218  dir.normalize();
219  if (((pt_next - pt).dot(dir) < (T)0) != reversing_) {
220  dir = -dir;
221  }
222  Eigen::Matrix<T, 3, 3> transform;
223  transform << dir[0], -dir[1], pt[0],
224  dir[1], dir[0], pt[1],
225  (T)0, (T)0, (T)1;
226  for (size_t i = 0; i < params_.cost_check_points.size(); i += 3) {
227  Eigen::Matrix<T, 3, 1> ccpt((T)params_.cost_check_points[i],
228  (T)params_.cost_check_points[i + 1], (T)1);
229  auto ccpt_world = (transform * ccpt).template block<2, 1>(0, 0);
230  Eigen::Matrix<T, 2,
231  1> interp_pos = (ccpt_world - costmap_origin_.template cast<T>()) /
232  (T)costmap_resolution_;
233  T value;
234  costmap_interpolator_->Evaluate(interp_pos[1] - (T)0.5, interp_pos[0] - (T)0.5, &value);
235 
236  r += (T)weight * (T)params_.cost_check_points[i + 2] * value * value;
237  }
238  }
239  }
240 
241  const Eigen::Vector2d original_pos_;
242  double next_to_last_length_ratio_;
243  bool reversing_;
244  SmootherParams params_;
245  double costmap_weight_;
246  Eigen::Vector2d costmap_origin_;
247  double costmap_resolution_;
248  std::shared_ptr<ceres::BiCubicInterpolator<ceres::Grid2D<unsigned char>>> costmap_interpolator_;
249 };
250 
251 } // namespace nav2_constrained_smoother
252 
253 #endif // NAV2_CONSTRAINED_SMOOTHER__SMOOTHER_COST_FUNCTION_HPP_
Cost function for path smoothing with multiple terms including curvature, smoothness,...
bool operator()(const T *const pt, const T *const pt_next, const T *const pt_prev, T *pt_residual) const
Smoother cost function evaluation.
SmootherCostFunction(const Eigen::Vector2d &original_pos, double next_to_last_length_ratio, bool reversing, const nav2_costmap_2d::Costmap2D *costmap, const std::shared_ptr< ceres::BiCubicInterpolator< ceres::Grid2D< unsigned char >>> &costmap_interpolator, const SmootherParams &params, double costmap_weight)
A constructor for nav2_constrained_smoother::SmootherCostFunction.
void addCostResidual(const double &weight, const Eigen::Matrix< T, 2, 1 > &pt, const Eigen::Matrix< T, 2, 1 > &pt_next, const Eigen::Matrix< T, 2, 1 > &pt_prev, T &r) const
Cost function term for steering away from costs.
void addCurvatureResidual(const double &weight, const Eigen::Matrix< T, 2, 1 > &pt, const Eigen::Matrix< T, 2, 1 > &pt_next, const Eigen::Matrix< T, 2, 1 > &pt_prev, T &r) const
Cost function term for maximum curved paths.
void addDistanceResidual(const double &weight, const Eigen::Matrix< T, 2, 1 > &xi, const Eigen::Matrix< T, 2, 1 > &xi_original, T &r) const
Cost function derivative term for steering away changes in pose.
void addSmoothingResidual(const double &weight, const Eigen::Matrix< T, 2, 1 > &pt, const Eigen::Matrix< T, 2, 1 > &pt_next, const Eigen::Matrix< T, 2, 1 > &pt_prev, T &r) const
Cost function term for smooth paths.
A 2D costmap provides a mapping between points in the world and their associated "costs".
Definition: costmap_2d.hpp:69