@@ -408,11 +408,20 @@ PlannerPlugin::LaneletRoute DefaultPlanner::plan(const RoutePoints & points)
408
408
409
409
LaneletRoute route_msg;
410
410
RouteSections route_sections;
411
+ RoutePoints check_points{points};
412
+
413
+ if (param_.enable_correct_goal_pose ) {
414
+ for (size_t i = 1 ; i < check_points.size (); ++i) {
415
+ check_points.at (i) = get_closest_centerline_pose (
416
+ lanelet::utils::query::laneletLayer (lanelet_map_ptr_), check_points.at (i), vehicle_info_);
417
+ }
418
+ }
411
419
412
420
lanelet::ConstLanelets all_route_lanelets;
413
- for (std::size_t i = 1 ; i < points.size (); i++) {
414
- const auto start_check_point = points.at (i - 1 );
415
- const auto goal_check_point = points.at (i);
421
+ for (std::size_t i = 1 ; i < check_points.size (); i++) {
422
+ const auto start_check_point = check_points.at (i - 1 );
423
+ const auto goal_check_point = check_points.at (i);
424
+
416
425
lanelet::ConstLanelets path_lanelets;
417
426
if (!route_handler_.planPathLaneletsBetweenCheckpoints (
418
427
start_check_point, goal_check_point, &path_lanelets, param_.consider_no_drivable_lanes )) {
@@ -429,13 +438,7 @@ PlannerPlugin::LaneletRoute DefaultPlanner::plan(const RoutePoints & points)
429
438
}
430
439
route_handler_.setRouteLanelets (all_route_lanelets);
431
440
432
- auto goal_pose = points.back ();
433
- if (param_.enable_correct_goal_pose ) {
434
- goal_pose = get_closest_centerline_pose (
435
- lanelet::utils::query::laneletLayer (lanelet_map_ptr_), goal_pose, vehicle_info_);
436
- }
437
-
438
- if (!is_goal_valid (goal_pose, all_route_lanelets)) {
441
+ if (!is_goal_valid (check_points.back (), all_route_lanelets)) {
439
442
RCLCPP_WARN (logger, " Goal is not valid! Please check position and angle of goal_pose" );
440
443
return route_msg;
441
444
}
@@ -445,12 +448,12 @@ PlannerPlugin::LaneletRoute DefaultPlanner::plan(const RoutePoints & points)
445
448
return route_msg;
446
449
}
447
450
448
- const auto refined_goal = refine_goal_height (goal_pose , route_sections);
451
+ const auto refined_goal = refine_goal_height (check_points. back () , route_sections);
449
452
RCLCPP_DEBUG (logger, " Goal Pose Z : %lf" , refined_goal.position .z );
450
453
451
454
// The header is assigned by mission planner.
452
- route_msg.start_pose = points .front ();
453
- route_msg.goal_pose = refined_goal ;
455
+ route_msg.start_pose = check_points .front ();
456
+ route_msg.goal_pose = check_points. back () ;
454
457
route_msg.segments = route_sections;
455
458
return route_msg;
456
459
}
0 commit comments