diff --git a/launch/tier4_system_launch/launch/system.launch.xml b/launch/tier4_system_launch/launch/system.launch.xml
index 6253dce864ddf..2699153edb11d 100644
--- a/launch/tier4_system_launch/launch/system.launch.xml
+++ b/launch/tier4_system_launch/launch/system.launch.xml
@@ -39,6 +39,9 @@
+
+
+
@@ -120,7 +123,9 @@
-
+
+
+
diff --git a/system/hazard_status_converter/launch/hazard_status_converter.launch.xml b/system/hazard_status_converter/launch/hazard_status_converter.launch.xml
index f3b07bfa94834..3cb54f2c5ca02 100644
--- a/system/hazard_status_converter/launch/hazard_status_converter.launch.xml
+++ b/system/hazard_status_converter/launch/hazard_status_converter.launch.xml
@@ -1,6 +1,8 @@
+
+
diff --git a/system/hazard_status_converter/src/converter.cpp b/system/hazard_status_converter/src/converter.cpp
index e8213b441bb33..215ddfd84c2bd 100644
--- a/system/hazard_status_converter/src/converter.cpp
+++ b/system/hazard_status_converter/src/converter.cpp
@@ -27,6 +27,8 @@ Converter::Converter(const rclcpp::NodeOptions & options) : Node("converter", op
sub_graph_.register_create_callback(std::bind(&Converter::on_create, this, _1));
sub_graph_.register_update_callback(std::bind(&Converter::on_update, this, _1));
sub_graph_.subscribe(*this, 1);
+
+ report_only_diag_ = declare_parameter("report_only_diag", false);
}
void Converter::on_create(DiagGraph::ConstSharedPtr graph)
@@ -93,7 +95,7 @@ void Converter::on_update(DiagGraph::ConstSharedPtr graph)
const auto get_hazards_vector = [](HazardStatus & status, HazardLevel level) {
if (level == HazardStatus::SINGLE_POINT_FAULT) return &status.diag_single_point_fault;
if (level == HazardStatus::LATENT_FAULT) return &status.diag_latent_fault;
- if (level == HazardStatus::SAFE_FAULT) return &status.diag_safe_fault;
+ if (level == HazardStatus::SAFE_FAULT) return &status.diag_latent_fault;
if (level == HazardStatus::NO_FAULT) return &status.diag_no_fault;
return static_cast *>(nullptr);
};
@@ -107,6 +109,7 @@ void Converter::on_update(DiagGraph::ConstSharedPtr graph)
HazardStatusStamped hazard;
for (const auto & unit : graph->units()) {
if (unit->path().empty()) continue;
+ if (report_only_diag_ && unit->type() != "diag") continue;
const bool is_auto_tree = auto_mode_tree_.count(unit);
const auto root_level = is_auto_tree ? auto_mode_root_->level() : DiagnosticStatus::OK;
const auto unit_level = unit->level();
diff --git a/system/hazard_status_converter/src/converter.hpp b/system/hazard_status_converter/src/converter.hpp
index 442eedf588429..28143c7644d82 100644
--- a/system/hazard_status_converter/src/converter.hpp
+++ b/system/hazard_status_converter/src/converter.hpp
@@ -41,6 +41,7 @@ class Converter : public rclcpp::Node
DiagUnit * auto_mode_root_;
std::unordered_set auto_mode_tree_;
+ bool report_only_diag_;
};
} // namespace hazard_status_converter