Skip to content

Commit 1cf58eb

Browse files
feat(autonomous_emergency_braking): make hull markers 3d (#8930)
make hull markers 3d Signed-off-by: Daniel Sanchez <danielsanchezaran@gmail.com>
1 parent d8dc258 commit 1cf58eb

File tree

4 files changed

+42
-5
lines changed

4 files changed

+42
-5
lines changed

control/autoware_autonomous_emergency_braking/include/autoware/autonomous_emergency_braking/node.hpp

+2-1
Original file line numberDiff line numberDiff line change
@@ -65,6 +65,7 @@ using sensor_msgs::msg::Imu;
6565
using sensor_msgs::msg::PointCloud2;
6666
using PointCloud = pcl::PointCloud<pcl::PointXYZ>;
6767
using autoware::universe_utils::Polygon2d;
68+
using autoware::universe_utils::Polygon3d;
6869
using autoware::vehicle_info_utils::VehicleInfo;
6970
using diagnostic_updater::DiagnosticStatusWrapper;
7071
using diagnostic_updater::Updater;
@@ -496,7 +497,7 @@ class AEB : public rclcpp::Node
496497
* @param debug_markers Marker array for debugging
497498
*/
498499
void addClusterHullMarkers(
499-
const rclcpp::Time & current_time, const std::vector<Polygon2d> & hulls,
500+
const rclcpp::Time & current_time, const std::vector<Polygon3d> & hulls,
500501
const colorTuple & debug_colors, const std::string & ns, MarkerArray & debug_markers);
501502

502503
/**

control/autoware_autonomous_emergency_braking/include/autoware/autonomous_emergency_braking/utils.hpp

+9
Original file line numberDiff line numberDiff line change
@@ -42,6 +42,7 @@
4242
namespace autoware::motion::control::autonomous_emergency_braking::utils
4343
{
4444
using autoware::universe_utils::Polygon2d;
45+
using autoware::universe_utils::Polygon3d;
4546
using autoware_perception_msgs::msg::PredictedObject;
4647
using autoware_perception_msgs::msg::PredictedObjects;
4748
using geometry_msgs::msg::Point;
@@ -105,6 +106,14 @@ std::optional<geometry_msgs::msg::TransformStamped> getTransform(
105106
*/
106107
void fillMarkerFromPolygon(
107108
const std::vector<Polygon2d> & polygons, visualization_msgs::msg::Marker & polygon_marker);
109+
110+
/**
111+
* @brief Get the predicted object's shape as a geometry polygon
112+
* @param polygons vector of Polygon3d
113+
* @param polygon_marker marker to be filled with polygon points
114+
*/
115+
void fillMarkerFromPolygon(
116+
const std::vector<Polygon3d> & polygons, visualization_msgs::msg::Marker & polygon_marker);
108117
} // namespace autoware::motion::control::autonomous_emergency_braking::utils
109118

110119
#endif // AUTOWARE__AUTONOMOUS_EMERGENCY_BRAKING__UTILS_HPP_

control/autoware_autonomous_emergency_braking/src/node.cpp

+14-4
Original file line numberDiff line numberDiff line change
@@ -59,6 +59,7 @@ namespace autoware::motion::control::autonomous_emergency_braking
5959
{
6060
using autoware::motion::control::autonomous_emergency_braking::utils::convertObjToPolygon;
6161
using autoware::universe_utils::Point2d;
62+
using autoware::universe_utils::Point3d;
6263
using diagnostic_msgs::msg::DiagnosticStatus;
6364
namespace bg = boost::geometry;
6465

@@ -71,6 +72,16 @@ void appendPointToPolygon(Polygon2d & polygon, const geometry_msgs::msg::Point &
7172
bg::append(polygon.outer(), point);
7273
}
7374

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+
7485
Polygon2d createPolygon(
7586
const geometry_msgs::msg::Pose & base_pose, const geometry_msgs::msg::Pose & next_pose,
7687
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
580591
// collision happens
581592
ObjectData collision_data = closest_object;
582593
collision_data.rss = rss_dist;
583-
collision_data.distance_to_object = closest_object.distance_to_object;
584594
collision_data_keeper_.setCollisionData(collision_data);
585595
return true;
586596
}
@@ -787,7 +797,7 @@ void AEB::getPointsBelongingToClusterHulls(
787797
ec.extract(cluster_idx);
788798
return cluster_idx;
789799
});
790-
std::vector<Polygon2d> hull_polygons;
800+
std::vector<Polygon3d> hull_polygons;
791801
for (const auto & indices : cluster_indices) {
792802
PointCloud::Ptr cluster(new PointCloud);
793803
bool cluster_surpasses_threshold_height{false};
@@ -806,7 +816,7 @@ void AEB::getPointsBelongingToClusterHulls(
806816
std::vector<pcl::Vertices> polygons;
807817
PointCloud::Ptr surface_hull(new PointCloud);
808818
hull.reconstruct(*surface_hull, polygons);
809-
Polygon2d hull_polygon;
819+
Polygon3d hull_polygon;
810820
for (const auto & p : *surface_hull) {
811821
points_belonging_to_cluster_hulls->push_back(p);
812822
if (publish_debug_markers_) {
@@ -900,7 +910,7 @@ void AEB::cropPointCloudWithEgoFootprintPath(
900910
}
901911

902912
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,
904914
const colorTuple & debug_colors, const std::string & ns, MarkerArray & debug_markers)
905915
{
906916
autoware::universe_utils::ScopedTimeTrack st(__func__, *time_keeper_);

control/autoware_autonomous_emergency_braking/src/utils.cpp

+17
Original file line numberDiff line numberDiff line change
@@ -186,4 +186,21 @@ void fillMarkerFromPolygon(
186186
}
187187
}
188188

189+
void fillMarkerFromPolygon(
190+
const std::vector<Polygon3d> & polygons, visualization_msgs::msg::Marker & polygon_marker)
191+
{
192+
for (const auto & poly : polygons) {
193+
for (size_t dp_idx = 0; dp_idx < poly.outer().size(); ++dp_idx) {
194+
const auto & boost_cp = poly.outer().at(dp_idx);
195+
const auto & boost_np = poly.outer().at((dp_idx + 1) % poly.outer().size());
196+
const auto curr_point =
197+
autoware::universe_utils::createPoint(boost_cp.x(), boost_cp.y(), boost_cp.z());
198+
const auto next_point =
199+
autoware::universe_utils::createPoint(boost_np.x(), boost_np.y(), boost_np.z());
200+
polygon_marker.points.push_back(curr_point);
201+
polygon_marker.points.push_back(next_point);
202+
}
203+
}
204+
}
205+
189206
} // namespace autoware::motion::control::autonomous_emergency_braking::utils

0 commit comments

Comments
 (0)