Skip to content

Commit f67e154

Browse files
author
Ahmed Ebrahim
committed
fix(log-messages): reverting proposed solution for error message "vehicle_state_report msg is timeout... (isDataHeartbeatTimeout()..."
Signed-off-by: AhmedEbrahim <ahmed.a.d.ebrahim@gmail.com>
1 parent 1eda491 commit f67e154

File tree

2 files changed

+2
-9
lines changed

2 files changed

+2
-9
lines changed

system/system_error_monitor/include/system_error_monitor/system_error_monitor_core.hpp

-1
Original file line numberDiff line numberDiff line change
@@ -135,7 +135,6 @@ class AutowareErrorMonitor : public rclcpp::Node
135135
rclcpp::Time autoware_state_stamp_;
136136
rclcpp::Time current_gate_mode_stamp_;
137137
rclcpp::Time control_mode_stamp_;
138-
bool control_mode_activated_;
139138

140139
// Algorithm
141140
boost::optional<DiagStamped> getLatestDiag(const std::string & diag_name) const;

system/system_error_monitor/src/system_error_monitor_core.cpp

+2-8
Original file line numberDiff line numberDiff line change
@@ -209,8 +209,7 @@ AutowareErrorMonitor::AutowareErrorMonitor()
209209
diag_array_stamp_(0, 0, this->get_clock()->get_clock_type()),
210210
autoware_state_stamp_(0, 0, this->get_clock()->get_clock_type()),
211211
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())
214213
{
215214
// Parameter
216215
get_parameter_or<int>("update_rate", params_.update_rate, 10);
@@ -375,10 +374,6 @@ void AutowareErrorMonitor::onAutowareState(
375374
void AutowareErrorMonitor::onControlMode(
376375
const autoware_auto_vehicle_msgs::msg::ControlModeReport::ConstSharedPtr msg)
377376
{
378-
// used for indicating that onControlMode callback is called at least once.
379-
if (!control_mode_activated_) {
380-
control_mode_activated_ = true;
381-
}
382377

383378
control_mode_ = msg;
384379

@@ -437,8 +432,7 @@ bool AutowareErrorMonitor::isDataHeartbeatTimeout()
437432
return true;
438433
}
439434

440-
if (
441-
(isTimeout(control_mode_stamp_, params_.data_heartbeat_timeout)) && (control_mode_activated_)) {
435+
if (isTimeout(control_mode_stamp_, params_.data_heartbeat_timeout)) {
442436
RCLCPP_ERROR_THROTTLE(
443437
get_logger(), *get_clock(), 5000, "vehicle_state_report msg is timeout...");
444438
return true;

0 commit comments

Comments
 (0)