@@ -208,68 +208,72 @@ void AEB::onTimer()
208
208
updater_.force_update ();
209
209
}
210
210
211
- void AEB::onVelocity ( const VelocityReport::ConstSharedPtr input_msg )
211
+ void AEB::fetchVelocity ( )
212
212
{
213
- current_velocity_ptr_ = input_msg;
213
+ current_velocity_ptr_ = std::make_shared<VelocityReport>();
214
+ *current_velocity_ptr_ = sub_velocity_.getData ();
214
215
}
215
216
216
- void AEB::onImu ( const Imu::ConstSharedPtr input_msg )
217
+ void AEB::fetchImu ( )
217
218
{
219
+ const auto & input_msg = sub_imu_.getData ();
218
220
// transform imu
219
221
geometry_msgs::msg::TransformStamped transform_stamped{};
220
222
try {
221
223
transform_stamped = tf_buffer_.lookupTransform (
222
- " base_link" , input_msg-> header .frame_id , input_msg-> header .stamp ,
224
+ " base_link" , input_msg. header .frame_id , input_msg. header .stamp ,
223
225
rclcpp::Duration::from_seconds (0.5 ));
224
226
} catch (tf2::TransformException & ex) {
225
227
RCLCPP_ERROR_STREAM (
226
228
get_logger (),
227
- " [AEB] Failed to look up transform from base_link to" << input_msg-> header .frame_id );
229
+ " [AEB] Failed to look up transform from base_link to" << input_msg. header .frame_id );
228
230
return ;
229
231
}
230
232
231
233
angular_velocity_ptr_ = std::make_shared<Vector3>();
232
- tf2::doTransform (input_msg-> angular_velocity , *angular_velocity_ptr_, transform_stamped);
234
+ tf2::doTransform (input_msg. angular_velocity , *angular_velocity_ptr_, transform_stamped);
233
235
}
234
236
235
- void AEB::onPredictedTrajectory (
236
- const autoware_auto_planning_msgs::msg::Trajectory::ConstSharedPtr input_msg)
237
+ void AEB::fetchPredictedTrajectory ()
237
238
{
238
- predicted_traj_ptr_ = input_msg;
239
+ predicted_traj_ptr_ = std::make_shared<Trajectory>();
240
+ *predicted_traj_ptr_ = sub_predicted_traj_.getData ();
239
241
}
240
242
241
- void AEB::onAutowareState ( const AutowareState::ConstSharedPtr input_msg )
243
+ void AEB::fetchAutowareState ( )
242
244
{
243
- autoware_state_ = input_msg;
245
+ autoware_state_ = std::make_shared<AutowareState>();
246
+ *autoware_state_ = sub_autoware_state_.getData ();
244
247
}
245
248
246
- void AEB::onPointCloud ( const PointCloud2::ConstSharedPtr input_msg )
249
+ void AEB::fetchPointCloud ( )
247
250
{
251
+ const auto & input_msg = sub_point_cloud_.getData ();
248
252
PointCloud::Ptr pointcloud_ptr (new PointCloud);
249
- pcl::fromROSMsg (* input_msg, *pointcloud_ptr);
253
+ pcl::fromROSMsg (input_msg, *pointcloud_ptr);
250
254
251
- if (input_msg-> header .frame_id != " base_link" ) {
255
+ if (input_msg. header .frame_id != " base_link" ) {
252
256
RCLCPP_ERROR_STREAM (
253
257
get_logger (),
254
- " [AEB]: Input point cloud frame is not base_link and it is " << input_msg-> header .frame_id );
258
+ " [AEB]: Input point cloud frame is not base_link and it is " << input_msg. header .frame_id );
255
259
// transform pointcloud
256
260
geometry_msgs::msg::TransformStamped transform_stamped{};
257
261
try {
258
262
transform_stamped = tf_buffer_.lookupTransform (
259
- " base_link" , input_msg-> header .frame_id , input_msg-> header .stamp ,
263
+ " base_link" , input_msg. header .frame_id , input_msg. header .stamp ,
260
264
rclcpp::Duration::from_seconds (0.5 ));
261
265
} catch (tf2::TransformException & ex) {
262
266
RCLCPP_ERROR_STREAM (
263
267
get_logger (),
264
- " [AEB] Failed to look up transform from base_link to" << input_msg-> header .frame_id );
268
+ " [AEB] Failed to look up transform from base_link to" << input_msg. header .frame_id );
265
269
return ;
266
270
}
267
271
268
272
// transform by using eigen matrix
269
273
PointCloud2 transformed_points{};
270
274
const Eigen::Matrix4f affine_matrix =
271
275
tf2::transformToEigen (transform_stamped.transform ).matrix ().cast <float >();
272
- pcl_ros::transformPointCloud (affine_matrix, * input_msg, transformed_points);
276
+ pcl_ros::transformPointCloud (affine_matrix, input_msg, transformed_points);
273
277
pcl::fromROSMsg (transformed_points, *pointcloud_ptr);
274
278
}
275
279
@@ -292,7 +296,7 @@ void AEB::onPointCloud(const PointCloud2::ConstSharedPtr input_msg)
292
296
obstacle_ros_pointcloud_ptr_ = std::make_shared<PointCloud2>();
293
297
294
298
pcl::toROSMsg (*no_height_filtered_pointcloud_ptr, *obstacle_ros_pointcloud_ptr_);
295
- obstacle_ros_pointcloud_ptr_->header = input_msg-> header ;
299
+ obstacle_ros_pointcloud_ptr_->header = input_msg. header ;
296
300
}
297
301
298
302
bool AEB::isDataReady ()
@@ -302,22 +306,27 @@ bool AEB::isDataReady()
302
306
return false ;
303
307
};
304
308
309
+ fetchVelocity ();
305
310
if (!current_velocity_ptr_) {
306
311
return missing (" ego velocity" );
307
312
}
308
313
314
+ fetchPointCloud ();
309
315
if (!obstacle_ros_pointcloud_ptr_) {
310
- return missing (" object pointcloud" );
316
+ return missing (" filtered object pointcloud" );
311
317
}
312
318
319
+ fetchImu ();
313
320
if (use_imu_path_ && !angular_velocity_ptr_) {
314
- return missing (" imu" );
321
+ return missing (" filtered imu" );
315
322
}
316
323
324
+ fetchPredictedTrajectory ();
317
325
if (use_predicted_trajectory_ && !predicted_traj_ptr_) {
318
326
return missing (" control predicted trajectory" );
319
327
}
320
328
329
+ fetchAutowareState ();
321
330
if (!autoware_state_) {
322
331
return missing (" autoware_state" );
323
332
}
0 commit comments