24
24
#include " tf2/utils.hpp"
25
25
26
26
#include " nav2_smac_planner/smoother.hpp"
27
+ #include " nav2_util/smoother_utils.hpp"
27
28
28
29
namespace nav2_smac_planner
29
30
{
30
31
using namespace nav2_util ::geometry_utils; // NOLINT
31
32
using namespace std ::chrono; // NOLINT
33
+ using nav2_util::PathSegment;
32
34
33
35
Smoother::Smoother (const SmootherParams & params)
34
36
{
@@ -62,7 +64,8 @@ bool Smoother::smooth(
62
64
bool success = true , reversing_segment;
63
65
nav_msgs::msg::Path curr_path_segment;
64
66
curr_path_segment.header = path.header ;
65
- std::vector<PathSegment> path_segments = findDirectionalPathSegments (path);
67
+ std::vector<PathSegment> path_segments = nav2_util::findDirectionalPathSegments (path,
68
+ is_holonomic_);
66
69
67
70
for (unsigned int i = 0 ; i != path_segments.size (); i++) {
68
71
if (path_segments[i].end - path_segments[i].start > 10 ) {
@@ -130,7 +133,7 @@ bool Smoother::smoothImpl(
130
133
rclcpp::get_logger (" SmacPlannerSmoother" ),
131
134
" Number of iterations has exceeded limit of %i." , max_its_);
132
135
path = last_path;
133
- updateApproximatePathOrientations (path, reversing_segment);
136
+ nav2_util:: updateApproximatePathOrientations (path, reversing_segment, is_holonomic_ );
134
137
return false ;
135
138
}
136
139
@@ -142,7 +145,7 @@ bool Smoother::smoothImpl(
142
145
rclcpp::get_logger (" SmacPlannerSmoother" ),
143
146
" Smoothing time exceeded allowed duration of %0.2f." , max_time);
144
147
path = last_path;
145
- updateApproximatePathOrientations (path, reversing_segment);
148
+ nav2_util:: updateApproximatePathOrientations (path, reversing_segment, is_holonomic_ );
146
149
return false ;
147
150
}
148
151
@@ -176,7 +179,7 @@ bool Smoother::smoothImpl(
176
179
" Smoothing process resulted in an infeasible collision. "
177
180
" Returning the last path before the infeasibility was introduced." );
178
181
path = last_path;
179
- updateApproximatePathOrientations (path, reversing_segment);
182
+ nav2_util:: updateApproximatePathOrientations (path, reversing_segment, is_holonomic_ );
180
183
return false ;
181
184
}
182
185
}
@@ -191,7 +194,7 @@ bool Smoother::smoothImpl(
191
194
smoothImpl (new_path, reversing_segment, costmap, max_time);
192
195
}
193
196
194
- updateApproximatePathOrientations (new_path, reversing_segment);
197
+ nav2_util:: updateApproximatePathOrientations (new_path, reversing_segment, is_holonomic_ );
195
198
path = new_path;
196
199
return true ;
197
200
}
@@ -221,92 +224,6 @@ void Smoother::setFieldByDim(
221
224
}
222
225
}
223
226
224
- std::vector<PathSegment> Smoother::findDirectionalPathSegments (const nav_msgs::msg::Path & path)
225
- {
226
- std::vector<PathSegment> segments;
227
- PathSegment curr_segment;
228
- curr_segment.start = 0 ;
229
-
230
- // If holonomic, no directional changes and
231
- // may have abrupt angular changes from naive grid search
232
- if (is_holonomic_) {
233
- curr_segment.end = path.poses .size () - 1 ;
234
- segments.push_back (curr_segment);
235
- return segments;
236
- }
237
-
238
- // Iterating through the path to determine the position of the cusp
239
- for (unsigned int idx = 1 ; idx < path.poses .size () - 1 ; ++idx) {
240
- // We have two vectors for the dot product OA and AB. Determining the vectors.
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 ;
249
-
250
- // Checking for the existence of cusp, in the path, using the dot product.
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;
256
- }
257
-
258
- // Checking for the existence of a differential rotation in place.
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;
266
- }
267
- }
268
-
269
- curr_segment.end = path.poses .size () - 1 ;
270
- segments.push_back (curr_segment);
271
- return segments;
272
- }
273
-
274
- void Smoother::updateApproximatePathOrientations (
275
- nav_msgs::msg::Path & path,
276
- bool & reversing_segment)
277
- {
278
- double dx, dy, theta, pt_yaw;
279
- reversing_segment = false ;
280
-
281
- // Find if this path segment is in reverse
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 ;
288
- }
289
-
290
- // Find the angle relative the path position vectors
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);
295
-
296
- // If points are overlapping, pass
297
- if (fabs (dx) < 1e-4 && fabs (dy) < 1e-4 ) {
298
- continue ;
299
- }
300
-
301
- // Flip the angle if this path segment is in reverse
302
- if (reversing_segment) {
303
- theta += M_PI; // orientationAroundZAxis will normalize
304
- }
305
-
306
- path.poses [i].pose .orientation = orientationAroundZAxis (theta);
307
- }
308
- }
309
-
310
227
unsigned int Smoother::findShortestBoundaryExpansionIdx (
311
228
const BoundaryExpansions & boundary_expansions)
312
229
{
0 commit comments