@@ -197,56 +197,47 @@ geometry_msgs::msg::TwistStamped GracefulController::computeVelocityCommands(
197
197
}
198
198
199
199
// Find a valid target pose and its trajectory
200
- bool valid_target_pose_found = false ;
201
200
nav_msgs::msg::Path local_plan;
202
-
203
- // Calculate target pose through lookahead interpolation to get most accurate
204
- // lookahead point, if possible
205
- double dist_to_target = params_->max_lookahead ;
206
- geometry_msgs::msg::PoseStamped target_pose = nav2_util::getLookAheadPoint (
207
- dist_to_target, transformed_plan, params_->interpolate_after_goal );
208
-
209
- valid_target_pose_found = validateTargetPose (
210
- target_pose, dist_to_target, dist_to_goal, local_plan, costmap_transform, cmd_vel);
211
-
212
- if (!valid_target_pose_found) {
213
- // If target pose through interpolation is not valid
214
- // Work back from the end of plan to find valid target pose
215
- // Precompute distance to candidate poses
216
- std::vector<double > target_distances;
217
- computeDistanceAlongPath (transformed_plan.poses , target_distances);
218
-
219
- for (int i = transformed_plan.poses .size () - 1 ; i >= 0 ; --i) {
201
+ bool valid_target_pose_found;
202
+ geometry_msgs::msg::PoseStamped target_pose;
203
+
204
+ double dist_to_target;
205
+ std::vector<double > target_distances;
206
+ computeDistanceAlongPath (transformed_plan.poses , target_distances);
207
+
208
+ for (int i = transformed_plan.poses .size (); i >= 0 ; --i) {
209
+ if (i == static_cast <int >(transformed_plan.poses .size ())) {
210
+ // Calculate target pose through lookahead interpolation to get most accurate
211
+ // lookahead point, if possible
212
+ dist_to_target = params_->max_lookahead ;
213
+ target_pose = nav2_util::getLookAheadPoint (
214
+ dist_to_target, transformed_plan, params_->interpolate_after_goal );
215
+ } else {
220
216
// Underlying control law needs a single target pose, which should:
221
217
// * Be as far away as possible from the robot (for smoothness)
222
218
// * But no further than the max_lookahed_ distance
223
219
// * Be feasible to reach in a collision free manner
224
- target_pose = transformed_plan.poses [i];
225
220
dist_to_target = target_distances[i];
221
+ target_pose = transformed_plan.poses [i];
222
+ }
226
223
227
- valid_target_pose_found = validateTargetPose (
224
+ valid_target_pose_found = validateTargetPose (
228
225
target_pose, dist_to_target, dist_to_goal, local_plan, costmap_transform, cmd_vel);
229
- if (valid_target_pose_found) {
230
- break ;
231
- }
232
- }
233
- } else {
234
- valid_target_pose_found = true ;
235
- }
236
226
237
- // Compute velocity at this moment if valid target pose is found
238
- if (valid_target_pose_found) {
239
- // Publish the selected target_pose
240
- motion_target_pub_->publish (target_pose);
241
- // Publish marker for slowdown radius around motion target for debugging / visualization
242
- auto slowdown_marker = nav2_graceful_controller::createSlowdownMarker (
243
- target_pose, params_->slowdown_radius );
244
- slowdown_pub_->publish (slowdown_marker);
245
- // Publish the local plan
246
- local_plan.header = transformed_plan.header ;
247
- local_plan_pub_->publish (local_plan);
248
- // Successfully found velocity command
249
- return cmd_vel;
227
+ // Compute velocity at this moment if valid target pose is found
228
+ if (valid_target_pose_found) {
229
+ // Publish the selected target_pose
230
+ motion_target_pub_->publish (target_pose);
231
+ // Publish marker for slowdown radius around motion target for debugging / visualization
232
+ auto slowdown_marker = nav2_graceful_controller::createSlowdownMarker (
233
+ target_pose, params_->slowdown_radius );
234
+ slowdown_pub_->publish (slowdown_marker);
235
+ // Publish the local plan
236
+ local_plan.header = transformed_plan.header ;
237
+ local_plan_pub_->publish (local_plan);
238
+ // Successfully found velocity command
239
+ return cmd_vel;
240
+ }
250
241
}
251
242
252
243
throw nav2_core::NoValidControl (" Collision detected in trajectory" );
0 commit comments