Skip to content

Commit 2018157

Browse files
committed
fix(start/goal_planner): bug of autoware prefix and current_pose
Signed-off-by: Shumpei Wakabayashi <shumpei.wakabayashi@tier4.jp>
1 parent 35d1ecc commit 2018157

File tree

2 files changed

+4
-4
lines changed

2 files changed

+4
-4
lines changed

planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -276,7 +276,7 @@ void GoalPlannerModule::onTimer()
276276
// calculate absolute maximum curvature of parking path(start pose to end pose) for path
277277
// priority
278278
const std::vector<double> curvatures =
279-
autoware::motion_utils::calcCurvature(pull_over_path->getParkingPath().points);
279+
motion_utils::calcCurvature(pull_over_path->getParkingPath().points);
280280
pull_over_path->max_curvature = std::abs(*std::max_element(
281281
curvatures.begin(), curvatures.end(),
282282
[](const double & a, const double & b) { return std::abs(a) < std::abs(b); }));

planning/behavior_path_start_planner_module/src/start_planner_module.cpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -366,7 +366,7 @@ bool StartPlannerModule::isPreventingRearVehicleFromPassingThrough() const
366366
const auto & current_pose = planner_data_->self_odometry->pose.pose;
367367
std::vector<Pose> preventing_check_pose{current_pose};
368368
const auto min_stop_distance =
369-
autoware::behavior_path_planner::utils::parking_departure::calcFeasibleDecelDistance(
369+
behavior_path_planner::utils::parking_departure::calcFeasibleDecelDistance(
370370
planner_data_, parameters_->maximum_deceleration_for_stop, parameters_->maximum_jerk_for_stop,
371371
0.0);
372372
debug_data_.estimated_stop_pose.reset(); // debug
@@ -500,7 +500,7 @@ bool StartPlannerModule::isPreventingRearVehicleFromPassingThrough(const Pose &
500500
// Check backwards just in case the Vehicle behind ego is in a different lanelet
501501
constexpr double backwards_length = 200.0;
502502
const auto prev_lanes = behavior_path_planner::utils::getBackwardLanelets(
503-
*route_handler, target_lanes, current_pose, backwards_length);
503+
*route_handler, target_lanes, ego_pose, backwards_length);
504504
// return all the relevant lanelets
505505
lanelet::ConstLanelets relevant_lanelets{closest_lanelet_const};
506506
relevant_lanelets.insert(relevant_lanelets.end(), prev_lanes.begin(), prev_lanes.end());
@@ -527,7 +527,7 @@ bool StartPlannerModule::isPreventingRearVehicleFromPassingThrough(const Pose &
527527
target_objects_on_lane.on_current_lane.begin(), target_objects_on_lane.on_current_lane.end(),
528528
[&](const auto & o) {
529529
const auto arc_length = motion_utils::calcSignedArcLength(
530-
centerline_path.points, current_pose.position, o.initial_pose.pose.position);
530+
centerline_path.points, ego_pose.position, o.initial_pose.pose.position);
531531
if (arc_length > 0.0) return;
532532
if (std::abs(arc_length) >= std::abs(arc_length_to_closet_object)) return;
533533
arc_length_to_closet_object = arc_length;

0 commit comments

Comments
 (0)