15 #include <ompl/base/ScopedState.h>
16 #include <ompl/base/spaces/DubinsStateSpace.h>
19 #include "nav2_smac_planner/smoother.hpp"
21 namespace nav2_smac_planner
23 using namespace nav2_util::geometry_utils;
24 using namespace std::chrono;
28 tolerance_ = params.tolerance_;
29 max_its_ = params.max_its_;
30 data_w_ = params.w_data_;
31 smooth_w_ = params.w_smooth_;
32 is_holonomic_ = params.holonomic_;
33 do_refinement_ = params.do_refinement_;
34 refinement_num_ = params.refinement_num_;
39 min_turning_rad_ = min_turning_radius;
40 state_space_ = std::make_unique<ompl::base::DubinsStateSpace>(min_turning_rad_);
44 nav_msgs::msg::Path & path,
46 const double & max_time)
53 steady_clock::time_point start = steady_clock::now();
54 double time_remaining = max_time;
55 bool success =
true, reversing_segment;
56 nav_msgs::msg::Path curr_path_segment;
57 curr_path_segment.header = path.header;
58 std::vector<PathSegment> path_segments = findDirectionalPathSegments(path);
60 for (
unsigned int i = 0; i != path_segments.size(); i++) {
61 if (path_segments[i].end - path_segments[i].start > 10) {
63 curr_path_segment.poses.clear();
65 path.poses.begin() + path_segments[i].start,
66 path.poses.begin() + path_segments[i].end + 1,
67 std::back_inserter(curr_path_segment.poses));
70 steady_clock::time_point now = steady_clock::now();
71 time_remaining = max_time - duration_cast<duration<double>>(now - start).count();
75 const geometry_msgs::msg::Pose start_pose = curr_path_segment.poses.front().pose;
76 const geometry_msgs::msg::Pose goal_pose = curr_path_segment.poses.back().pose;
78 smoothImpl(curr_path_segment, reversing_segment, costmap, time_remaining);
79 success = success && local_success;
82 if (!is_holonomic_ && local_success) {
83 enforceStartBoundaryConditions(start_pose, curr_path_segment, costmap, reversing_segment);
84 enforceEndBoundaryConditions(goal_pose, curr_path_segment, costmap, reversing_segment);
89 curr_path_segment.poses.begin(),
90 curr_path_segment.poses.end(),
91 path.poses.begin() + path_segments[i].start);
99 nav_msgs::msg::Path & path,
100 bool & reversing_segment,
102 const double & max_time)
104 steady_clock::time_point a = steady_clock::now();
105 rclcpp::Duration max_dur = rclcpp::Duration::from_seconds(max_time);
108 double change = tolerance_;
109 const unsigned int & path_size = path.poses.size();
110 double x_i, y_i, y_m1, y_ip1, y_i_org;
113 nav_msgs::msg::Path new_path = path;
114 nav_msgs::msg::Path last_path = path;
116 while (change >= tolerance_) {
121 if (its >= max_its_) {
123 rclcpp::get_logger(
"SmacPlannerSmoother"),
124 "Number of iterations has exceeded limit of %i.", max_its_);
126 updateApproximatePathOrientations(path, reversing_segment);
131 steady_clock::time_point b = steady_clock::now();
132 rclcpp::Duration timespan(duration_cast<duration<double>>(b - a));
133 if (timespan > max_dur) {
135 rclcpp::get_logger(
"SmacPlannerSmoother"),
136 "Smoothing time exceeded allowed duration of %0.2f.", max_time);
138 updateApproximatePathOrientations(path, reversing_segment);
142 for (
unsigned int i = 1; i != path_size - 1; i++) {
143 for (
unsigned int j = 0; j != 2; j++) {
144 x_i = getFieldByDim(path.poses[i], j);
145 y_i = getFieldByDim(new_path.poses[i], j);
146 y_m1 = getFieldByDim(new_path.poses[i - 1], j);
147 y_ip1 = getFieldByDim(new_path.poses[i + 1], j);
151 y_i += data_w_ * (x_i - y_i) + smooth_w_ * (y_ip1 + y_m1 - (2.0 * y_i));
152 setFieldByDim(new_path.poses[i], j, y_i);
153 change += abs(y_i - y_i_org);
160 getFieldByDim(new_path.poses[i], 0),
161 getFieldByDim(new_path.poses[i], 1),
163 cost =
static_cast<float>(costmap->
getCost(mx, my));
166 if (cost > MAX_NON_OBSTACLE && cost != UNKNOWN) {
168 rclcpp::get_logger(
"SmacPlannerSmoother"),
169 "Smoothing process resulted in an infeasible collision. "
170 "Returning the last path before the infeasibility was introduced.");
172 updateApproximatePathOrientations(path, reversing_segment);
177 last_path = new_path;
182 if (do_refinement_ && refinement_ctr_ < refinement_num_) {
184 smoothImpl(new_path, reversing_segment, costmap, max_time);
187 updateApproximatePathOrientations(new_path, reversing_segment);
193 const geometry_msgs::msg::PoseStamped & msg,
const unsigned int & dim)
196 return msg.pose.position.x;
197 }
else if (dim == 1) {
198 return msg.pose.position.y;
200 return msg.pose.position.z;
205 geometry_msgs::msg::PoseStamped & msg,
const unsigned int dim,
206 const double & value)
209 msg.pose.position.x = value;
210 }
else if (dim == 1) {
211 msg.pose.position.y = value;
213 msg.pose.position.z = value;
219 std::vector<PathSegment> segments;
221 curr_segment.start = 0;
226 curr_segment.end = path.poses.size() - 1;
227 segments.push_back(curr_segment);
232 for (
unsigned int idx = 1; idx < path.poses.size() - 1; ++idx) {
234 double oa_x = path.poses[idx].pose.position.x -
235 path.poses[idx - 1].pose.position.x;
236 double oa_y = path.poses[idx].pose.position.y -
237 path.poses[idx - 1].pose.position.y;
238 double ab_x = path.poses[idx + 1].pose.position.x -
239 path.poses[idx].pose.position.x;
240 double ab_y = path.poses[idx + 1].pose.position.y -
241 path.poses[idx].pose.position.y;
244 double dot_product = (oa_x * ab_x) + (oa_y * ab_y);
245 if (dot_product < 0.0) {
246 curr_segment.end = idx;
247 segments.push_back(curr_segment);
248 curr_segment.start = idx;
252 double cur_theta = tf2::getYaw(path.poses[idx].pose.orientation);
253 double next_theta = tf2::getYaw(path.poses[idx + 1].pose.orientation);
254 double dtheta = angles::shortest_angular_distance(cur_theta, next_theta);
255 if (fabs(ab_x) < 1e-4 && fabs(ab_y) < 1e-4 && fabs(dtheta) > 1e-4) {
256 curr_segment.end = idx;
257 segments.push_back(curr_segment);
258 curr_segment.start = idx;
262 curr_segment.end = path.poses.size() - 1;
263 segments.push_back(curr_segment);
268 nav_msgs::msg::Path & path,
269 bool & reversing_segment)
271 double dx, dy, theta, pt_yaw;
272 reversing_segment =
false;
275 dx = path.poses[2].pose.position.x - path.poses[1].pose.position.x;
276 dy = path.poses[2].pose.position.y - path.poses[1].pose.position.y;
277 theta = atan2(dy, dx);
278 pt_yaw = tf2::getYaw(path.poses[1].pose.orientation);
279 if (!is_holonomic_ && fabs(angles::shortest_angular_distance(pt_yaw, theta)) > M_PI_2) {
280 reversing_segment =
true;
284 for (
unsigned int i = 0; i != path.poses.size() - 1; i++) {
285 dx = path.poses[i + 1].pose.position.x - path.poses[i].pose.position.x;
286 dy = path.poses[i + 1].pose.position.y - path.poses[i].pose.position.y;
287 theta = atan2(dy, dx);
290 if (fabs(dx) < 1e-4 && fabs(dy) < 1e-4) {
295 if (reversing_segment) {
299 path.poses[i].pose.orientation = orientationAroundZAxis(theta);
304 const BoundaryExpansions & boundary_expansions)
309 double min_length = 1e9;
310 int shortest_boundary_expansion_idx = 1e9;
311 for (
unsigned int idx = 0; idx != boundary_expansions.size(); idx++) {
312 if (boundary_expansions[idx].expansion_path_length<min_length &&
313 !boundary_expansions[idx].in_collision &&
314 boundary_expansions[idx].path_end_idx>0.0 &&
315 boundary_expansions[idx].expansion_path_length > 0.0)
317 min_length = boundary_expansions[idx].expansion_path_length;
318 shortest_boundary_expansion_idx = idx;
322 return shortest_boundary_expansion_idx;
326 const geometry_msgs::msg::Pose & start,
327 const geometry_msgs::msg::Pose & end,
331 static ompl::base::ScopedState<> from(state_space_), to(state_space_), s(state_space_);
333 from[0] = start.position.x;
334 from[1] = start.position.y;
335 from[2] = tf2::getYaw(start.orientation);
336 to[0] = end.position.x;
337 to[1] = end.position.y;
338 to[2] = tf2::getYaw(end.orientation);
340 double d = state_space_->distance(from(), to());
348 if (d > 2.0 * expansion.original_path_length) {
352 std::vector<double> reals;
353 double theta(0.0), x(0.0), y(0.0);
354 double x_m = start.position.x;
355 double y_m = start.position.y;
358 for (
double i = 0; i <= expansion.path_end_idx; i++) {
359 state_space_->interpolate(from(), to(), i / expansion.path_end_idx, s());
362 theta = (reals[2] < 0.0) ? (reals[2] + 2.0 * M_PI) : reals[2];
363 theta = (theta > 2.0 * M_PI) ? (theta - 2.0 * M_PI) : theta;
370 if (
static_cast<float>(costmap->
getCost(mx, my)) >= INSCRIBED) {
371 expansion.in_collision =
true;
375 expansion.expansion_path_length += hypot(x - x_m, y - y_m);
380 expansion.pts.emplace_back(x, y, theta);
384 template<
typename IteratorT>
387 std::vector<double> distances = {
389 2.0 * min_turning_rad_,
390 M_PI * min_turning_rad_,
391 2.0 * M_PI * min_turning_rad_
394 BoundaryExpansions boundary_expansions;
395 boundary_expansions.resize(distances.size());
396 double curr_dist = 0.0;
397 double x_last = start->pose.position.x;
398 double y_last = start->pose.position.y;
399 geometry_msgs::msg::Point pt;
400 unsigned int curr_dist_idx = 0;
402 for (IteratorT iter = start; iter != end; iter++) {
403 pt = iter->pose.position;
404 curr_dist += hypot(pt.x - x_last, pt.y - y_last);
408 if (curr_dist >= distances[curr_dist_idx]) {
409 boundary_expansions[curr_dist_idx].path_end_idx = iter - start;
410 boundary_expansions[curr_dist_idx].original_path_length = curr_dist;
414 if (curr_dist_idx == boundary_expansions.size()) {
419 return boundary_expansions;
423 const geometry_msgs::msg::Pose & start_pose,
424 nav_msgs::msg::Path & path,
426 const bool & reversing_segment)
429 BoundaryExpansions boundary_expansions =
430 generateBoundaryExpansionPoints<PathIterator>(path.poses.begin(), path.poses.end());
433 for (
unsigned int i = 0; i != boundary_expansions.size(); i++) {
435 if (expansion.path_end_idx == 0.0) {
439 if (!reversing_segment) {
440 findBoundaryExpansion(
441 start_pose, path.poses[expansion.path_end_idx].pose, expansion,
444 findBoundaryExpansion(
445 path.poses[expansion.path_end_idx].pose, start_pose, expansion,
451 unsigned int best_expansion_idx = findShortestBoundaryExpansionIdx(boundary_expansions);
452 if (best_expansion_idx > boundary_expansions.size()) {
458 if (reversing_segment) {
459 std::reverse(best_expansion.pts.begin(), best_expansion.pts.end());
461 for (
unsigned int i = 0; i != best_expansion.pts.size(); i++) {
462 path.poses[i].pose.position.x = best_expansion.pts[i].x;
463 path.poses[i].pose.position.y = best_expansion.pts[i].y;
464 path.poses[i].pose.orientation = orientationAroundZAxis(best_expansion.pts[i].theta);
469 const geometry_msgs::msg::Pose & end_pose,
470 nav_msgs::msg::Path & path,
472 const bool & reversing_segment)
475 BoundaryExpansions boundary_expansions =
476 generateBoundaryExpansionPoints<ReversePathIterator>(path.poses.rbegin(), path.poses.rend());
479 unsigned int expansion_starting_idx;
480 for (
unsigned int i = 0; i != boundary_expansions.size(); i++) {
482 if (expansion.path_end_idx == 0.0) {
485 expansion_starting_idx = path.poses.size() - expansion.path_end_idx - 1;
486 if (!reversing_segment) {
487 findBoundaryExpansion(path.poses[expansion_starting_idx].pose, end_pose, expansion, costmap);
489 findBoundaryExpansion(end_pose, path.poses[expansion_starting_idx].pose, expansion, costmap);
494 unsigned int best_expansion_idx = findShortestBoundaryExpansionIdx(boundary_expansions);
495 if (best_expansion_idx > boundary_expansions.size()) {
501 if (reversing_segment) {
502 std::reverse(best_expansion.pts.begin(), best_expansion.pts.end());
504 expansion_starting_idx = path.poses.size() - best_expansion.path_end_idx - 1;
505 for (
unsigned int i = 0; i != best_expansion.pts.size(); i++) {
506 path.poses[expansion_starting_idx + i].pose.position.x = best_expansion.pts[i].x;
507 path.poses[expansion_starting_idx + i].pose.position.y = best_expansion.pts[i].y;
508 path.poses[expansion_starting_idx + i].pose.orientation = orientationAroundZAxis(
509 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.