@@ -58,19 +58,6 @@ VelocitySmootherNode::VelocitySmootherNode(const rclcpp::NodeOptions & node_opti
58
58
pub_over_stop_velocity_ = create_publisher<StopSpeedExceeded>(" ~/stop_speed_exceeded" , 1 );
59
59
sub_current_trajectory_ = create_subscription<Trajectory>(
60
60
" ~/input/trajectory" , 1 , std::bind (&VelocitySmootherNode::onCurrentTrajectory, this , _1));
61
- sub_current_odometry_ = create_subscription<Odometry>(
62
- " /localization/kinematic_state" , 1 ,
63
- std::bind (&VelocitySmootherNode::onCurrentOdometry, this , _1));
64
- sub_external_velocity_limit_ = create_subscription<VelocityLimit>(
65
- " ~/input/external_velocity_limit_mps" , 1 ,
66
- std::bind (&VelocitySmootherNode::onExternalVelocityLimit, this , _1));
67
- sub_current_acceleration_ = create_subscription<AccelWithCovarianceStamped>(
68
- " ~/input/acceleration" , 1 , [this ](const AccelWithCovarianceStamped::ConstSharedPtr msg) {
69
- current_acceleration_ptr_ = msg;
70
- });
71
- sub_operation_mode_ = create_subscription<OperationModeState>(
72
- " ~/input/operation_mode_state" , 1 ,
73
- [this ](const OperationModeState::ConstSharedPtr msg) { operation_mode_ = *msg; });
74
61
75
62
// parameter update
76
63
set_param_res_ =
@@ -319,16 +306,6 @@ void VelocitySmootherNode::publishTrajectory(const TrajectoryPoints & trajectory
319
306
pub_trajectory_, publishing_trajectory.header .stamp );
320
307
}
321
308
322
- void VelocitySmootherNode::onCurrentOdometry (const Odometry::ConstSharedPtr msg)
323
- {
324
- current_odometry_ptr_ = msg;
325
- }
326
-
327
- void VelocitySmootherNode::onExternalVelocityLimit (const VelocityLimit::ConstSharedPtr msg)
328
- {
329
- external_velocity_limit_ptr_ = msg;
330
- }
331
-
332
309
void VelocitySmootherNode::calcExternalVelocityLimit ()
333
310
{
334
311
if (!external_velocity_limit_ptr_) {
@@ -441,6 +418,15 @@ void VelocitySmootherNode::onCurrentTrajectory(const Trajectory::ConstSharedPtr
441
418
442
419
base_traj_raw_ptr_ = msg;
443
420
421
+ // receive data
422
+ current_odometry_ptr_ = sub_current_odometry_.takeData ();
423
+ current_acceleration_ptr_ = sub_current_acceleration_.takeData ();
424
+ external_velocity_limit_ptr_ = sub_external_velocity_limit_.takeData ();
425
+ const auto operation_mode_ptr = sub_operation_mode_.takeData ();
426
+ if (operation_mode_ptr) {
427
+ operation_mode_ = *operation_mode_ptr;
428
+ }
429
+
444
430
// guard
445
431
if (!checkData ()) {
446
432
return ;
0 commit comments