diff --git a/system/autoware_redundancy_relay_manager/src/redundancy_relay_manager_node.cpp b/system/autoware_redundancy_relay_manager/src/redundancy_relay_manager_node.cpp index 86d2b9033478c..a733ee073b499 100644 --- a/system/autoware_redundancy_relay_manager/src/redundancy_relay_manager_node.cpp +++ b/system/autoware_redundancy_relay_manager/src/redundancy_relay_manager_node.cpp @@ -58,8 +58,10 @@ void RedundancyRelayManager::onMainElectionStatus( if (is_relaying_) { if (tmp_election_status == nullptr) return; - if (operation_mode_state->mode != autoware_adapi_v1_msgs::msg::OperationModeState::AUTONOMOUS) return; - if (((msg->path_info >> 3) & 0x01) == 1 || ((tmp_election_status->path_info >> 3) & 0x01) == 0) return; + if (operation_mode_state->mode != autoware_adapi_v1_msgs::msg::OperationModeState::AUTONOMOUS) + return; + if (((msg->path_info >> 3) & 0x01) == 1 || ((tmp_election_status->path_info >> 3) & 0x01) == 0) + return; requestTopicRelayControl(false, client_relay_trajectory_, "topic_relay_control_trajectory"); requestTopicRelayControl( @@ -87,8 +89,10 @@ void RedundancyRelayManager::onSubElectionStatus( if (is_relaying_) { if (tmp_election_status == nullptr) return; - if (operation_mode_state->mode != autoware_adapi_v1_msgs::msg::OperationModeState::AUTONOMOUS) return; - if (((msg->path_info >> 3) & 0x01) == 1 || ((tmp_election_status->path_info >> 3) & 0x01) == 0) return; + if (operation_mode_state->mode != autoware_adapi_v1_msgs::msg::OperationModeState::AUTONOMOUS) + return; + if (((msg->path_info >> 3) & 0x01) == 1 || ((tmp_election_status->path_info >> 3) & 0x01) == 0) + return; requestTopicRelayControl(false, client_relay_trajectory_, "topic_relay_control_trajectory"); requestTopicRelayControl( diff --git a/system/autoware_redundancy_relay_manager/src/redundancy_relay_manager_node.hpp b/system/autoware_redundancy_relay_manager/src/redundancy_relay_manager_node.hpp index 6f2d48d380f75..1c0b603a98f45 100644 --- a/system/autoware_redundancy_relay_manager/src/redundancy_relay_manager_node.hpp +++ b/system/autoware_redundancy_relay_manager/src/redundancy_relay_manager_node.hpp @@ -16,9 +16,9 @@ #define REDUNDANCY_RELAY_MANAGER_NODE_HPP_ // ROS 2 core +#include #include -#include #include #include #include @@ -41,7 +41,8 @@ class RedundancyRelayManager : public rclcpp::Node // Params NodeParam node_param_; // Subscribers - autoware::universe_utils::InterProcessPollingSubscriber + autoware::universe_utils::InterProcessPollingSubscriber< + autoware_adapi_v1_msgs::msg::OperationModeState> sub_operation_mode_state_{this, "~/input/operation_mode/state"}; rclcpp::Subscription::SharedPtr sub_main_election_status_; rclcpp::Subscription::SharedPtr sub_sub_election_status_;