@@ -59,6 +59,7 @@ namespace autoware::motion::control::autonomous_emergency_braking
59
59
{
60
60
using autoware::motion::control::autonomous_emergency_braking::utils::convertObjToPolygon;
61
61
using autoware::universe_utils::Point2d;
62
+ using autoware::universe_utils::Point3d;
62
63
using diagnostic_msgs::msg::DiagnosticStatus;
63
64
namespace bg = boost::geometry;
64
65
@@ -71,6 +72,16 @@ void appendPointToPolygon(Polygon2d & polygon, const geometry_msgs::msg::Point &
71
72
bg::append (polygon.outer (), point);
72
73
}
73
74
75
+ void appendPointToPolygon (Polygon3d & polygon, const geometry_msgs::msg::Point & geom_point)
76
+ {
77
+ Point3d point;
78
+ point.x () = geom_point.x ;
79
+ point.y () = geom_point.y ;
80
+ point.z () = geom_point.z ;
81
+
82
+ bg::append (polygon.outer (), point);
83
+ }
84
+
74
85
Polygon2d createPolygon (
75
86
const geometry_msgs::msg::Pose & base_pose, const geometry_msgs::msg::Pose & next_pose,
76
87
const autoware::vehicle_info_utils::VehicleInfo & vehicle_info, const double expand_width)
@@ -580,7 +591,6 @@ bool AEB::hasCollision(const double current_v, const ObjectData & closest_object
580
591
// collision happens
581
592
ObjectData collision_data = closest_object;
582
593
collision_data.rss = rss_dist;
583
- collision_data.distance_to_object = closest_object.distance_to_object ;
584
594
collision_data_keeper_.setCollisionData (collision_data);
585
595
return true ;
586
596
}
@@ -787,7 +797,7 @@ void AEB::getPointsBelongingToClusterHulls(
787
797
ec.extract (cluster_idx);
788
798
return cluster_idx;
789
799
});
790
- std::vector<Polygon2d > hull_polygons;
800
+ std::vector<Polygon3d > hull_polygons;
791
801
for (const auto & indices : cluster_indices) {
792
802
PointCloud::Ptr cluster (new PointCloud);
793
803
bool cluster_surpasses_threshold_height{false };
@@ -806,7 +816,7 @@ void AEB::getPointsBelongingToClusterHulls(
806
816
std::vector<pcl::Vertices> polygons;
807
817
PointCloud::Ptr surface_hull (new PointCloud);
808
818
hull.reconstruct (*surface_hull, polygons);
809
- Polygon2d hull_polygon;
819
+ Polygon3d hull_polygon;
810
820
for (const auto & p : *surface_hull) {
811
821
points_belonging_to_cluster_hulls->push_back (p);
812
822
if (publish_debug_markers_) {
@@ -900,7 +910,7 @@ void AEB::cropPointCloudWithEgoFootprintPath(
900
910
}
901
911
902
912
void AEB::addClusterHullMarkers (
903
- const rclcpp::Time & current_time, const std::vector<Polygon2d > & hulls,
913
+ const rclcpp::Time & current_time, const std::vector<Polygon3d > & hulls,
904
914
const colorTuple & debug_colors, const std::string & ns, MarkerArray & debug_markers)
905
915
{
906
916
autoware::universe_utils::ScopedTimeTrack st (__func__, *time_keeper_);
0 commit comments