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