@@ -209,8 +209,7 @@ AutowareErrorMonitor::AutowareErrorMonitor()
209
209
diag_array_stamp_(0 , 0 , this ->get_clock ()->get_clock_type()),
210
210
autoware_state_stamp_(0 , 0 , this ->get_clock ()->get_clock_type()),
211
211
current_gate_mode_stamp_(0 , 0 , this ->get_clock ()->get_clock_type()),
212
- control_mode_stamp_(0 , 0 , this ->get_clock ()->get_clock_type()),
213
- control_mode_activated_(false )
212
+ control_mode_stamp_(0 , 0 , this ->get_clock ()->get_clock_type())
214
213
{
215
214
// Parameter
216
215
get_parameter_or<int >(" update_rate" , params_.update_rate , 10 );
@@ -375,10 +374,6 @@ void AutowareErrorMonitor::onAutowareState(
375
374
void AutowareErrorMonitor::onControlMode (
376
375
const autoware_auto_vehicle_msgs::msg::ControlModeReport::ConstSharedPtr msg)
377
376
{
378
- // used for indicating that onControlMode callback is called at least once.
379
- if (!control_mode_activated_) {
380
- control_mode_activated_ = true ;
381
- }
382
377
383
378
control_mode_ = msg;
384
379
@@ -437,8 +432,7 @@ bool AutowareErrorMonitor::isDataHeartbeatTimeout()
437
432
return true ;
438
433
}
439
434
440
- if (
441
- (isTimeout (control_mode_stamp_, params_.data_heartbeat_timeout )) && (control_mode_activated_)) {
435
+ if (isTimeout (control_mode_stamp_, params_.data_heartbeat_timeout )) {
442
436
RCLCPP_ERROR_THROTTLE (
443
437
get_logger (), *get_clock (), 5000 , " vehicle_state_report msg is timeout..." );
444
438
return true ;
0 commit comments