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"
27 #include "nav2_util/smoother_utils.hpp"
29 namespace nav2_smac_planner
31 using namespace nav2_util::geometry_utils;
32 using namespace std::chrono;
37 tolerance_ = params.tolerance_;
38 max_its_ = params.max_its_;
39 data_w_ = params.w_data_;
40 smooth_w_ = params.w_smooth_;
41 is_holonomic_ = params.holonomic_;
42 do_refinement_ = params.do_refinement_;
43 refinement_num_ = params.refinement_num_;
48 min_turning_rad_ = min_turning_radius;
49 state_space_ = std::make_unique<ompl::base::DubinsStateSpace>(min_turning_rad_);
53 nav_msgs::msg::Path & path,
55 const double & max_time)
62 steady_clock::time_point start = steady_clock::now();
63 double time_remaining = max_time;
64 bool success =
true, reversing_segment;
65 nav_msgs::msg::Path curr_path_segment;
66 curr_path_segment.header = path.header;
67 std::vector<PathSegment> path_segments = nav2_util::findDirectionalPathSegments(path,
70 for (
unsigned int i = 0; i != path_segments.size(); i++) {
71 if (path_segments[i].end - path_segments[i].start > 10) {
73 curr_path_segment.poses.clear();
75 path.poses.begin() + path_segments[i].start,
76 path.poses.begin() + path_segments[i].end + 1,
77 std::back_inserter(curr_path_segment.poses));
80 steady_clock::time_point now = steady_clock::now();
81 time_remaining = max_time - duration_cast<duration<double>>(now - start).count();
85 const geometry_msgs::msg::Pose start_pose = curr_path_segment.poses.front().pose;
86 const geometry_msgs::msg::Pose goal_pose = curr_path_segment.poses.back().pose;
88 smoothImpl(curr_path_segment, reversing_segment, costmap, time_remaining);
89 success = success && local_success;
92 if (!is_holonomic_ && local_success) {
93 enforceStartBoundaryConditions(start_pose, curr_path_segment, costmap, reversing_segment);
94 enforceEndBoundaryConditions(goal_pose, curr_path_segment, costmap, reversing_segment);
99 curr_path_segment.poses.begin(),
100 curr_path_segment.poses.end(),
101 path.poses.begin() + path_segments[i].start);
109 nav_msgs::msg::Path & path,
110 bool & reversing_segment,
112 const double & max_time)
114 steady_clock::time_point a = steady_clock::now();
115 rclcpp::Duration max_dur = rclcpp::Duration::from_seconds(max_time);
118 double change = tolerance_;
119 const unsigned int & path_size = path.poses.size();
120 double x_i, y_i, y_m1, y_ip1, y_i_org;
123 nav_msgs::msg::Path new_path = path;
124 nav_msgs::msg::Path last_path = path;
126 while (change >= tolerance_) {
131 if (its >= max_its_) {
133 rclcpp::get_logger(
"SmacPlannerSmoother"),
134 "Number of iterations has exceeded limit of %i.", max_its_);
136 nav2_util::updateApproximatePathOrientations(path, reversing_segment, is_holonomic_);
141 steady_clock::time_point b = steady_clock::now();
142 rclcpp::Duration timespan(duration_cast<duration<double>>(b - a));
143 if (timespan > max_dur) {
145 rclcpp::get_logger(
"SmacPlannerSmoother"),
146 "Smoothing time exceeded allowed duration of %0.2f.", max_time);
148 nav2_util::updateApproximatePathOrientations(path, reversing_segment, is_holonomic_);
152 for (
unsigned int i = 1; i != path_size - 1; i++) {
153 for (
unsigned int j = 0; j != 2; j++) {
154 x_i = getFieldByDim(path.poses[i], j);
155 y_i = getFieldByDim(new_path.poses[i], j);
156 y_m1 = getFieldByDim(new_path.poses[i - 1], j);
157 y_ip1 = getFieldByDim(new_path.poses[i + 1], j);
161 y_i += data_w_ * (x_i - y_i) + smooth_w_ * (y_ip1 + y_m1 - (2.0 * y_i));
162 setFieldByDim(new_path.poses[i], j, y_i);
163 change += abs(y_i - y_i_org);
170 getFieldByDim(new_path.poses[i], 0),
171 getFieldByDim(new_path.poses[i], 1),
173 cost =
static_cast<float>(costmap->
getCost(mx, my));
176 if (cost > MAX_NON_OBSTACLE_COST && cost != UNKNOWN_COST) {
178 rclcpp::get_logger(
"SmacPlannerSmoother"),
179 "Smoothing process resulted in an infeasible collision. "
180 "Returning the last path before the infeasibility was introduced.");
182 nav2_util::updateApproximatePathOrientations(path, reversing_segment, is_holonomic_);
187 last_path = new_path;
192 if (do_refinement_ && refinement_ctr_ < refinement_num_) {
194 smoothImpl(new_path, reversing_segment, costmap, max_time);
197 nav2_util::updateApproximatePathOrientations(new_path, reversing_segment, is_holonomic_);
203 const geometry_msgs::msg::PoseStamped & msg,
const unsigned int & dim)
206 return msg.pose.position.x;
207 }
else if (dim == 1) {
208 return msg.pose.position.y;
210 return msg.pose.position.z;
215 geometry_msgs::msg::PoseStamped & msg,
const unsigned int dim,
216 const double & value)
219 msg.pose.position.x = value;
220 }
else if (dim == 1) {
221 msg.pose.position.y = value;
223 msg.pose.position.z = value;
228 const BoundaryExpansions & boundary_expansions)
233 double min_length = 1e9;
234 int shortest_boundary_expansion_idx = 1e9;
235 for (
unsigned int idx = 0; idx != boundary_expansions.size(); idx++) {
236 if (boundary_expansions[idx].expansion_path_length<min_length &&
237 !boundary_expansions[idx].in_collision &&
238 boundary_expansions[idx].path_end_idx>0.0 &&
239 boundary_expansions[idx].expansion_path_length > 0.0)
241 min_length = boundary_expansions[idx].expansion_path_length;
242 shortest_boundary_expansion_idx = idx;
246 return shortest_boundary_expansion_idx;
250 const geometry_msgs::msg::Pose & start,
251 const geometry_msgs::msg::Pose & end,
255 static ompl::base::ScopedState<> from(state_space_), to(state_space_), s(state_space_);
257 from[0] = start.position.x;
258 from[1] = start.position.y;
259 from[2] = tf2::getYaw(start.orientation);
260 to[0] = end.position.x;
261 to[1] = end.position.y;
262 to[2] = tf2::getYaw(end.orientation);
264 double d = state_space_->distance(from(), to());
272 if (d > 2.0 * expansion.original_path_length) {
276 std::vector<double> reals;
277 double theta(0.0), x(0.0), y(0.0);
278 double x_m = start.position.x;
279 double y_m = start.position.y;
282 for (
double i = 0; i <= expansion.path_end_idx; i++) {
283 state_space_->interpolate(from(), to(), i / expansion.path_end_idx, s());
286 theta = (reals[2] < 0.0) ? (reals[2] + 2.0 * M_PI) : reals[2];
287 theta = (theta > 2.0 * M_PI) ? (theta - 2.0 * M_PI) : theta;
294 if (
static_cast<float>(costmap->
getCost(mx, my)) >= INSCRIBED_COST) {
295 expansion.in_collision =
true;
299 expansion.expansion_path_length += hypot(x - x_m, y - y_m);
304 expansion.pts.emplace_back(x, y, theta);
308 template<
typename IteratorT>
311 std::vector<double> distances = {
313 2.0 * min_turning_rad_,
314 M_PI * min_turning_rad_,
315 2.0 * M_PI * min_turning_rad_
318 BoundaryExpansions boundary_expansions;
319 boundary_expansions.resize(distances.size());
320 double curr_dist = 0.0;
321 double x_last = start->pose.position.x;
322 double y_last = start->pose.position.y;
323 geometry_msgs::msg::Point pt;
324 unsigned int curr_dist_idx = 0;
326 for (IteratorT iter = start; iter != end; iter++) {
327 pt = iter->pose.position;
328 curr_dist += hypot(pt.x - x_last, pt.y - y_last);
332 if (curr_dist >= distances[curr_dist_idx]) {
333 boundary_expansions[curr_dist_idx].path_end_idx = iter - start;
334 boundary_expansions[curr_dist_idx].original_path_length = curr_dist;
338 if (curr_dist_idx == boundary_expansions.size()) {
343 return boundary_expansions;
347 const geometry_msgs::msg::Pose & start_pose,
348 nav_msgs::msg::Path & path,
350 const bool & reversing_segment)
353 BoundaryExpansions boundary_expansions =
354 generateBoundaryExpansionPoints<PathIterator>(path.poses.begin(), path.poses.end());
357 for (
unsigned int i = 0; i != boundary_expansions.size(); i++) {
359 if (expansion.path_end_idx == 0.0) {
363 if (!reversing_segment) {
364 findBoundaryExpansion(
365 start_pose, path.poses[expansion.path_end_idx].pose, expansion,
368 findBoundaryExpansion(
369 path.poses[expansion.path_end_idx].pose, start_pose, expansion,
375 unsigned int best_expansion_idx = findShortestBoundaryExpansionIdx(boundary_expansions);
376 if (best_expansion_idx > boundary_expansions.size()) {
382 if (reversing_segment) {
383 std::reverse(best_expansion.pts.begin(), best_expansion.pts.end());
385 for (
unsigned int i = 0; i != best_expansion.pts.size(); i++) {
386 path.poses[i].pose.position.x = best_expansion.pts[i].x;
387 path.poses[i].pose.position.y = best_expansion.pts[i].y;
388 path.poses[i].pose.orientation = orientationAroundZAxis(best_expansion.pts[i].theta);
393 const geometry_msgs::msg::Pose & end_pose,
394 nav_msgs::msg::Path & path,
396 const bool & reversing_segment)
399 BoundaryExpansions boundary_expansions =
400 generateBoundaryExpansionPoints<ReversePathIterator>(path.poses.rbegin(), path.poses.rend());
403 unsigned int expansion_starting_idx;
404 for (
unsigned int i = 0; i != boundary_expansions.size(); i++) {
406 if (expansion.path_end_idx == 0.0) {
409 expansion_starting_idx = path.poses.size() - expansion.path_end_idx - 1;
410 if (!reversing_segment) {
411 findBoundaryExpansion(path.poses[expansion_starting_idx].pose, end_pose, expansion, costmap);
413 findBoundaryExpansion(end_pose, path.poses[expansion_starting_idx].pose, expansion, costmap);
418 unsigned int best_expansion_idx = findShortestBoundaryExpansionIdx(boundary_expansions);
419 if (best_expansion_idx > boundary_expansions.size()) {
425 if (reversing_segment) {
426 std::reverse(best_expansion.pts.begin(), best_expansion.pts.end());
428 expansion_starting_idx = path.poses.size() - best_expansion.path_end_idx - 1;
429 for (
unsigned int i = 0; i != best_expansion.pts.size(); i++) {
430 path.poses[expansion_starting_idx + i].pose.position.x = best_expansion.pts[i].x;
431 path.poses[expansion_starting_idx + i].pose.position.y = best_expansion.pts[i].y;
432 path.poses[expansion_starting_idx + i].pose.orientation = orientationAroundZAxis(
433 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 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.
Parameters for the smoother cost function.
A segment of a path in start/end indices.