@@ -27,6 +27,8 @@ Converter::Converter(const rclcpp::NodeOptions & options) : Node("converter", op
27
27
sub_graph_.register_create_callback (std::bind (&Converter::on_create, this , _1));
28
28
sub_graph_.register_update_callback (std::bind (&Converter::on_update, this , _1));
29
29
sub_graph_.subscribe (*this , 1 );
30
+
31
+ report_only_diag_ = declare_parameter<bool >(" report_only_diag" , false );
30
32
}
31
33
32
34
void Converter::on_create (DiagGraph::ConstSharedPtr graph)
@@ -93,7 +95,7 @@ void Converter::on_update(DiagGraph::ConstSharedPtr graph)
93
95
const auto get_hazards_vector = [](HazardStatus & status, HazardLevel level) {
94
96
if (level == HazardStatus::SINGLE_POINT_FAULT) return &status.diag_single_point_fault ;
95
97
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 ;
97
99
if (level == HazardStatus::NO_FAULT) return &status.diag_no_fault ;
98
100
return static_cast <std::vector<DiagnosticStatus> *>(nullptr );
99
101
};
@@ -107,6 +109,7 @@ void Converter::on_update(DiagGraph::ConstSharedPtr graph)
107
109
HazardStatusStamped hazard;
108
110
for (const auto & unit : graph->units ()) {
109
111
if (unit->path ().empty ()) continue ;
112
+ if (report_only_diag_ && unit->type () != " diag" ) continue ;
110
113
const bool is_auto_tree = auto_mode_tree_.count (unit);
111
114
const auto root_level = is_auto_tree ? auto_mode_root_->level () : DiagnosticStatus::OK;
112
115
const auto unit_level = unit->level ();
0 commit comments