Skip to content

Commit 885e6b4

Browse files
niniemannmintar
authored andcommitted
Extended the dwb_local_planner with a split_path option.
When split_path is set to true, upon receiving a new path from the global planner, dwb will now split the path into segments of the same movement direction (roughly forwards/backwards/in-place-rotation). The segments will be treated as if they were given by the global planner one by one. This avoids taking shortcuts during complex maneuvers.
1 parent 33c974b commit 885e6b4

File tree

2 files changed

+185
-11
lines changed

2 files changed

+185
-11
lines changed

dwb_local_planner/include/dwb_local_planner/dwb_local_planner.h

+12-1
Original file line numberDiff line numberDiff line change
@@ -171,8 +171,19 @@ class DWBLocalPlanner: public nav_core2::LocalPlanner
171171
*/
172172
geometry_msgs::Pose2D transformPoseToLocal(const nav_2d_msgs::Pose2DStamped& pose);
173173

174-
nav_2d_msgs::Path2D global_plan_; ///< Saved Global Plan
174+
175+
/**
176+
* @brief Reset the critics and other plugins, e.g. when getting a new plan,
177+
* or starting the next path segment.
178+
*/
179+
virtual void resetPlugins();
180+
181+
std::vector<nav_2d_msgs::Path2D> global_plan_segments_; ///< Path segments of same movement direction (forward/backward/rotation only)
182+
nav_2d_msgs::Path2D global_plan_; ///< The currently active segment of the plan, or the whole plan if path segmentation is disabled.
183+
175184
nav_2d_msgs::Pose2DStamped goal_pose_; ///< Saved Goal Pose
185+
nav_2d_msgs::Pose2DStamped intermediate_goal_pose_; ///< Goal of current path segment
186+
176187
bool prune_plan_;
177188
double prune_distance_;
178189
bool debug_trajectory_details_;

dwb_local_planner/src/dwb_local_planner.cpp

