Skip to content

Commit d013ee4

Browse files
authored
Merge pull request #1725 from saka1-s/feat/report-safe-fault
feat: customize hazard status converter
2 parents 72c0271 + bfacb16 commit d013ee4

File tree

4 files changed

+13
-2
lines changed

4 files changed

+13
-2
lines changed

launch/tier4_system_launch/launch/system.launch.xml

+6-1
Original file line numberDiff line numberDiff line change
@@ -39,6 +39,9 @@
3939
<arg name="launch_rqt_robot_monitor" default="false"/>
4040
<arg name="launch_rqt_runtime_monitor_err" default="false"/>
4141

42+
<!-- Hazard Status Converter -->
43+
<arg name="report_only_diag" default="false"/>
44+
4245
<group>
4346
<push-ros-namespace namespace="/system"/>
4447

@@ -120,7 +123,9 @@
120123

121124
<!-- Hazard Status Converter -->
122125
<group unless="$(var use_emergency_handler)">
123-
<include file="$(find-pkg-share hazard_status_converter)/launch/hazard_status_converter.launch.xml"/>
126+
<include file="$(find-pkg-share hazard_status_converter)/launch/hazard_status_converter.launch.xml">
127+
<arg name="report_only_diag" value="$(var report_only_diag)"/>
128+
</include>
124129
</group>
125130

126131
<!-- MRM Handler -->
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,8 @@
11
<launch>
2+
<arg name="report_only_diag" default="false"/>
23
<node pkg="hazard_status_converter" exec="converter" name="hazard_status_converter">
34
<remap from="~/diagnostics_graph" to="/diagnostics_graph"/>
45
<remap from="~/hazard_status" to="/system/emergency/hazard_status"/>
6+
<param name="report_only_diag" value="$(var report_only_diag)"/>
57
</node>
68
</launch>

system/hazard_status_converter/src/converter.cpp

+4-1
Original file line numberDiff line numberDiff line change
@@ -27,6 +27,8 @@ Converter::Converter(const rclcpp::NodeOptions & options) : Node("converter", op
2727
sub_graph_.register_create_callback(std::bind(&Converter::on_create, this, _1));
2828
sub_graph_.register_update_callback(std::bind(&Converter::on_update, this, _1));
2929
sub_graph_.subscribe(*this, 1);
30+
31+
report_only_diag_ = declare_parameter<bool>("report_only_diag", false);
3032
}
3133

3234
void Converter::on_create(DiagGraph::ConstSharedPtr graph)
@@ -93,7 +95,7 @@ void Converter::on_update(DiagGraph::ConstSharedPtr graph)
9395
const auto get_hazards_vector = [](HazardStatus & status, HazardLevel level) {
9496
if (level == HazardStatus::SINGLE_POINT_FAULT) return &status.diag_single_point_fault;
9597
if (level == HazardStatus::LATENT_FAULT) return &status.diag_latent_fault;
96-
if (level == HazardStatus::SAFE_FAULT) return &status.diag_safe_fault;
98+
if (level == HazardStatus::SAFE_FAULT) return &status.diag_latent_fault;
9799
if (level == HazardStatus::NO_FAULT) return &status.diag_no_fault;
98100
return static_cast<std::vector<DiagnosticStatus> *>(nullptr);
99101
};
@@ -107,6 +109,7 @@ void Converter::on_update(DiagGraph::ConstSharedPtr graph)
107109
HazardStatusStamped hazard;
108110
for (const auto & unit : graph->units()) {
109111
if (unit->path().empty()) continue;
112+
if (report_only_diag_ && unit->type() != "diag") continue;
110113
const bool is_auto_tree = auto_mode_tree_.count(unit);
111114
const auto root_level = is_auto_tree ? auto_mode_root_->level() : DiagnosticStatus::OK;
112115
const auto unit_level = unit->level();

system/hazard_status_converter/src/converter.hpp

+1
Original file line numberDiff line numberDiff line change
@@ -41,6 +41,7 @@ class Converter : public rclcpp::Node
4141

4242
DiagUnit * auto_mode_root_;
4343
std::unordered_set<DiagUnit *> auto_mode_tree_;
44+
bool report_only_diag_;
4445
};
4546

4647
} // namespace hazard_status_converter

0 commit comments

Comments
 (0)