Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

fix: revert customized hazard status converter #1817

Merged
merged 4 commits into from
Feb 14, 2025
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
7 changes: 1 addition & 6 deletions launch/tier4_system_launch/launch/system.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -39,9 +39,6 @@
<arg name="launch_rqt_robot_monitor" default="false"/>
<arg name="launch_rqt_runtime_monitor_err" default="false"/>

<!-- Hazard Status Converter -->
<arg name="report_only_diag" default="false"/>

<group>
<push-ros-namespace namespace="/system"/>

Expand Down Expand Up @@ -123,9 +120,7 @@

<!-- Hazard Status Converter -->
<group unless="$(var use_emergency_handler)">
<include file="$(find-pkg-share hazard_status_converter)/launch/hazard_status_converter.launch.xml">
<arg name="report_only_diag" value="$(var report_only_diag)"/>
</include>
<include file="$(find-pkg-share hazard_status_converter)/launch/hazard_status_converter.launch.xml"/>
</group>

<!-- MRM Handler -->
Expand Down
Original file line number Diff line number Diff line change
@@ -1,8 +1,6 @@
<launch>
<arg name="report_only_diag" default="false"/>
<node pkg="hazard_status_converter" exec="converter" name="hazard_status_converter">
<remap from="~/diagnostics_graph" to="/diagnostics_graph"/>
<remap from="~/hazard_status" to="/system/emergency/hazard_status"/>
<param name="report_only_diag" value="$(var report_only_diag)"/>
</node>
</launch>
5 changes: 1 addition & 4 deletions system/hazard_status_converter/src/converter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,8 +27,6 @@ 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<bool>("report_only_diag", false);
}

void Converter::on_create(DiagGraph::ConstSharedPtr graph)
Expand Down Expand Up @@ -95,7 +93,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_latent_fault;
if (level == HazardStatus::SAFE_FAULT) return &status.diag_safe_fault;
if (level == HazardStatus::NO_FAULT) return &status.diag_no_fault;
return static_cast<std::vector<DiagnosticStatus> *>(nullptr);
};
Expand All @@ -109,7 +107,6 @@ 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();
Expand Down
1 change: 0 additions & 1 deletion system/hazard_status_converter/src/converter.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,6 @@ class Converter : public rclcpp::Node

DiagUnit * auto_mode_root_;
std::unordered_set<DiagUnit *> auto_mode_tree_;
bool report_only_diag_;
};

} // namespace hazard_status_converter
Expand Down
Loading