23
23
#include < pcl_ros/transforms.hpp>
24
24
#include < rclcpp/rclcpp.hpp>
25
25
26
+ #include < autoware_perception_msgs/msg/predicted_objects.hpp>
26
27
#include < autoware_planning_msgs/msg/trajectory.hpp>
27
28
#include < autoware_system_msgs/msg/autoware_state.hpp>
28
29
#include < autoware_vehicle_msgs/msg/velocity_report.hpp>
@@ -68,6 +69,9 @@ using visualization_msgs::msg::Marker;
68
69
using visualization_msgs::msg::MarkerArray;
69
70
using Path = std::vector<geometry_msgs::msg::Pose>;
70
71
using Vector3 = geometry_msgs::msg::Vector3;
72
+ using autoware_perception_msgs::msg::PredictedObject;
73
+ using autoware_perception_msgs::msg::PredictedObjects;
74
+
71
75
struct ObjectData
72
76
{
73
77
rclcpp::Time stamp;
@@ -176,6 +180,13 @@ class CollisionDataKeeper
176
180
std::optional<double > calcObjectSpeedFromHistory (
177
181
const ObjectData & closest_object, const Path & path, const double current_ego_speed)
178
182
{
183
+ // in case the object comes from predicted objects info, we reuse the speed.
184
+ if (closest_object.velocity > 0.0 ) {
185
+ this ->setPreviousObjectData (closest_object);
186
+ this ->updateVelocityHistory (closest_object.velocity , closest_object.stamp );
187
+ return this ->getMedianObstacleVelocity ();
188
+ }
189
+
179
190
if (this ->checkPreviousObjectDataExpired ()) {
180
191
this ->setPreviousObjectData (closest_object);
181
192
this ->resetVelocityHistory ();
@@ -243,6 +254,8 @@ class AEB : public rclcpp::Node
243
254
autoware_universe_utils::InterProcessPollingSubscriber<Imu> sub_imu_{this , " ~/input/imu" };
244
255
autoware_universe_utils::InterProcessPollingSubscriber<Trajectory> sub_predicted_traj_{
245
256
this , " ~/input/predicted_trajectory" };
257
+ autoware_universe_utils::InterProcessPollingSubscriber<PredictedObjects> predicted_objects_sub_{
258
+ this , " ~/input/objects" };
246
259
autoware_universe_utils::InterProcessPollingSubscriber<AutowareState> sub_autoware_state_{
247
260
this , " /autoware/state" };
248
261
// publisher
@@ -275,6 +288,10 @@ class AEB : public rclcpp::Node
275
288
std::vector<ObjectData> & objects,
276
289
const pcl::PointCloud<pcl::PointXYZ>::Ptr obstacle_points_ptr);
277
290
291
+ void createObjectDataUsingPredictedObjects (
292
+ const Path & ego_path, const std::vector<Polygon2d> & ego_polys,
293
+ std::vector<ObjectData> & objects);
294
+
278
295
void cropPointCloudWithEgoFootprintPath (
279
296
const std::vector<Polygon2d> & ego_polys, pcl::PointCloud<pcl::PointXYZ>::Ptr filtered_objects);
280
297
@@ -298,6 +315,7 @@ class AEB : public rclcpp::Node
298
315
VelocityReport::ConstSharedPtr current_velocity_ptr_{nullptr };
299
316
Vector3::SharedPtr angular_velocity_ptr_{nullptr };
300
317
Trajectory::ConstSharedPtr predicted_traj_ptr_{nullptr };
318
+ PredictedObjects::ConstSharedPtr predicted_objects_ptr_{nullptr };
301
319
AutowareState::ConstSharedPtr autoware_state_{nullptr };
302
320
303
321
tf2_ros::Buffer tf_buffer_{get_clock ()};
@@ -313,6 +331,8 @@ class AEB : public rclcpp::Node
313
331
bool publish_debug_pointcloud_;
314
332
bool use_predicted_trajectory_;
315
333
bool use_imu_path_;
334
+ bool use_pointcloud_data_;
335
+ bool use_predicted_object_data_;
316
336
bool use_object_velocity_calculation_;
317
337
double path_footprint_extra_margin_;
318
338
double detection_range_min_height_;
0 commit comments