15 #include <ompl/base/ScopedState.h>
16 #include <ompl/base/spaces/DubinsStateSpace.h>
22 #include "angles/angles.h"
24 #include "tf2/utils.hpp"
26 #include "nav2_smac_planner/smoother.hpp"
28 namespace nav2_smac_planner
30 using namespace nav2_util::geometry_utils;
31 using namespace std::chrono;
35 tolerance_ = params.tolerance_;
36 max_its_ = params.max_its_;
37 data_w_ = params.w_data_;
38 smooth_w_ = params.w_smooth_;
39 is_holonomic_ = params.holonomic_;
40 do_refinement_ = params.do_refinement_;
41 refinement_num_ = params.refinement_num_;
46 min_turning_rad_ = min_turning_radius;
47 state_space_ = std::make_unique<ompl::base::DubinsStateSpace>(min_turning_rad_);
51 nav_msgs::msg::Path & path,
53 const double & max_time)
60 steady_clock::time_point start = steady_clock::now();
61 double time_remaining = max_time;
62 bool success =
true, reversing_segment;
63 nav_msgs::msg::Path curr_path_segment;
64 curr_path_segment.header = path.header;
65 std::vector<PathSegment> path_segments = findDirectionalPathSegments(path);
67 for (
unsigned int i = 0; i != path_segments.size(); i++) {
68 if (path_segments[i].end - path_segments[i].start > 10) {
70 curr_path_segment.poses.clear();
72 path.poses.begin() + path_segments[i].start,
73 path.poses.begin() + path_segments[i].end + 1,
74 std::back_inserter(curr_path_segment.poses));
77 steady_clock::time_point now = steady_clock::now();
78 time_remaining = max_time - duration_cast<duration<double>>(now - start).count();
82 const geometry_msgs::msg::Pose start_pose = curr_path_segment.poses.front().pose;
83 const geometry_msgs::msg::Pose goal_pose = curr_path_segment.poses.back().pose;
85 smoothImpl(curr_path_segment, reversing_segment, costmap, time_remaining);
86 success = success && local_success;
89 if (!is_holonomic_ && local_success) {
90 enforceStartBoundaryConditions(start_pose, curr_path_segment, costmap, reversing_segment);
91 enforceEndBoundaryConditions(goal_pose, curr_path_segment, costmap, reversing_segment);
96 curr_path_segment.poses.begin(),
97 curr_path_segment.poses.end(),
98 path.poses.begin() + path_segments[i].start);
106 nav_msgs::msg::Path & path,
107 bool & reversing_segment,
109 const double & max_time)
111 steady_clock::time_point a = steady_clock::now();
112 rclcpp::Duration max_dur = rclcpp::Duration::from_seconds(max_time);
115 double change = tolerance_;
116 const unsigned int & path_size = path.poses.size();
117 double x_i, y_i, y_m1, y_ip1, y_i_org;
120 nav_msgs::msg::Path new_path = path;
121 nav_msgs::msg::Path last_path = path;
123 while (change >= tolerance_) {
128 if (its >= max_its_) {
130 rclcpp::get_logger(
"SmacPlannerSmoother"),
131 "Number of iterations has exceeded limit of %i.", max_its_);
133 updateApproximatePathOrientations(path, reversing_segment);
138 steady_clock::time_point b = steady_clock::now();
139 rclcpp::Duration timespan(duration_cast<duration<double>>(b - a));
140 if (timespan > max_dur) {
142 rclcpp::get_logger(
"SmacPlannerSmoother"),
143 "Smoothing time exceeded allowed duration of %0.2f.", max_time);
145 updateApproximatePathOrientations(path, reversing_segment);
149 for (
unsigned int i = 1; i != path_size - 1; i++) {
150 for (
unsigned int j = 0; j != 2; j++) {
151 x_i = getFieldByDim(path.poses[i], j);
152 y_i = getFieldByDim(new_path.poses[i], j);
153 y_m1 = getFieldByDim(new_path.poses[i - 1], j);
154 y_ip1 = getFieldByDim(new_path.poses[i + 1], j);
158 y_i += data_w_ * (x_i - y_i) + smooth_w_ * (y_ip1 + y_m1 - (2.0 * y_i));
159 setFieldByDim(new_path.poses[i], j, y_i);
160 change += abs(y_i - y_i_org);
167 getFieldByDim(new_path.poses[i], 0),
168 getFieldByDim(new_path.poses[i], 1),
170 cost =
static_cast<float>(costmap->
getCost(mx, my));
173 if (cost > MAX_NON_OBSTACLE_COST && cost != UNKNOWN_COST) {
175 rclcpp::get_logger(
"SmacPlannerSmoother"),
176 "Smoothing process resulted in an infeasible collision. "
177 "Returning the last path before the infeasibility was introduced.");
179 updateApproximatePathOrientations(path, reversing_segment);
184 last_path = new_path;
189 if (do_refinement_ && refinement_ctr_ < refinement_num_) {
191 smoothImpl(new_path, reversing_segment, costmap, max_time);
194 updateApproximatePathOrientations(new_path, reversing_segment);
200 const geometry_msgs::msg::PoseStamped & msg,
const unsigned int & dim)
203 return msg.pose.position.x;
204 }
else if (dim == 1) {
205 return msg.pose.position.y;
207 return msg.pose.position.z;
212 geometry_msgs::msg::PoseStamped & msg,
const unsigned int dim,
213 const double & value)
216 msg.pose.position.x = value;
217 }
else if (dim == 1) {
218 msg.pose.position.y = value;
220 msg.pose.position.z = value;
226 std::vector<PathSegment> segments;
228 curr_segment.start = 0;
233 curr_segment.end = path.poses.size() - 1;
234 segments.push_back(curr_segment);
239 for (
unsigned int idx = 1; idx < path.poses.size() - 1; ++idx) {
241 double oa_x = path.poses[idx].pose.position.x -
242 path.poses[idx - 1].pose.position.x;
243 double oa_y = path.poses[idx].pose.position.y -
244 path.poses[idx - 1].pose.position.y;
245 double ab_x = path.poses[idx + 1].pose.position.x -
246 path.poses[idx].pose.position.x;
247 double ab_y = path.poses[idx + 1].pose.position.y -
248 path.poses[idx].pose.position.y;
251 double dot_product = (oa_x * ab_x) + (oa_y * ab_y);
252 if (dot_product < 0.0) {
253 curr_segment.end = idx;
254 segments.push_back(curr_segment);
255 curr_segment.start = idx;
259 double cur_theta = tf2::getYaw(path.poses[idx].pose.orientation);
260 double next_theta = tf2::getYaw(path.poses[idx + 1].pose.orientation);
261 double dtheta = angles::shortest_angular_distance(cur_theta, next_theta);
262 if (fabs(ab_x) < 1e-4 && fabs(ab_y) < 1e-4 && fabs(dtheta) > 1e-4) {
263 curr_segment.end = idx;
264 segments.push_back(curr_segment);
265 curr_segment.start = idx;
269 curr_segment.end = path.poses.size() - 1;
270 segments.push_back(curr_segment);
275 nav_msgs::msg::Path & path,
276 bool & reversing_segment)
278 double dx, dy, theta, pt_yaw;
279 reversing_segment =
false;
282 dx = path.poses[2].pose.position.x - path.poses[1].pose.position.x;
283 dy = path.poses[2].pose.position.y - path.poses[1].pose.position.y;
284 theta = atan2(dy, dx);
285 pt_yaw = tf2::getYaw(path.poses[1].pose.orientation);
286 if (!is_holonomic_ && fabs(angles::shortest_angular_distance(pt_yaw, theta)) > M_PI_2) {
287 reversing_segment =
true;
291 for (
unsigned int i = 0; i != path.poses.size() - 1; i++) {
292 dx = path.poses[i + 1].pose.position.x - path.poses[i].pose.position.x;
293 dy = path.poses[i + 1].pose.position.y - path.poses[i].pose.position.y;
294 theta = atan2(dy, dx);
297 if (fabs(dx) < 1e-4 && fabs(dy) < 1e-4) {
302 if (reversing_segment) {
306 path.poses[i].pose.orientation = orientationAroundZAxis(theta);
311 const BoundaryExpansions & boundary_expansions)
316 double min_length = 1e9;
317 int shortest_boundary_expansion_idx = 1e9;
318 for (
unsigned int idx = 0; idx != boundary_expansions.size(); idx++) {
319 if (boundary_expansions[idx].expansion_path_length<min_length &&
320 !boundary_expansions[idx].in_collision &&
321 boundary_expansions[idx].path_end_idx>0.0 &&
322 boundary_expansions[idx].expansion_path_length > 0.0)
324 min_length = boundary_expansions[idx].expansion_path_length;
325 shortest_boundary_expansion_idx = idx;
329 return shortest_boundary_expansion_idx;
333 const geometry_msgs::msg::Pose & start,
334 const geometry_msgs::msg::Pose & end,
338 static ompl::base::ScopedState<> from(state_space_), to(state_space_), s(state_space_);
340 from[0] = start.position.x;
341 from[1] = start.position.y;
342 from[2] = tf2::getYaw(start.orientation);
343 to[0] = end.position.x;
344 to[1] = end.position.y;
345 to[2] = tf2::getYaw(end.orientation);
347 double d = state_space_->distance(from(), to());
355 if (d > 2.0 * expansion.original_path_length) {
359 std::vector<double> reals;
360 double theta(0.0), x(0.0), y(0.0);
361 double x_m = start.position.x;
362 double y_m = start.position.y;
365 for (
double i = 0; i <= expansion.path_end_idx; i++) {
366 state_space_->interpolate(from(), to(), i / expansion.path_end_idx, s());
369 theta = (reals[2] < 0.0) ? (reals[2] + 2.0 * M_PI) : reals[2];
370 theta = (theta > 2.0 * M_PI) ? (theta - 2.0 * M_PI) : theta;
377 if (
static_cast<float>(costmap->
getCost(mx, my)) >= INSCRIBED_COST) {
378 expansion.in_collision =
true;
382 expansion.expansion_path_length += hypot(x - x_m, y - y_m);
387 expansion.pts.emplace_back(x, y, theta);
391 template<
typename IteratorT>
394 std::vector<double> distances = {
396 2.0 * min_turning_rad_,
397 M_PI * min_turning_rad_,
398 2.0 * M_PI * min_turning_rad_
401 BoundaryExpansions boundary_expansions;
402 boundary_expansions.resize(distances.size());
403 double curr_dist = 0.0;
404 double x_last = start->pose.position.x;
405 double y_last = start->pose.position.y;
406 geometry_msgs::msg::Point pt;
407 unsigned int curr_dist_idx = 0;
409 for (IteratorT iter = start; iter != end; iter++) {
410 pt = iter->pose.position;
411 curr_dist += hypot(pt.x - x_last, pt.y - y_last);
415 if (curr_dist >= distances[curr_dist_idx]) {
416 boundary_expansions[curr_dist_idx].path_end_idx = iter - start;
417 boundary_expansions[curr_dist_idx].original_path_length = curr_dist;
421 if (curr_dist_idx == boundary_expansions.size()) {
426 return boundary_expansions;
430 const geometry_msgs::msg::Pose & start_pose,
431 nav_msgs::msg::Path & path,
433 const bool & reversing_segment)
436 BoundaryExpansions boundary_expansions =
437 generateBoundaryExpansionPoints<PathIterator>(path.poses.begin(), path.poses.end());
440 for (
unsigned int i = 0; i != boundary_expansions.size(); i++) {
442 if (expansion.path_end_idx == 0.0) {
446 if (!reversing_segment) {
447 findBoundaryExpansion(
448 start_pose, path.poses[expansion.path_end_idx].pose, expansion,
451 findBoundaryExpansion(
452 path.poses[expansion.path_end_idx].pose, start_pose, expansion,
458 unsigned int best_expansion_idx = findShortestBoundaryExpansionIdx(boundary_expansions);
459 if (best_expansion_idx > boundary_expansions.size()) {
465 if (reversing_segment) {
466 std::reverse(best_expansion.pts.begin(), best_expansion.pts.end());
468 for (
unsigned int i = 0; i != best_expansion.pts.size(); i++) {
469 path.poses[i].pose.position.x = best_expansion.pts[i].x;
470 path.poses[i].pose.position.y = best_expansion.pts[i].y;
471 path.poses[i].pose.orientation = orientationAroundZAxis(best_expansion.pts[i].theta);
476 const geometry_msgs::msg::Pose & end_pose,
477 nav_msgs::msg::Path & path,
479 const bool & reversing_segment)
482 BoundaryExpansions boundary_expansions =
483 generateBoundaryExpansionPoints<ReversePathIterator>(path.poses.rbegin(), path.poses.rend());
486 unsigned int expansion_starting_idx;
487 for (
unsigned int i = 0; i != boundary_expansions.size(); i++) {
489 if (expansion.path_end_idx == 0.0) {
492 expansion_starting_idx = path.poses.size() - expansion.path_end_idx - 1;
493 if (!reversing_segment) {
494 findBoundaryExpansion(path.poses[expansion_starting_idx].pose, end_pose, expansion, costmap);
496 findBoundaryExpansion(end_pose, path.poses[expansion_starting_idx].pose, expansion, costmap);
501 unsigned int best_expansion_idx = findShortestBoundaryExpansionIdx(boundary_expansions);
502 if (best_expansion_idx > boundary_expansions.size()) {
508 if (reversing_segment) {
509 std::reverse(best_expansion.pts.begin(), best_expansion.pts.end());
511 expansion_starting_idx = path.poses.size() - best_expansion.path_end_idx - 1;
512 for (
unsigned int i = 0; i != best_expansion.pts.size(); i++) {
513 path.poses[expansion_starting_idx + i].pose.position.x = best_expansion.pts[i].x;
514 path.poses[expansion_starting_idx + i].pose.position.y = best_expansion.pts[i].y;
515 path.poses[expansion_starting_idx + i].pose.orientation = orientationAroundZAxis(
516 best_expansion.pts[i].theta);
A 2D costmap provides a mapping between points in the world and their associated "costs".
unsigned char getCost(unsigned int mx, unsigned int my) const
Get the cost of a cell in the costmap.
bool worldToMap(double wx, double wy, unsigned int &mx, unsigned int &my) const
Convert from world coordinates to map coordinates.
void initialize(const double &min_turning_radius)
Initialization of the smoother.
bool smooth(nav_msgs::msg::Path &path, const nav2_costmap_2d::Costmap2D *costmap, const double &max_time)
Smoother API method.
bool smoothImpl(nav_msgs::msg::Path &path, bool &reversing_segment, const nav2_costmap_2d::Costmap2D *costmap, const double &max_time)
Smoother method - does the smoothing on a segment.
void updateApproximatePathOrientations(nav_msgs::msg::Path &path, bool &reversing_segment)
For a given path, update the path point orientations based on smoothing.
std::vector< PathSegment > findDirectionalPathSegments(const nav_msgs::msg::Path &path)
Finds the starting and end indices of path segments where the robot is traveling in the same directio...
void enforceStartBoundaryConditions(const geometry_msgs::msg::Pose &start_pose, nav_msgs::msg::Path &path, const nav2_costmap_2d::Costmap2D *costmap, const bool &reversing_segment)
Enforced minimum curvature boundary conditions on plan output the robot is traveling in the same dire...
double getFieldByDim(const geometry_msgs::msg::PoseStamped &msg, const unsigned int &dim)
Get the field value for a given dimension.
void enforceEndBoundaryConditions(const geometry_msgs::msg::Pose &end_pose, nav_msgs::msg::Path &path, const nav2_costmap_2d::Costmap2D *costmap, const bool &reversing_segment)
Enforced minimum curvature boundary conditions on plan output the robot is traveling in the same dire...
void setFieldByDim(geometry_msgs::msg::PoseStamped &msg, const unsigned int dim, const double &value)
Set the field value for a given dimension.
Smoother(const SmootherParams ¶ms)
A constructor for nav2_smac_planner::Smoother.
BoundaryExpansions generateBoundaryExpansionPoints(IteratorT start, IteratorT end)
Generates boundary expansions with end idx at least strategic distances away, using either Reverse or...
unsigned int findShortestBoundaryExpansionIdx(const BoundaryExpansions &boundary_expansions)
Given a set of boundary expansion, find the one which is shortest such that it is least likely to con...
void findBoundaryExpansion(const geometry_msgs::msg::Pose &start, const geometry_msgs::msg::Pose &end, BoundaryExpansion &expansion, const nav2_costmap_2d::Costmap2D *costmap)
Populate a motion model expansion from start->end into expansion.
Boundary expansion state.
A segment of a path in start/end indices.
Parameters for the smoother cost function.