@@ -87,6 +87,37 @@ VehicleCmdGate::VehicleCmdGate(const rclcpp::NodeOptions & node_options)
87
87
external_emergency_stop_heartbeat_sub_ = create_subscription<Heartbeat>(
88
88
" input/external_emergency_stop_heartbeat" , 1 ,
89
89
std::bind (&VehicleCmdGate::onExternalEmergencyStopHeartbeat, this , _1));
90
+ gate_mode_sub_ = create_subscription<GateMode>(
91
+ " input/gate_mode" , 1 , std::bind (&VehicleCmdGate::onGateMode, this , _1));
92
+ engage_sub_ = create_subscription<EngageMsg>(
93
+ " input/engage" , 1 , std::bind (&VehicleCmdGate::onEngage, this , _1));
94
+ kinematics_sub_ = create_subscription<Odometry>(
95
+ " /localization/kinematic_state" , 1 ,
96
+ [this ](Odometry::SharedPtr msg) { current_kinematics_ = *msg; });
97
+ acc_sub_ = create_subscription<AccelWithCovarianceStamped>(
98
+ " input/acceleration" , 1 , [this ](AccelWithCovarianceStamped::SharedPtr msg) {
99
+ current_acceleration_ = msg->accel .accel .linear .x ;
100
+ });
101
+ steer_sub_ = create_subscription<SteeringReport>(
102
+ " input/steering" , 1 ,
103
+ [this ](SteeringReport::SharedPtr msg) { current_steer_ = msg->steering_tire_angle ; });
104
+ operation_mode_sub_ = create_subscription<OperationModeState>(
105
+ " input/operation_mode" , rclcpp::QoS (1 ).transient_local (),
106
+ [this ](const OperationModeState::SharedPtr msg) { current_operation_mode_ = *msg; });
107
+ mrm_state_sub_ = create_subscription<MrmState>(
108
+ " input/mrm_state" , 1 , std::bind (&VehicleCmdGate::onMrmState, this , _1));
109
+
110
+ // Subscriber for auto
111
+ auto_control_cmd_sub_ = create_subscription<Control>(
112
+ " input/auto/control_cmd" , 1 , std::bind (&VehicleCmdGate::onAutoCtrlCmd, this , _1));
113
+
114
+ // Subscriber for external
115
+ remote_control_cmd_sub_ = create_subscription<Control>(
116
+ " input/external/control_cmd" , 1 , std::bind (&VehicleCmdGate::onRemoteCtrlCmd, this , _1));
117
+
118
+ // Subscriber for emergency
119
+ emergency_control_cmd_sub_ = create_subscription<Control>(
120
+ " input/emergency/control_cmd" , 1 , std::bind (&VehicleCmdGate::onEmergencyCtrlCmd, this , _1));
90
121
91
122
// Parameter
92
123
use_emergency_handling_ = declare_parameter<bool >(" use_emergency_handling" );
@@ -291,32 +322,29 @@ bool VehicleCmdGate::isDataReady()
291
322
}
292
323
293
324
// for auto
294
- void VehicleCmdGate::onAutoCtrlCmd ()
325
+ void VehicleCmdGate::onAutoCtrlCmd (Control::ConstSharedPtr msg )
295
326
{
296
- const auto msg = auto_control_cmd_sub_.takeData ();
297
- if (msg) auto_commands_.control = *msg;
327
+ auto_commands_.control = *msg;
298
328
299
329
if (current_gate_mode_.data == GateMode::AUTO) {
300
330
publishControlCommands (auto_commands_);
301
331
}
302
332
}
303
333
304
334
// for remote
305
- void VehicleCmdGate::onRemoteCtrlCmd ()
335
+ void VehicleCmdGate::onRemoteCtrlCmd (Control::ConstSharedPtr msg )
306
336
{
307
- const auto msg = remote_control_cmd_sub_.takeData ();
308
- if (msg) remote_commands_.control = *msg;
337
+ remote_commands_.control = *msg;
309
338
310
339
if (current_gate_mode_.data == GateMode::EXTERNAL) {
311
340
publishControlCommands (remote_commands_);
312
341
}
313
342
}
314
343
315
344
// for emergency
316
- void VehicleCmdGate::onEmergencyCtrlCmd ()
345
+ void VehicleCmdGate::onEmergencyCtrlCmd (Control::ConstSharedPtr msg )
317
346
{
318
- const auto msg = emergency_control_cmd_sub_.takeData ();
319
- if (msg) emergency_commands_.control = *msg;
347
+ emergency_commands_.control = *msg;
320
348
321
349
if (use_emergency_handling_ && is_system_emergency_) {
322
350
publishControlCommands (emergency_commands_);
@@ -325,25 +353,7 @@ void VehicleCmdGate::onEmergencyCtrlCmd()
325
353
326
354
void VehicleCmdGate::onTimer ()
327
355
{
328
- onGateMode ();
329
-
330
- const auto msg_kinematics = kinematics_sub_.takeData ();
331
- if (msg_kinematics) current_kinematics_ = *msg_kinematics;
332
-
333
- const auto msg_acceleration = acc_sub_.takeData ();
334
- if (msg_acceleration) current_acceleration_ = msg_acceleration->accel .accel .linear .x ;
335
-
336
- const auto msg_steer = steer_sub_.takeData ();
337
- if (msg_steer) current_steer_ = msg_steer->steering_tire_angle ;
338
-
339
- const auto msg_operation_mode = operation_mode_sub_.takeData ();
340
- if (msg_operation_mode) current_operation_mode_ = *msg_operation_mode;
341
-
342
- onMrmState ();
343
-
344
356
// Subscriber for auto
345
- onAutoCtrlCmd ();
346
-
347
357
const auto msg_auto_command_turn_indicator = auto_turn_indicator_cmd_sub_.takeData ();
348
358
if (msg_auto_command_turn_indicator)
349
359
auto_commands_.turn_indicator = *msg_auto_command_turn_indicator;
@@ -355,8 +365,6 @@ void VehicleCmdGate::onTimer()
355
365
if (msg_auto_command_gear) auto_commands_.gear = *msg_auto_command_gear;
356
366
357
367
// Subscribe for external
358
- onRemoteCtrlCmd ();
359
-
360
368
const auto msg_remote_command_turn_indicator = remote_turn_indicator_cmd_sub_.takeData ();
361
369
if (msg_remote_command_turn_indicator)
362
370
remote_commands_.turn_indicator = *msg_remote_command_turn_indicator;
@@ -369,17 +377,13 @@ void VehicleCmdGate::onTimer()
369
377
if (msg_remote_command_gear) remote_commands_.gear = *msg_remote_command_gear;
370
378
371
379
// Subscribe for emergency
372
- onEmergencyCtrlCmd ();
373
-
374
380
const auto msg_emergency_command_hazard_light = emergency_hazard_light_cmd_sub_.takeData ();
375
381
if (msg_emergency_command_hazard_light)
376
382
emergency_commands_.hazard_light = *msg_emergency_command_hazard_light;
377
383
378
384
const auto msg_emergency_command_gear = emergency_gear_cmd_sub_.takeData ();
379
385
if (msg_emergency_command_gear) emergency_commands_.gear = *msg_emergency_command_gear;
380
386
381
- onEngage ();
382
-
383
387
updater_.force_update ();
384
388
385
389
if (!isDataReady ()) {
@@ -705,11 +709,8 @@ void VehicleCmdGate::onExternalEmergencyStopHeartbeat(
705
709
external_emergency_stop_heartbeat_received_time_ = std::make_shared<rclcpp::Time>(this ->now ());
706
710
}
707
711
708
- void VehicleCmdGate::onGateMode ()
712
+ void VehicleCmdGate::onGateMode (GateMode::ConstSharedPtr msg )
709
713
{
710
- const auto msg = gate_mode_sub_.takeData ();
711
- if (!msg) return ;
712
-
713
714
const auto prev_gate_mode = current_gate_mode_;
714
715
current_gate_mode_ = *msg;
715
716
@@ -720,10 +721,9 @@ void VehicleCmdGate::onGateMode()
720
721
}
721
722
}
722
723
723
- void VehicleCmdGate::onEngage ()
724
+ void VehicleCmdGate::onEngage (EngageMsg::ConstSharedPtr msg )
724
725
{
725
- const auto msg = engage_sub_.takeData ();
726
- if (msg) is_engaged_ = msg->engage ;
726
+ is_engaged_ = msg->engage ;
727
727
}
728
728
729
729
void VehicleCmdGate::onEngageService (
@@ -733,11 +733,8 @@ void VehicleCmdGate::onEngageService(
733
733
response->status = tier4_api_utils::response_success ();
734
734
}
735
735
736
- void VehicleCmdGate::onMrmState ()
736
+ void VehicleCmdGate::onMrmState (MrmState::ConstSharedPtr msg )
737
737
{
738
- const auto msg = mrm_state_sub_.takeData ();
739
- if (!msg) return ;
740
-
741
738
is_system_emergency_ =
742
739
(msg->state == MrmState::MRM_OPERATING || msg->state == MrmState::MRM_SUCCEEDED ||
743
740
msg->state == MrmState::MRM_FAILED) &&
@@ -830,7 +827,8 @@ void VehicleCmdGate::checkExternalEmergencyStop(diagnostic_updater::DiagnosticSt
830
827
} else if (is_external_emergency_stop_) {
831
828
status.level = DiagnosticStatus::ERROR;
832
829
status.message =
833
- " external_emergency_stop is required. Please call `clear_external_emergency_stop` service to "
830
+ " external_emergency_stop is required. Please call `clear_external_emergency_stop` service "
831
+ " to "
834
832
" clear state." ;
835
833
} else {
836
834
status.level = DiagnosticStatus::OK;
0 commit comments