Skip to content

Commit 70e4cd6

Browse files
fix(lane_change): cap ego's predicted path velocity (RT1-8505) (#9341)
* fix(lane_change): cap ego's predicted path velocity (RT1-8505) Signed-off-by: Zulfaqar Azmi <zulfaqar.azmi@tier4.jp> * properly cap based on 0.0 instead of min lc vel Signed-off-by: Zulfaqar Azmi <zulfaqar.azmi@tier4.jp> * fix build error Signed-off-by: Zulfaqar Azmi <zulfaqar.azmi@tier4.jp> --------- Signed-off-by: Zulfaqar Azmi <zulfaqar.azmi@tier4.jp>
1 parent 996336f commit 70e4cd6

File tree

3 files changed

+32
-38
lines changed
  • planning/behavior_path_planner/autoware_behavior_path_lane_change_module

3 files changed

+32
-38
lines changed

Diff for: planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/utils.hpp

+3-4
Original file line numberDiff line numberDiff line change
@@ -116,10 +116,9 @@ CandidateOutput assignToCandidate(
116116
std::optional<lanelet::ConstLanelet> get_lane_change_target_lane(
117117
const CommonDataPtr & common_data_ptr, const lanelet::ConstLanelets & current_lanes);
118118

119-
std::vector<PoseWithVelocityStamped> convertToPredictedPath(
120-
const LaneChangePath & lane_change_path, const Twist & vehicle_twist, const Pose & pose,
121-
const double lane_changing_acceleration, const BehaviorPathPlannerParameters & common_parameters,
122-
const LaneChangeParameters & lane_change_parameters, const double resolution);
119+
std::vector<PoseWithVelocityStamped> convert_to_predicted_path(
120+
const CommonDataPtr & common_data_ptr, const LaneChangePath & lane_change_path,
121+
const double lane_changing_acceleration);
123122

124123
bool isParkedObject(
125124
const PathWithLaneId & path, const RouteHandler & route_handler,

Diff for: planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp

+2-10
Original file line numberDiff line numberDiff line change
@@ -1809,8 +1809,6 @@ bool NormalLaneChange::has_collision_with_decel_patterns(
18091809
return false;
18101810
}
18111811

1812-
const auto current_pose = common_data_ptr_->get_ego_pose();
1813-
const auto current_twist = common_data_ptr_->get_ego_twist();
18141812
const auto bpp_param = *common_data_ptr_->bpp_param_ptr;
18151813
const auto global_min_acc = bpp_param.min_acc;
18161814
const auto lane_changing_acc = lane_change_path.info.longitudinal_acceleration.lane_changing;
@@ -1827,17 +1825,11 @@ bool NormalLaneChange::has_collision_with_decel_patterns(
18271825
acceleration_values.begin(), acceleration_values.end(), acceleration_values.begin(),
18281826
[&](double n) { return lane_changing_acc + n * acc_resolution; });
18291827

1830-
const auto time_resolution =
1831-
lane_change_parameters_->safety.collision_check.prediction_time_resolution;
1832-
18331828
const auto stopped_obj_vel_th = lane_change_parameters_->safety.th_stopped_object_velocity;
18341829
const auto all_collided = std::all_of(
18351830
acceleration_values.begin(), acceleration_values.end(), [&](const auto acceleration) {
1836-
const auto ego_predicted_path = utils::lane_change::convertToPredictedPath(
1837-
lane_change_path, current_twist, current_pose, acceleration, bpp_param,
1838-
*lane_change_parameters_, time_resolution);
1839-
const auto debug_predicted_path =
1840-
utils::path_safety_checker::convertToPredictedPath(ego_predicted_path, time_resolution);
1831+
const auto ego_predicted_path = utils::lane_change::convert_to_predicted_path(
1832+
common_data_ptr_, lane_change_path, acceleration);
18411833

18421834
return std::any_of(objects.begin(), objects.end(), [&](const auto & obj) {
18431835
const auto selected_rss_param = (obj.initial_twist.linear.x <= stopped_obj_vel_th)

Diff for: planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp

+27-24
Original file line numberDiff line numberDiff line change
@@ -599,52 +599,55 @@ std::optional<lanelet::ConstLanelet> get_lane_change_target_lane(
599599
return route_handler_ptr->getLaneChangeTargetExceptPreferredLane(current_lanes, direction);
600600
}
601601

602-
std::vector<PoseWithVelocityStamped> convertToPredictedPath(
603-
const LaneChangePath & lane_change_path, const Twist & vehicle_twist, const Pose & vehicle_pose,
604-
const double lane_changing_acceleration, const BehaviorPathPlannerParameters & common_parameters,
605-
const LaneChangeParameters & lane_change_parameters, const double resolution)
602+
std::vector<PoseWithVelocityStamped> convert_to_predicted_path(
603+
const CommonDataPtr & common_data_ptr, const LaneChangePath & lane_change_path,
604+
const double lane_changing_acceleration)
606605
{
607606
if (lane_change_path.path.points.empty()) {
608607
return {};
609608
}
610609

611610
const auto & path = lane_change_path.path;
612-
const auto prepare_acc = lane_change_path.info.longitudinal_acceleration.prepare;
613-
const auto duration = lane_change_path.info.duration.sum();
614-
const auto prepare_time = lane_change_path.info.duration.prepare;
615-
const auto & minimum_lane_changing_velocity =
616-
lane_change_parameters.trajectory.min_lane_changing_velocity;
617-
611+
const auto & vehicle_pose = common_data_ptr->get_ego_pose();
612+
const auto & bpp_param_ptr = common_data_ptr->bpp_param_ptr;
618613
const auto nearest_seg_idx =
619614
autoware::motion_utils::findFirstNearestSegmentIndexWithSoftConstraints(
620-
path.points, vehicle_pose, common_parameters.ego_nearest_dist_threshold,
621-
common_parameters.ego_nearest_yaw_threshold);
615+
path.points, vehicle_pose, bpp_param_ptr->ego_nearest_dist_threshold,
616+
bpp_param_ptr->ego_nearest_yaw_threshold);
622617

623-
std::vector<PoseWithVelocityStamped> predicted_path;
624618
const auto vehicle_pose_frenet =
625619
convertToFrenetPoint(path.points, vehicle_pose.position, nearest_seg_idx);
626-
const double initial_velocity = std::abs(vehicle_twist.linear.x);
620+
621+
const auto initial_velocity = common_data_ptr->get_ego_speed();
622+
const auto prepare_acc = lane_change_path.info.longitudinal_acceleration.prepare;
623+
const auto duration = lane_change_path.info.duration.sum();
624+
const auto prepare_time = lane_change_path.info.duration.prepare;
625+
const auto & lc_param_ptr = common_data_ptr->lc_param_ptr;
626+
const auto resolution = lc_param_ptr->safety.collision_check.prediction_time_resolution;
627+
std::vector<PoseWithVelocityStamped> predicted_path;
627628

628629
// prepare segment
629630
for (double t = 0.0; t < prepare_time; t += resolution) {
630-
const double velocity =
631-
std::max(initial_velocity + prepare_acc * t, minimum_lane_changing_velocity);
632-
const double length = initial_velocity * t + 0.5 * prepare_acc * t * t;
631+
const auto velocity =
632+
std::clamp(initial_velocity + prepare_acc * t, 0.0, lane_change_path.info.velocity.prepare);
633+
const auto length = initial_velocity * t + 0.5 * prepare_acc * t * t;
633634
const auto pose = autoware::motion_utils::calcInterpolatedPose(
634635
path.points, vehicle_pose_frenet.length + length);
635636
predicted_path.emplace_back(t, pose, velocity);
636637
}
637638

638639
// lane changing segment
639-
const double lane_changing_velocity =
640-
std::max(initial_velocity + prepare_acc * prepare_time, minimum_lane_changing_velocity);
641-
const double offset =
640+
const auto lane_changing_velocity = std::clamp(
641+
initial_velocity + prepare_acc * prepare_time, 0.0, lane_change_path.info.velocity.prepare);
642+
const auto offset =
642643
initial_velocity * prepare_time + 0.5 * prepare_acc * prepare_time * prepare_time;
643644
for (double t = prepare_time; t < duration; t += resolution) {
644-
const double delta_t = t - prepare_time;
645-
const double velocity = lane_changing_velocity + lane_changing_acceleration * delta_t;
646-
const double length = lane_changing_velocity * delta_t +
647-
0.5 * lane_changing_acceleration * delta_t * delta_t + offset;
645+
const auto delta_t = t - prepare_time;
646+
const auto velocity = std::clamp(
647+
lane_changing_velocity + lane_changing_acceleration * delta_t, 0.0,
648+
lane_change_path.info.velocity.lane_changing);
649+
const auto length = lane_changing_velocity * delta_t +
650+
0.5 * lane_changing_acceleration * delta_t * delta_t + offset;
648651
const auto pose = autoware::motion_utils::calcInterpolatedPose(
649652
path.points, vehicle_pose_frenet.length + length);
650653
predicted_path.emplace_back(t, pose, velocity);

0 commit comments

Comments
 (0)