Skip to content

Commit 2aca1c9

Browse files
committed
feat: implement MRM automatic recovery feature
Signed-off-by: Tomohito Ando <[email protected]>
1 parent 4ecf5f9 commit 2aca1c9

File tree

5 files changed

+208
-0
lines changed

5 files changed

+208
-0
lines changed

launch/tier4_system_launch/launch/system.launch.xml

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -22,6 +22,7 @@
2222

2323
<arg name="launch_system_monitor" default="true" description="launch system monitor"/>
2424
<arg name="launch_dummy_diag_publisher" description="launch dummy diag publisher"/>
25+
<arg name="launch_system_recover_operator" default="false" description="launch recover operator"/>
2526
<arg name="run_mode" default="online" description="options: online, logging_simulation, planning_simulation"/>
2627
<arg name="sensor_model" description="sensor model name"/>
2728

@@ -142,4 +143,9 @@
142143
<arg name="launch_rqt_runtime_monitor_err" value="$(var launch_rqt_runtime_monitor_err)"/>
143144
</include>
144145
</group>
146+
147+
<!-- System Recover Operator -->
148+
<group if="$(var launch_system_recover_operator)">
149+
<node pkg="diagnostic_graph_utils" exec="recovery_node" name="recovery"/>
150+
</group>
145151
</launch>

system/diagnostic_graph_utils/CMakeLists.txt

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -13,6 +13,7 @@ ament_auto_add_library(${PROJECT_NAME}_tools SHARED
1313
src/node/dump.cpp
1414
src/node/converter.cpp
1515
src/node/logging.cpp
16+
src/node/recovery.cpp
1617
)
1718