+173-10
Original file line numberDiff line numberDiff line change
@@ -148,11 +148,37 @@ bool DWBLocalPlanner::isGoalReached(const nav_2d_msgs::Pose2DStamped& pose, cons
148148

149149
// Update time stamp of goal pose
150150
goal_pose_.header.stamp = pose.header.stamp;
151+
intermediate_goal_pose_.header.stamp = pose.header.stamp;
151152

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);
153158
if (ret)
154159
{
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+
}
156182
}
157183
return ret;
158184
}
@@ -161,20 +187,156 @@ void DWBLocalPlanner::setGoalPose(const nav_2d_msgs::Pose2DStamped& goal_pose)
161187
{
162188
ROS_INFO_NAMED("DWBLocalPlanner", "New Goal Received.");
163189
goal_pose_ = goal_pose;
164-
traj_generator_->reset();
165-
goal_checker_->reset();
166-
for (TrajectoryCritic::Ptr critic : critics_)
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.
193+
}
194+
195+
void DWBLocalPlanner::setPlan(const nav_2d_msgs::Path2D& path)
196+
{
197+
bool split_path;
198+
planner_nh_.param("split_path", split_path, false);
199+
200+
global_plan_segments_.clear();
201+
202+
if (split_path)
167203
{
168-
critic->reset();
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+
segment.poses[1].x - segment.poses[0].x,
252+
segment.poses[1].y - segment.poses[0].y
253+
};
254+
double v2[2] = {
255+
cos(segment.poses[0].theta),
256+
sin(segment.poses[0].theta)
257+
};
258+
double d = v1[0] * v2[0] + v1[1] * v2[1]; // dotproduct of the vectors. if < 0, the angle is over 90 degrees.
259+
bool backwards = (d < 0);
260+
bool onlyRotation = (d*d) < 1e-10; // if the dotproduct is zero, the two positions are equal
261+
// and the plan is to rotate on the spot. Since dwb would
262+
// enthusiastically speed up at the start of a trajectory,
263+
// even if it starts with in-place-rotation, it would
264+
// miss the path by a lot. So lets split the path into
265+
// forwards / backwards / onlyRotation.
266+
267+
268+
// add more poses while they lead into the same direction (driving forwards/backwards/onlyRotation)
269+
while (copy.poses.size() > 0)
270+
{
271+
// vector from the last pose in the segment to the next in the path
272+
double v1[2] = {
273+
copy.poses[0].x - segment.poses.back().x,
274+
copy.poses[0].y - segment.poses.back().y
275+
};
276+
// orientation at the last pose in the segment
277+
double v2[2] = {
278+
cos(segment.poses.back().theta),
279+
sin(segment.poses.back().theta)
280+
};
281+
double d = v1[0] * v2[0] + v1[1] * v2[1]; // dotproduct of the vectors. if < 0, the angle is over 90 degrees.
282+
bool b = (d < 0);
283+
bool rot = (d*d) < 1e-10;
284+
285+
if (b == backwards && rot == onlyRotation)
286+
{
287+
// same direction -> just add the pose
288+
segment.poses.push_back(copy.poses[0]);
289+
copy.poses.erase(copy.poses.begin());
290+
}
291+
else
292+
{
293+
// direction changes -> add the last pose of the last segment back to
294+
// the path, to start a new segment at the end of the last
295+
copy.poses.insert(copy.poses.begin(), segment.poses.back());
296+
break;
297+
}
298+
}
299+
300+
// add the created segment to the list
301+
global_plan_segments_.push_back(segment);
302+
}
303+
304+
ROS_INFO_STREAM("Split path into " << global_plan_segments_.size() << " segments.");
169305
}
306+
else
307+
{
308+
// split_path option is disabled, hence there is only one segment, which
309+
// is the complete path.
310+
global_plan_segments_.push_back(path);
311+
}
312+
313+
// set the global_plan_ to be the first segment
314+
global_plan_ = global_plan_segments_[0];
315+
global_plan_segments_.erase(global_plan_segments_.begin());
316+
317+
// publish not the complete path, but only the first segment.
318+
pub_.publishGlobalPlan(global_plan_);
319+
320+
// set the intermediate goal
321+
intermediate_goal_pose_.header = global_plan_.header;
322+
intermediate_goal_pose_.pose = global_plan_.poses.back();
323+
324+
resetPlugins();
325+
// prepare(...) to initialize the critics for the new segment does not need
326+
// to be called here, as it is called at every computeVelocityCommands-call.
170327
}
171328

172-
void DWBLocalPlanner::setPlan(const nav_2d_msgs::Path2D& path)
329+
void DWBLocalPlanner::resetPlugins()
173330
{
174-
pub_.publishGlobalPlan(path);
175-
global_plan_ = path;
331+
traj_generator_->reset();
332+
goal_checker_->reset();
333+
for(TrajectoryCritic::Ptr critic : critics_)
334+
{
335+
critic->reset();
336+
}
176337
}
177338

339+
178340
nav_2d_msgs::Twist2DStamped DWBLocalPlanner::computeVelocityCommands(const nav_2d_msgs::Pose2DStamped& pose,
179341
const nav_2d_msgs::Twist2D& velocity)
180342
{
@@ -209,9 +371,10 @@ void DWBLocalPlanner::prepare(const nav_2d_msgs::Pose2DStamped& pose, const nav_
209371

210372
// Update time stamp of goal pose
211373
goal_pose_.header.stamp = pose.header.stamp;
374+
intermediate_goal_pose_.header.stamp = pose.header.stamp;
212375

213376
geometry_msgs::Pose2D local_start_pose = transformPoseToLocal(pose),
214-
local_goal_pose = transformPoseToLocal(goal_pose_);
377+
local_goal_pose = transformPoseToLocal(intermediate_goal_pose_);
215378

216379
pub_.publishInputParams(costmap_->getInfo(), local_start_pose, velocity, local_goal_pose);
217380

0 commit comments

Comments
 (0)