Skip to content

Commit

Permalink
run precommit
Browse files Browse the repository at this point in the history
  • Loading branch information
saka1-s committed Sep 6, 2024
1 parent c2e1d0a commit 4a9e372
Show file tree
Hide file tree
Showing 4 changed files with 29 additions and 26 deletions.
6 changes: 3 additions & 3 deletions launch/tier4_system_launch/launch/system.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -157,7 +157,7 @@
</group>

<!-- System Recover Operator -->
<group if="$(var launch_system_recover_operator)">
<node pkg="diagnostic_graph_aggregator" exec="recovery" name="recovery"/>
</group>
<group if="$(var launch_system_recover_operator)">
<node pkg="diagnostic_graph_aggregator" exec="recovery" name="recovery"/>
</group>
</launch>
6 changes: 3 additions & 3 deletions system/diagnostic_graph_aggregator/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -10,13 +10,13 @@
<buildtool_depend>ament_cmake_auto</buildtool_depend>
<buildtool_depend>autoware_cmake</buildtool_depend>

<depend>autoware_adapi_v1_msgs</depend>
<depend>autoware_auto_system_msgs</depend>
<depend>component_interface_utils</depend>
<depend>diagnostic_msgs</depend>
<depend>rclcpp</depend>
<depend>std_srvs</depend>
<depend>tier4_system_msgs</depend>
<depend>autoware_auto_system_msgs</depend>
<depend>autoware_adapi_v1_msgs</depend>
<depend>component_interface_utils</depend>
<depend>yaml_cpp_vendor</depend>

<test_depend>ament_cmake_gtest</test_depend>
Expand Down
35 changes: 19 additions & 16 deletions system/diagnostic_graph_aggregator/src/node/recovery.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,15 +27,17 @@ RecoveryNode::RecoveryNode() : Node("recovery")
const auto qos_mrm_state = rclcpp::QoS(1);

const auto callback_graph = std::bind(&RecoveryNode::on_graph, this, _1);
sub_graph_ = create_subscription<DiagnosticGraph>("/diagnostics_graph", qos_graph, callback_graph);
sub_graph_ =
create_subscription<DiagnosticGraph>("/diagnostics_graph", qos_graph, callback_graph);
const auto callback_aw_state = std::bind(&RecoveryNode::on_aw_state, this, _1);
sub_aw_state_ = create_subscription<AutowareState>("/autoware/state", qos_aw_state, callback_aw_state);
sub_aw_state_ =
create_subscription<AutowareState>("/autoware/state", qos_aw_state, callback_aw_state);
const auto callback_mrm_state = std::bind(&RecoveryNode::on_mrm_state, this, _1);
sub_mrm_state_ = create_subscription<MrmState>("/system/fail_safe/mrm_state",
qos_mrm_state, callback_mrm_state);
sub_mrm_state_ =
create_subscription<MrmState>("/system/fail_safe/mrm_state", qos_mrm_state, callback_mrm_state);
callback_group_ = create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
srv_clear_mrm_ = create_client<std_srvs::srv::Trigger>("/system/clear_mrm",
rmw_qos_profile_services_default, callback_group_);
srv_clear_mrm_ = create_client<std_srvs::srv::Trigger>(
"/system/clear_mrm", rmw_qos_profile_services_default, callback_group_);

fatal_error_ = false;
mrm_occur_ = false;
Expand All @@ -51,40 +53,42 @@ void RecoveryNode::on_graph(const DiagnosticGraph::ConstSharedPtr msg)
}
// aggregate non-recoverable error
if (node.status.name == "/autoware/fatal_error/autonomous_available") {
if (node.status.level != DiagnosticStatus::OK){
if (node.status.level != DiagnosticStatus::OK) {
fatal_error_ = true;
} else {
fatal_error_ = false;
}
}
}

}

void RecoveryNode::on_aw_state(const AutowareState::ConstSharedPtr msg){
void RecoveryNode::on_aw_state(const AutowareState::ConstSharedPtr msg)
{
auto_driving_ = msg->state == AutowareState::DRIVING;
}

void RecoveryNode::on_mrm_state(const MrmState::ConstSharedPtr msg){
void RecoveryNode::on_mrm_state(const MrmState::ConstSharedPtr msg)
{
// set flag if mrm happened by fatal error
if (msg->state != MrmState::NORMAL && fatal_error_){
if (msg->state != MrmState::NORMAL && fatal_error_) {
mrm_by_fatal_error_ = true;
}
// reset flag if recoverd (transition from mrm to normal)

Check warning on line 76 in system/diagnostic_graph_aggregator/src/node/recovery.cpp

View workflow job for this annotation

GitHub Actions / spell-check-differential

Unknown word (recoverd)

Check warning on line 76 in system/diagnostic_graph_aggregator/src/node/recovery.cpp

View workflow job for this annotation

GitHub Actions / spell-check-partial

Unknown word (recoverd)
if (mrm_occur_ && msg->state == MrmState::NORMAL){
if (mrm_occur_ && msg->state == MrmState::NORMAL) {
mrm_by_fatal_error_ = false;
}
mrm_occur_ = msg->state != MrmState::NORMAL;
// 1. Not emergency
// 2. Non-recovoerable MRM have not happened

Check warning on line 82 in system/diagnostic_graph_aggregator/src/node/recovery.cpp

View workflow job for this annotation

GitHub Actions / spell-check-differential

Unknown word (recovoerable)

Check warning on line 82 in system/diagnostic_graph_aggregator/src/node/recovery.cpp

View workflow job for this annotation

GitHub Actions / spell-check-partial

Unknown word (recovoerable)
// 3. on MRM
// 4. on autonomous driving
if (autonomous_available_ && !mrm_by_fatal_error_ && mrm_occur_ && auto_driving_){
if (autonomous_available_ && !mrm_by_fatal_error_ && mrm_occur_ && auto_driving_) {
clear_mrm();
}
}

void RecoveryNode::clear_mrm(){
void RecoveryNode::clear_mrm()
{
const auto req = std::make_shared<std_srvs::srv::Trigger::Request>();

auto logger = get_logger();
Expand All @@ -95,8 +99,7 @@ void RecoveryNode::clear_mrm(){
RCLCPP_INFO(logger, "Recover MRM automatically.");
auto res = srv_clear_mrm_->async_send_request(req);
std::future_status status = res.wait_for(std::chrono::milliseconds(50));
if(status == std::future_status::timeout)
{
if (status == std::future_status::timeout) {
RCLCPP_INFO(logger, "Service timeout");
return;
}
Expand Down
8 changes: 4 additions & 4 deletions system/diagnostic_graph_aggregator/src/node/recovery.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -20,11 +20,12 @@
#include <rclcpp/rclcpp.hpp>

// Autoware
#include <std_msgs/msg/string.hpp>
#include <std_srvs/srv/trigger.hpp>
#include <component_interface_utils/rclcpp.hpp>
#include <autoware_auto_system_msgs/msg/autoware_state.hpp>

#include <autoware_adapi_v1_msgs/msg/mrm_state.hpp>
#include <autoware_auto_system_msgs/msg/autoware_state.hpp>
#include <std_msgs/msg/string.hpp>
#include <std_srvs/srv/trigger.hpp>

#include <functional>
#include <map> // Use map for sorting keys.
Expand Down Expand Up @@ -64,7 +65,6 @@ class RecoveryNode : public rclcpp::Node
void on_mrm_state(const MrmState::ConstSharedPtr msg);

void clear_mrm();

};

} // namespace diagnostic_graph_aggregator
Expand Down

0 comments on commit 4a9e372

Please sign in to comment.