1819
rclcpp_components_register_node(${PROJECT_NAME}_tools
@@ -30,4 +31,9 @@ rclcpp_components_register_node(${PROJECT_NAME}_tools
3031
EXECUTABLE logging_node
3132
)
3233

34+
rclcpp_components_register_node(${PROJECT_NAME}_tools
35+
PLUGIN "diagnostic_graph_utils::RecoveryNode"
36+
EXECUTABLE recovery_node
37+
)
38+
3339
ament_auto_package(INSTALL_TO_SHARE launch)

system/diagnostic_graph_utils/package.xml

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -10,9 +10,13 @@
1010
<buildtool_depend>ament_cmake_auto</buildtool_depend>
1111
<buildtool_depend>autoware_cmake</buildtool_depend>
1212

13+
<depend>autoware_adapi_v1_msgs</depend>
14+
<depend>autoware_system_msgs</depend>
15+
<depend>component_interface_utils</depend>
1316
<depend>diagnostic_msgs</depend>
1417
<depend>rclcpp</depend>
1518
<depend>rclcpp_components</depend>
19+
<depend>std_srvs</depend>
1620
<depend>tier4_system_msgs</depend>
1721

1822
<test_depend>ament_lint_auto</test_depend>
Lines changed: 117 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,117 @@
1+
// Copyright 2023 The Autoware Contributors
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
#include "recovery.hpp"
16+
17+
#include <algorithm>
18+
19+
namespace diagnostic_graph_utils
20+
{
21+
22+
RecoveryNode::RecoveryNode(const rclcpp::NodeOptions & options) : Node("dump", options)
23+
{
24+
using std::placeholders::_1;
25+
const auto qos_aw_state = rclcpp::QoS(1);
26+
const auto qos_mrm_state = rclcpp::QoS(1);
27+
28+
sub_graph_.register_update_callback(std::bind(&RecoveryNode::on_graph_update, this, _1));
29+
sub_graph_.subscribe(*this, 1);
30+
31+
const auto callback_aw_state = std::bind(&RecoveryNode::on_aw_state, this, _1);
32+
sub_aw_state_ =
33+
create_subscription<AutowareState>("/autoware/state", qos_aw_state, callback_aw_state);
34+
35+
const auto callback_mrm_state = std::bind(&RecoveryNode::on_mrm_state, this, _1);
36+
sub_mrm_state_ =
37+
create_subscription<MrmState>("/system/fail_safe/mrm_state", qos_mrm_state, callback_mrm_state);
38+
callback_group_ = create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
39+
srv_clear_mrm_ = create_client<std_srvs::srv::Trigger>(
40+
"/system/clear_mrm", rmw_qos_profile_services_default, callback_group_);
41+
42+
fatal_error_ = false;
43+
mrm_occur_ = false;
44+
autonomous_available_ = false;
45+
mrm_by_fatal_error_ = false;
46+
}
47+
48+
void RecoveryNode::on_graph_update(DiagGraph::ConstSharedPtr graph)
49+
{
50+
for (const auto & node : graph->nodes()) {
51+
if (node->path() == "/autoware/modes/autonomous") {
52+
autonomous_available_ = node->level() == DiagnosticStatus::OK;
53+
}
54+
55+
// aggregate non-recoverable error
56+
if (node->path() == "/autoware/fatal_error/autonomous_available") {
57+
if (node->level() != DiagnosticStatus::OK) {
58+
fatal_error_ = true;
59+
} else {
60+
fatal_error_ = false;
61+
}
62+
}
63+
}
64+
}
65+
66+
void RecoveryNode::on_aw_state(const AutowareState::ConstSharedPtr msg)
67+
{
68+
auto_driving_ = msg->state == AutowareState::DRIVING;
69+
}
70+
71+
void RecoveryNode::on_mrm_state(const MrmState::ConstSharedPtr msg)
72+
{
73+
// set flag if mrm happened by fatal error
74+
if (msg->state != MrmState::NORMAL && fatal_error_) {
75+
mrm_by_fatal_error_ = true;
76+
}
77+
// reset flag if recoverd (transition from mrm to normal)
78+
if (mrm_occur_ && msg->state == MrmState::NORMAL) {
79+
mrm_by_fatal_error_ = false;
80+
}
81+
mrm_occur_ = msg->state != MrmState::NORMAL;
82+
// 1. Not emergency
83+
// 2. Non-recovoerable MRM have not happened
84+
// 3. on MRM
85+
// 4. on autonomous driving
86+
if (autonomous_available_ && !mrm_by_fatal_error_ && mrm_occur_ && auto_driving_) {
87+
clear_mrm();
88+
}
89+
}
90+
91+
void RecoveryNode::clear_mrm()
92+
{
93+
const auto req = std::make_shared<std_srvs::srv::Trigger::Request>();
94+
95+
auto logger = get_logger();
96+
if (!srv_clear_mrm_->service_is_ready()) {
97+
RCLCPP_ERROR(logger, "MRM clear server is not ready.");
98+
return;
99+
}
100+
RCLCPP_INFO(logger, "Recover MRM automatically.");
101+
auto res = srv_clear_mrm_->async_send_request(req);
102+
std::future_status status = res.wait_for(std::chrono::milliseconds(50));
103+
if (status == std::future_status::timeout) {
104+
RCLCPP_INFO(logger, "Service timeout");
105+
return;
106+
}
107+
if (!res.get()->success) {
108+
RCLCPP_INFO(logger, "Recovering MRM failed.");
109+
return;
110+
}
111+
RCLCPP_INFO(logger, "Recovering MRM succeed.");
112+
}
113+
114+
} // namespace diagnostic_graph_utils
115+
116+
#include <rclcpp_components/register_node_macro.hpp>
117+
RCLCPP_COMPONENTS_REGISTER_NODE(diagnostic_graph_utils::RecoveryNode)
Lines changed: 75 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,75 @@
1+
// Copyright 2023 The Autoware Contributors
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
#ifndef NODE__RECOVERY_HPP_
16+
#define NODE__RECOVERY_HPP_
17+
18+
#include "diagnostic_graph_utils/subscription.hpp"
19+
20+
#include <rclcpp/rclcpp.hpp>
21+
22+
#include <diagnostic_msgs/msg/diagnostic_status.hpp>
23+
24+
// Autoware
25+
#include <component_interface_utils/rclcpp.hpp>
26+
27+
#include <autoware_adapi_v1_msgs/msg/mrm_state.hpp>
28+
#include <autoware_system_msgs/msg/autoware_state.hpp>
29+
#include <std_msgs/msg/string.hpp>
30+
#include <std_srvs/srv/trigger.hpp>
31+
32+
#include <functional>
33+
#include <map> // Use map for sorting keys.
34+
#include <memory>
35+
#include <string>
36+
#include <vector>
37+
38+
namespace diagnostic_graph_utils
39+
{
40+
41+
class RecoveryNode : public rclcpp::Node
42+
{
43+
public:
44+
explicit RecoveryNode(const rclcpp::NodeOptions & options);
45+
46+
private:
47+
using AutowareState = autoware_system_msgs::msg::AutowareState;
48+
using MrmState = autoware_adapi_v1_msgs::msg::MrmState;
49+
using DiagnosticStatus = diagnostic_msgs::msg::DiagnosticStatus;
50+
51+
bool fatal_error_;
52+
bool autonomous_available_;
53+
bool mrm_occur_;
54+
bool auto_driving_;
55+
bool mrm_by_fatal_error_;
56+
DiagGraphSubscription sub_graph_;
57+
rclcpp::Subscription<AutowareState>::SharedPtr sub_aw_state_;
58+
rclcpp::Subscription<MrmState>::SharedPtr sub_mrm_state_;
59+
60+
// service
61+
rclcpp::Client<std_srvs::srv::Trigger>::SharedPtr srv_clear_mrm_;
62+
63+
// callback group for service
64+
rclcpp::CallbackGroup::SharedPtr callback_group_;
65+
66+
void on_graph_update(DiagGraph::ConstSharedPtr graph);
67+
void on_aw_state(const AutowareState::ConstSharedPtr msg);
68+
void on_mrm_state(const MrmState::ConstSharedPtr msg);
69+
70+
void clear_mrm();
71+
};
72+
73+
} // namespace diagnostic_graph_utils
74+
75+
#endif // NODE__RECOVERY_HPP_

0 commit comments

Comments
 (0)