@@ -148,11 +148,37 @@ bool DWBLocalPlanner::isGoalReached(const nav_2d_msgs::Pose2DStamped& pose, cons
148
148
149
149
// Update time stamp of goal pose
150
150
goal_pose_.header .stamp = pose.header .stamp ;
151
+ intermediate_goal_pose_.header .stamp = pose.header .stamp ;
151
152
152
- bool ret = goal_checker_->isGoalReached (transformPoseToLocal (pose), transformPoseToLocal (goal_pose_), velocity);
153
+ // use the goal_checker_ to check if the intermediate goal was reached.
154
+ bool ret = goal_checker_->isGoalReached (
155
+ transformPoseToLocal (pose),
156
+ transformPoseToLocal (intermediate_goal_pose_),
157
+ velocity);
153
158
if (ret)
154
159
{
155
- ROS_INFO_THROTTLE_NAMED (1.0 , " DWBLocalPlanner" , " Goal reached!" );
160
+ if (global_plan_segments_.empty ())
161
+ ROS_INFO_THROTTLE_NAMED (1.0 , " DWBLocalPlanner" , " Goal reached!" );
162
+ else
163
+ {
164
+ ROS_INFO_THROTTLE_NAMED (1.0 , " DWBLocalPlanner" , " Intermediate goal reached!" );
165
+ ret = false ; // reset to false, as we only finished one segment.
166
+
167
+ // activate next path segment
168
+ global_plan_ = global_plan_segments_[0 ];
169
+ global_plan_segments_.erase (global_plan_segments_.begin ());
170
+ // set the next goal pose
171
+ intermediate_goal_pose_.header = global_plan_.header ;
172
+ intermediate_goal_pose_.pose = global_plan_.poses .back ();
173
+
174
+ // publish the next path segment
175
+ pub_.publishGlobalPlan (global_plan_);
176
+
177
+ // reset critics etc, as we changed the global_plan_
178
+ resetPlugins ();
179
+ // prepare(...) will be called soon, automatically, when computing the
180
+ // velocity commands.
181
+ }
156
182
}
157
183
return ret;
158
184
}
@@ -161,12 +187,157 @@ void DWBLocalPlanner::setGoalPose(const nav_2d_msgs::Pose2DStamped& goal_pose)
161
187
{
162
188
ROS_INFO_NAMED (" DWBLocalPlanner" , " New Goal Received." );
163
189
goal_pose_ = goal_pose;
190
+ intermediate_goal_pose_ = goal_pose; // For now assume that the path will not
191
+ // be split. Else the intermediate goal
192
+ // will be reset in setPlan.
164
193
}
165
194
166
195
void DWBLocalPlanner::setPlan (const nav_2d_msgs::Path2D& path)
167
196
{
168
- pub_.publishGlobalPlan (path);
169
- global_plan_ = path;
197
+ bool split_path;
198
+ planner_nh_.param (" split_path" , split_path, false );
199
+
200
+ global_plan_segments_.clear ();
201
+
202
+ if (split_path)
203
+ {
204
+ /*
205
+ Global planners like SBPL might create trajectories with complex
206
+ maneuvers, switching between driving forwards and backwards, where it is
207
+ crucial that the individual segments are carefully followed and completed
208
+ before starting the next. The "split_path" option allows to split the
209
+ given path in such segments and to treat each of them independently.
210
+
211
+ The segmentation is computed as follows:
212
+ Given two poses in the path, we compute the vector v1 connecting them,
213
+ the vector of orientation given through the angle theta, check the dot
214
+ product of the vectors: If it is less than 0, the angle is over 90 deg,
215
+ which is a coarse approximation for "driving backwards", and for "driving
216
+ forwards" otherwise. In the special case that the vector connecting the
217
+ two poses is null we have to deal with in-place-rotations of the robot.
218
+ To avoid the robot from eagerly driving forward before having achieved the
219
+ correct orientation, these situations are grouped in a third category.
220
+ The path is then split into segments of the same movement-direction
221
+ (forward/backward/onlyRotation). When a cut is made, the last pose of the
222
+ last segment is copied, to be the first pose of the following segment, to
223
+ ensure a seamless path.
224
+
225
+ The "global_plan_" variable is then set to the first segment.
226
+ In the "isGoalReached" method, which is repeatedly called, we check if
227
+ the intermediate goal - i.e., the end of the current segment - is reached,
228
+ and if so proceed to the next segment.
229
+ */
230
+ ROS_INFO_NAMED (" DWBLocalPlanner" , " Splitting path..." );
231
+
232
+ auto copy = path;
233
+ while (copy.poses .size () > 1 ) // need at least 2 poses in a path
234
+ {
235
+ // start a new segment
236
+ nav_2d_msgs::Path2D segment;
237
+ segment.header = path.header ;
238
+
239
+ // add the first pose
240
+ segment.poses .push_back (copy.poses [0 ]);
241
+ copy.poses .erase (copy.poses .begin ());
242
+
243
+ // add the second pose and determine if we are going forward or backward
244
+ segment.poses .push_back (copy.poses [0 ]);
245
+ copy.poses .erase (copy.poses .begin ());
246
+
247
+ // take the vector from the first to the second position and compare it
248
+ // to the orientation vector at the first position. If the angle is > 90 deg,
249
+ // assume we are driving backwards.
250
+ double v1[2 ] =
251
+ {
252
+ segment.poses [1 ].x - segment.poses [0 ].x ,
253
+ segment.poses [1 ].y - segment.poses [0 ].y
254
+ };
255
+ double v2[2 ] =
256
+ {
257
+ cos (segment.poses [0 ].theta ),
258
+ sin (segment.poses [0 ].theta )
259
+ };
260
+ double d = v1[0 ] * v2[0 ] + v1[1 ] * v2[1 ]; // dotproduct of the vectors. if < 0, the angle is over 90 degrees.
261
+ bool backwards = (d < 0 );
262
+ bool onlyRotation = std::fabs (v1[0 ]) < 1e-5 && std::fabs (v1[1 ]) < 1e-5 ;
263
+ // if the translation vector is zero, the two positions are equal
264
+ // and the plan is to rotate on the spot. Since dwb would
265
+ // enthusiastically speed up at the start of a trajectory,
266
+ // even if it starts with in-place-rotation, it would
267
+ // miss the path by a lot. So let's split the path into
268
+ // forwards / backwards / onlyRotation.
269
+
270
+ // add more poses while they lead into the same direction (driving forwards/backwards/onlyRotation)
271
+ while (!copy.poses .empty ())
272
+ {
273
+ // vector from the last pose in the segment to the next in the path
274
+ double v1[2 ] =
275
+ {
276
+ copy.poses [0 ].x - segment.poses .back ().x ,
277
+ copy.poses [0 ].y - segment.poses .back ().y
278
+ };
279
+ // orientation at the last pose in the segment
280
+ double v2[2 ] =
281
+ {
282
+ cos (segment.poses .back ().theta ),
283
+ sin (segment.poses .back ().theta )
284
+ };
285
+ double d = v1[0 ] * v2[0 ] + v1[1 ] * v2[1 ]; // dotproduct of the vectors. if < 0, the angle is over 90 degrees.
286
+ bool b = (d < 0 );
287
+ bool rot = std::fabs (v1[0 ]) < 1e-5 && std::fabs (v1[1 ]) < 1e-5 ;
288
+
289
+ if (b == backwards && rot == onlyRotation)
290
+ {
291
+ // same direction -> just add the pose
292
+ segment.poses .push_back (copy.poses [0 ]);
293
+ copy.poses .erase (copy.poses .begin ());
294
+ }
295
+ else
296
+ {
297
+ // direction changes -> add the last pose of the last segment back to
298
+ // the path, to start a new segment at the end of the last
299
+ copy.poses .insert (copy.poses .begin (), segment.poses .back ());
300
+ break ;
301
+ }
302
+ }
303
+
304
+ // add the created segment to the list
305
+ global_plan_segments_.push_back (segment);
306
+ }
307
+ if (global_plan_segments_.empty ())
308
+ {
309
+ // path doesn't have at least 2 poses, hence there is only one segment, which
310
+ // is the complete path.
311
+ global_plan_segments_.push_back (path);
312
+ }
313
+
314
+ ROS_INFO_STREAM (" Split path into " << global_plan_segments_.size () << " segments." );
315
+ }
316
+ else
317
+ {
318
+ // split_path option is disabled, hence there is only one segment, which
319
+ // is the complete path.
320
+ global_plan_segments_.push_back (path);
321
+ }
322
+
323
+ // set the global_plan_ to be the first segment
324
+ global_plan_ = global_plan_segments_[0 ];
325
+ global_plan_segments_.erase (global_plan_segments_.begin ());
326
+
327
+ // publish not the complete path, but only the first segment.
328
+ pub_.publishGlobalPlan (global_plan_);
329
+
330
+ // set the intermediate goal
331
+ intermediate_goal_pose_.header = global_plan_.header ;
332
+ intermediate_goal_pose_.pose = global_plan_.poses .back ();
333
+
334
+ resetPlugins ();
335
+ // prepare(...) to initialize the critics for the new segment does not need
336
+ // to be called here, as it is called at every computeVelocityCommands-call.
337
+ }
338
+
339
+ void DWBLocalPlanner::resetPlugins ()
340
+ {
170
341
traj_generator_->reset ();
171
342
goal_checker_->reset ();
172
343
for (TrajectoryCritic::Ptr critic : critics_)
@@ -209,9 +380,10 @@ void DWBLocalPlanner::prepare(const nav_2d_msgs::Pose2DStamped& pose, const nav_
209
380
210
381
// Update time stamp of goal pose
211
382
goal_pose_.header .stamp = pose.header .stamp ;
383
+ intermediate_goal_pose_.header .stamp = pose.header .stamp ;
212
384
213
385
geometry_msgs::Pose2D local_start_pose = transformPoseToLocal (pose),
214
- local_goal_pose = transformPoseToLocal (goal_pose_ );
386
+ local_goal_pose = transformPoseToLocal (intermediate_goal_pose_ );
215
387
216
388
pub_.publishInputParams (costmap_->getInfo (), local_start_pose, velocity, local_goal_pose);
217
389
0 commit comments