Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

feat(system error monitor): use polling subscriber #7486

Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@
#define SYSTEM_ERROR_MONITOR__SYSTEM_ERROR_MONITOR_CORE_HPP_

#include "tier4_autoware_utils/ros/logger_level_configure.hpp"
#include "tier4_autoware_utils/ros/polling_subscriber.hpp"

#include <rclcpp/create_timer.hpp>
#include <rclcpp/rclcpp.hpp>
Expand Down Expand Up @@ -101,12 +102,14 @@ class AutowareErrorMonitor : public rclcpp::Node

// Subscriber
rclcpp::Subscription<diagnostic_msgs::msg::DiagnosticArray>::SharedPtr sub_diag_array_;
rclcpp::Subscription<autoware_system_msgs::msg::AutowareState>::SharedPtr sub_autoware_state_;
rclcpp::Subscription<tier4_control_msgs::msg::GateMode>::SharedPtr sub_current_gate_mode_;
rclcpp::Subscription<autoware_vehicle_msgs::msg::ControlModeReport>::SharedPtr sub_control_mode_;
void onAutowareState(const autoware_system_msgs::msg::AutowareState::ConstSharedPtr msg);
void onCurrentGateMode(const tier4_control_msgs::msg::GateMode::ConstSharedPtr msg);
void onControlMode(const autoware_vehicle_msgs::msg::ControlModeReport::ConstSharedPtr msg);
// polling subscribers
tier4_autoware_utils::InterProcessPollingSubscriber<autoware_system_msgs::msg::AutowareState>
sub_autoware_state_{this, "~/input/current_gate_mode"};
tier4_autoware_utils::InterProcessPollingSubscriber<tier4_control_msgs::msg::GateMode>
sub_current_gate_mode_{this, "~/input/autoware_state"};
tier4_autoware_utils::InterProcessPollingSubscriber<autoware_vehicle_msgs::msg::ControlModeReport>
sub_control_mode_{this, "~/input/control_mode"};

void onDiagArray(const diagnostic_msgs::msg::DiagnosticArray::ConstSharedPtr msg);

const size_t diag_buffer_size_ = 100;
Expand Down
1 change: 1 addition & 0 deletions system/system_error_monitor/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@
<version>0.1.1</version>
<description>The system_error_monitor package in ROS 2</description>
<maintainer email="fumihito.ito@tier4.jp">Fumihito Ito</maintainer>
<maintainer email="masahiro.kubota@tier4.jp">Masahiro Kubota</maintainer>
<license>Apache License 2.0</license>

<buildtool_depend>ament_cmake_auto</buildtool_depend>
Expand Down
33 changes: 24 additions & 9 deletions system/system_error_monitor/src/system_error_monitor_core.cpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2020 Tier IV, Inc.

Check notice on line 1 in system/system_error_monitor/src/system_error_monitor_core.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

ℹ Getting worse: Overall Code Complexity

The mean cyclomatic complexity increases from 4.15 to 4.26, threshold = 4. This file has many conditional statements (e.g. if, for, while) across its implementation, leading to lower code health. Avoid adding more conditionals.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand Down Expand Up @@ -232,15 +232,6 @@
// Subscriber
sub_diag_array_ = create_subscription<diagnostic_msgs::msg::DiagnosticArray>(
"input/diag_array", rclcpp::QoS{1}, std::bind(&AutowareErrorMonitor::onDiagArray, this, _1));
sub_current_gate_mode_ = create_subscription<tier4_control_msgs::msg::GateMode>(
"~/input/current_gate_mode", rclcpp::QoS{1},
std::bind(&AutowareErrorMonitor::onCurrentGateMode, this, _1));
sub_autoware_state_ = create_subscription<autoware_system_msgs::msg::AutowareState>(
"~/input/autoware_state", rclcpp::QoS{1},
std::bind(&AutowareErrorMonitor::onAutowareState, this, _1));
sub_control_mode_ = create_subscription<autoware_vehicle_msgs::msg::ControlModeReport>(
"~/input/control_mode", rclcpp::QoS{1},
std::bind(&AutowareErrorMonitor::onControlMode, this, _1));

// Publisher
pub_hazard_status_ = create_publisher<autoware_system_msgs::msg::HazardStatusStamped>(
Expand Down Expand Up @@ -440,6 +431,30 @@

void AutowareErrorMonitor::onTimer()
{
const auto autoware_state_msg = sub_autoware_state_.takeData();
const auto current_gate_msg = sub_current_gate_mode_.takeData();
const auto control_mode_msg = sub_control_mode_.takeData();

if (autoware_state_msg) {
autoware_state_ = autoware_state_msg;
// for Heartbeat
autoware_state_stamp_ = this->now();
}

if (current_gate_msg) {
current_gate_mode_ = current_gate_msg;
// for Heartbeat
current_gate_mode_stamp_ = this->now();
}

if (control_mode_msg) {
control_mode_ = control_mode_msg;
// for Heartbeat
control_mode_stamp_ = this->now();
}

// for Heartbeat
current_gate_mode_stamp_ = this->now();
if (!isDataReady()) {
if ((this->now() - initialized_time_).seconds() > params_.data_ready_timeout) {
RCLCPP_WARN_THROTTLE(
Expand Down
Loading