@@ -552,9 +552,10 @@ std::vector<Polygon2d> ObstacleCruisePlannerNode::createOneStepPolygons(
552
552
const geometry_msgs::msg::Pose & current_ego_pose, const double lat_margin) const
553
553
{
554
554
const auto & p = behavior_determination_param_;
555
- const bool is_enable_current_pose_consideration = p.enable_to_consider_current_pose ;
556
- const double step_length = p.decimate_trajectory_step_length ;
557
- const double time_to_convergence = p.time_to_convergence ;
555
+
556
+ const double front_length = vehicle_info.max_longitudinal_offset_m ;
557
+ const double rear_length = vehicle_info.rear_overhang_m ;
558
+ const double vehicle_width = vehicle_info.vehicle_width_m ;
558
559
559
560
const size_t nearest_idx =
560
561
motion_utils::findNearestSegmentIndex (traj_points, current_ego_pose.position );
@@ -563,41 +564,68 @@ std::vector<Polygon2d> ObstacleCruisePlannerNode::createOneStepPolygons(
563
564
tier4_autoware_utils::inverseTransformPose (current_ego_pose, nearest_pose);
564
565
const double current_ego_lat_error = current_ego_pose_error.position .y ;
565
566
const double current_ego_yaw_error = tf2::getYaw (current_ego_pose_error.orientation );
566
- double time_elapsed = 0.0 ;
567
-
568
- std::vector<Polygon2d> polygons;
569
- std::vector<geometry_msgs::msg::Pose> last_poses = {traj_points.at (0 ).pose };
570
- if (is_enable_current_pose_consideration) {
571
- last_poses.push_back (current_ego_pose);
572
- }
567
+ double time_elapsed{0.0 };
573
568
569
+ std::vector<Polygon2d> output_polygons;
570
+ Polygon2d tmp_polys{};
574
571
for (size_t i = 0 ; i < traj_points.size (); ++i) {
575
572
std::vector<geometry_msgs::msg::Pose> current_poses = {traj_points.at (i).pose };
576
573
577
574
// estimate the future ego pose with assuming that the pose error against the reference path
578
575
// will decrease to zero by the time_to_convergence
579
- if (is_enable_current_pose_consideration && time_elapsed < time_to_convergence) {
580
- const double rem_ratio = (time_to_convergence - time_elapsed) / time_to_convergence;
576
+ if (p. enable_to_consider_current_pose && time_elapsed < p. time_to_convergence ) {
577
+ const double rem_ratio = (p. time_to_convergence - time_elapsed) / p. time_to_convergence ;
581
578
geometry_msgs::msg::Pose indexed_pose_err;
582
579
indexed_pose_err.set__orientation (
583
580
tier4_autoware_utils::createQuaternionFromYaw (current_ego_yaw_error * rem_ratio));
584
581
indexed_pose_err.set__position (
585
582
tier4_autoware_utils::createPoint (0.0 , current_ego_lat_error * rem_ratio, 0.0 ));
586
-
587
583
current_poses.push_back (
588
584
tier4_autoware_utils::transformPose (indexed_pose_err, traj_points.at (i).pose ));
589
-
590
585
if (traj_points.at (i).longitudinal_velocity_mps != 0.0 ) {
591
- time_elapsed += step_length / std::abs (traj_points.at (i).longitudinal_velocity_mps );
586
+ time_elapsed +=
587
+ p.decimate_trajectory_step_length / std::abs (traj_points.at (i).longitudinal_velocity_mps );
592
588
} else {
593
589
time_elapsed = std::numeric_limits<double >::max ();
594
590
}
595
591
}
596
- polygons.push_back (
597
- polygon_utils::createOneStepPolygon (last_poses, current_poses, vehicle_info, lat_margin));
598
- last_poses = current_poses;
592
+
593
+ Polygon2d idx_poly{};
594
+ for (const auto & pose : current_poses) {
595
+ if (i == 0 && traj_points.at (i).longitudinal_velocity_mps > 1e-3 ) {
596
+ boost::geometry::append (
597
+ idx_poly,
598
+ tier4_autoware_utils::toFootprint (pose, front_length, rear_length, vehicle_width)
599
+ .outer ());
600
+ boost::geometry::append (
601
+ idx_poly,
602
+ tier4_autoware_utils::fromMsg (tier4_autoware_utils::calcOffsetPose (
603
+ pose, front_length, vehicle_width * 0.5 + lat_margin, 0.0 )
604
+ .position )
605
+ .to_2d ());
606
+ boost::geometry::append (
607
+ idx_poly, tier4_autoware_utils::fromMsg (
608
+ tier4_autoware_utils::calcOffsetPose (
609
+ pose, front_length, -vehicle_width * 0.5 - lat_margin, 0.0 )
610
+ .position )
611
+ .to_2d ());
612
+ } else {
613
+ boost::geometry::append (
614
+ idx_poly, tier4_autoware_utils::toFootprint (
615
+ pose, front_length, rear_length, vehicle_width + lat_margin * 2.0 )
616
+ .outer ());
617
+ }
618
+ }
619
+
620
+ boost::geometry::append (tmp_polys, idx_poly.outer ());
621
+ Polygon2d hull_polygon;
622
+ boost::geometry::convex_hull (tmp_polys, hull_polygon);
623
+ boost::geometry::correct (hull_polygon);
624
+
625
+ output_polygons.push_back (hull_polygon);
626
+ tmp_polys = std::move (idx_poly);
599
627
}
600
- return polygons ;
628
+ return output_polygons ;
601
629
}
602
630
603
631
std::vector<Obstacle> ObstacleCruisePlannerNode::convertToObstacles (
0 commit comments