@@ -599,52 +599,55 @@ std::optional<lanelet::ConstLanelet> get_lane_change_target_lane(
599
599
return route_handler_ptr->getLaneChangeTargetExceptPreferredLane (current_lanes, direction);
600
600
}
601
601
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)
606
605
{
607
606
if (lane_change_path.path .points .empty ()) {
608
607
return {};
609
608
}
610
609
611
610
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 ;
618
613
const auto nearest_seg_idx =
619
614
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 );
622
617
623
- std::vector<PoseWithVelocityStamped> predicted_path;
624
618
const auto vehicle_pose_frenet =
625
619
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;
627
628
628
629
// prepare segment
629
630
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;
633
634
const auto pose = autoware::motion_utils::calcInterpolatedPose (
634
635
path.points , vehicle_pose_frenet.length + length);
635
636
predicted_path.emplace_back (t, pose, velocity);
636
637
}
637
638
638
639
// 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 =
642
643
initial_velocity * prepare_time + 0.5 * prepare_acc * prepare_time * prepare_time;
643
644
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;
648
651
const auto pose = autoware::motion_utils::calcInterpolatedPose (
649
652
path.points , vehicle_pose_frenet.length + length);
650
653
predicted_path.emplace_back (t, pose, velocity);
0 commit comments