16 #ifndef NAV2_CONSTRAINED_SMOOTHER__SMOOTHER_COST_FUNCTION_HPP_
17 #define NAV2_CONSTRAINED_SMOOTHER__SMOOTHER_COST_FUNCTION_HPP_
22 #include <unordered_map>
27 #include "ceres/ceres.h"
28 #include "ceres/cubic_interpolation.h"
30 #include "nav2_costmap_2d/costmap_2d.hpp"
31 #include "nav2_constrained_smoother/options.hpp"
32 #include "nav2_constrained_smoother/utils.hpp"
34 namespace nav2_constrained_smoother
56 const Eigen::Vector2d & original_pos,
57 double next_to_last_length_ratio,
60 const std::shared_ptr<ceres::BiCubicInterpolator<ceres::Grid2D<unsigned char>>> &
63 double costmap_weight)
64 : original_pos_(original_pos),
65 next_to_last_length_ratio_(next_to_last_length_ratio),
66 reversing_(reversing),
68 costmap_weight_(costmap_weight),
69 costmap_origin_(costmap->getOriginX(), costmap->getOriginY()),
70 costmap_resolution_(costmap->getResolution()),
71 costmap_interpolator_(costmap_interpolator)
75 ceres::CostFunction * AutoDiff()
77 return new ceres::AutoDiffCostFunction<SmootherCostFunction, 4, 2, 2, 2>(
this);
80 void setCostmapWeight(
double costmap_weight)
82 costmap_weight_ = costmap_weight;
85 double getCostmapWeight()
87 return costmap_weight_;
100 const T *
const pt,
const T *
const pt_next,
const T *
const pt_prev,
101 T * pt_residual)
const
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);
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]);
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,
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);
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,
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])) {
166 T turning_rad = (pt - center).norm();
167 T ki_minus_kmax = (T)1.0 / turning_rad - params_.max_curvature;
169 if (ki_minus_kmax <= (T)EPSILON) {
173 r += (T)weight * ki_minus_kmax * ki_minus_kmax;
185 const double & weight,
186 const Eigen::Matrix<T, 2, 1> & xi,
187 const Eigen::Matrix<T, 2, 1> & xi_original,
190 r += (T)weight * (xi - xi_original).squaredNorm();
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,
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_;
212 costmap_interpolator_->Evaluate(interp_pos[1] - (T)0.5, interp_pos[0] - (T)0.5, &value);
213 r += (T)weight * value * value;
215 Eigen::Matrix<T, 2, 1> dir = tangentDir(
216 pt_prev, pt, pt_next,
217 next_to_last_length_ratio_ < 0);
219 if (((pt_next - pt).dot(dir) < (T)0) != reversing_) {
222 Eigen::Matrix<T, 3, 3> transform;
223 transform << dir[0], -dir[1], pt[0],
224 dir[1], dir[0], pt[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);
231 1> interp_pos = (ccpt_world - costmap_origin_.template cast<T>()) /
232 (T)costmap_resolution_;
234 costmap_interpolator_->Evaluate(interp_pos[1] - (T)0.5, interp_pos[0] - (T)0.5, &value);
236 r += (T)weight * (T)params_.cost_check_points[i + 2] * value * value;
241 const Eigen::Vector2d original_pos_;
242 double next_to_last_length_ratio_;
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_;
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 ¶ms, 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".