16 #ifndef NAV2_CONSTRAINED_SMOOTHER__SMOOTHER_HPP_
17 #define NAV2_CONSTRAINED_SMOOTHER__SMOOTHER_HPP_
29 #include "nav2_constrained_smoother/smoother_cost_function.hpp"
30 #include "nav2_constrained_smoother/utils.hpp"
32 #include "ceres/ceres.h"
35 namespace nav2_constrained_smoother
61 debug_ = params.debug;
63 options_.linear_solver_type = params.solver_types.at(params.linear_solver_type);
65 options_.max_num_iterations = params.max_iterations;
67 options_.function_tolerance = params.fn_tol;
68 options_.gradient_tolerance = params.gradient_tol;
69 options_.parameter_tolerance = params.param_tol;
72 options_.minimizer_progress_to_stdout =
true;
73 options_.logging_type = ceres::LoggingType::PER_MINIMIZER_ITERATION;
75 options_.logging_type = ceres::SILENT;
89 std::vector<Eigen::Vector3d> & path,
90 const Eigen::Vector2d & start_dir,
91 const Eigen::Vector2d & end_dir,
96 if (path.size() < 2) {
97 throw std::runtime_error(
"Constrained smoother: Path must have at least 2 points");
100 options_.max_solver_time_in_seconds = params.max_time;
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)) {
107 ceres::Solver::Summary summary;
108 ceres::Solve(options_, &problem, &summary);
110 RCLCPP_INFO(rclcpp::get_logger(
"smoother_server"),
"%s", summary.FullReport().c_str());
112 if (!summary.IsSolutionUsable() || summary.initial_cost - summary.final_cost < 0.0) {
116 RCLCPP_INFO(rclcpp::get_logger(
"smoother_server"),
"Path too short to optimize");
119 upsampleAndPopulate(path_optim, optimized, start_dir, end_dir, params, path);
136 const std::vector<Eigen::Vector3d> & path,
139 ceres::Problem & problem,
140 std::vector<Eigen::Vector3d> & path_optim,
141 std::vector<bool> & optimized)
144 costmap_grid_ = std::make_shared<ceres::Grid2D<u_char>>(
146 auto costmap_interpolator = std::make_shared<ceres::BiCubicInterpolator<ceres::Grid2D<u_char>>>(
150 const double cusp_half_length = params.cusp_zone_length / 2;
151 ceres::LossFunction * loss_function = NULL;
153 optimized = std::vector<bool>(path.size());
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();
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];
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)
184 double current_segment_len = (path_optim[i] - path_optim[last_i]).block<2, 1>(0, 0).norm();
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();
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];
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))
204 f.second->setCostmapWeight(new_weight);
206 len_to_cusp += f.first;
208 potential_cusp_funcs_len = 0;
209 potential_cusp_funcs.clear();
215 if (prelast_i != -1) {
216 double costmap_weight = params.costmap_weight;
217 if (len_since_cusp <= cusp_half_length) {
219 params.cusp_costmap_weight * (1.0 - len_since_cusp / cusp_half_length) +
220 params.costmap_weight * len_since_cusp / cusp_half_length;
222 SmootherCostFunction * cost_function =
new SmootherCostFunction(
223 path[last_i].
template block<2, 1>(
226 (last_was_cusp ? -1 : 1) * last_segment_len / current_segment_len,
229 costmap_interpolator,
233 problem.AddResidualBlock(
234 cost_function->AutoDiff(), loss_function,
235 path_optim[last_i].data(), pt.data(), path_optim[prelast_i].data());
237 potential_cusp_funcs.emplace_back(current_segment_len, cost_function);
241 last_was_cusp = is_cusp;
242 last_is_reversing = last_direction < 0;
245 len_since_cusp += current_segment_len;
246 last_segment_len = std::max(EPSILON, current_segment_len);
249 int posesToOptimize = problem.NumParameterBlocks() - 2;
250 if (params.keep_goal_orientation) {
251 posesToOptimize -= 1;
253 if (params.keep_start_orientation) {
254 posesToOptimize -= 1;
256 if (posesToOptimize <= 0) {
260 problem.SetParameterBlockConstant(path_optim.front().data());
261 if (params.keep_start_orientation) {
262 problem.SetParameterBlockConstant(path_optim[1].data());
264 if (params.keep_goal_orientation) {
265 problem.SetParameterBlockConstant(path_optim[path_optim.size() - 2].data());
267 problem.SetParameterBlockConstant(path_optim.back().data());
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)
290 if (params.path_upsampling_factor > 1) {
291 path.reserve(params.path_upsampling_factor * (path_optim.size() - 1) + 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];
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);
313 tangent_dir.dot((current - last).block<2, 1>(0, 0) * last[2]) >= 0 ?
316 last_dir.normalize();
317 }
else if (params.keep_goal_orientation) {
320 last_dir = (last - prelast).block<2, 1>(0, 0) * last[2];
321 last_dir.normalize();
323 double last_angle = atan2(last_dir[1], last_dir[0]);
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);
339 path.emplace_back(last[0], last[1], last_angle);
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),
349 tangent_dir.dot((path[j + 1] - path[j]).block<2, 1>(0, 0) * prelast[2]) >= 0 ?
352 path[j][2] = atan2(tangent_dir[1], tangent_dir[0]);
355 prelast_dir = last_dir;
357 auto & start = path_optim[0];
358 Eigen::Vector2d dir = params.keep_start_orientation ?
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]));
375 static Eigen::Vector2d cubicBezier(
376 Eigen::Vector2d & pt0, Eigen::Vector2d & pt1,
377 Eigen::Vector2d & pt2, Eigen::Vector2d & pt3,
double mu)
379 Eigen::Vector2d a, b, c, pt;
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];
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];
395 ceres::Solver::Options options_;
396 std::shared_ptr<ceres::Grid2D<u_char>> costmap_grid_;
Smoother()
A constructor for nav2_smac_planner::Smoother.
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 ¶ms)
Smoother method.
void initialize(const OptimizerParams params)
Initialization of the smoother.
~Smoother()
A destructor for nav2_smac_planner::Smoother.
A 2D costmap provides a mapping between points in the world and their associated "costs".
unsigned char * getCharMap() const
Will return a pointer to the underlying unsigned char array used as the costmap.
unsigned int getSizeInCellsX() const
Accessor for the x size of the costmap in cells.
unsigned int getSizeInCellsY() const
Accessor for the y size of the costmap in cells.