Skip to content

Commit 01ade5b

Browse files
committed
fix: address all PR #14 review comments
Fixes from @mfaferek93: - Update copyright year 2025 → 2026 in all source files - Add early return in report_fault() to avoid spamming FaultManager - Remove unused normal_dist_ member from camera_sim_node - Unify diagnostic topic to /diagnostics for all sensors (IMU, GPS, LiDAR, Camera) Fixes from @Copilot: - Add rcl_interfaces to ament_target_dependencies for lidar/camera nodes - Fix docker-compose jq filter: .[] → .items[] - Add exec_depend for ros2_medkit_diagnostic_bridge and fault_manager - Fix anomaly_detector topic subscriptions to match sensor namespaces - Add runtime scan_rate validation in lidar parameter callback - Add num_readings validation with fallback to 360 Additional fixes: - Update restore-normal.sh to clear IMU_SIM and GPS_SIM faults
1 parent 3379f7f commit 01ade5b

10 files changed

Lines changed: 62 additions & 24 deletions

File tree

demos/sensor_diagnostics/CMakeLists.txt

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -21,6 +21,7 @@ ament_target_dependencies(lidar_sim_node
2121
rclcpp
2222
sensor_msgs
2323
diagnostic_msgs
24+
rcl_interfaces
2425
)
2526

2627
# IMU simulator node
@@ -45,6 +46,7 @@ ament_target_dependencies(camera_sim_node
4546
rclcpp
4647
sensor_msgs
4748
diagnostic_msgs
49+
rcl_interfaces
4850
)
4951

5052
# Anomaly detector node

demos/sensor_diagnostics/docker-compose.yml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -44,5 +44,5 @@ services:
4444
ros2 launch sensor_diagnostics_demo demo.launch.py &
4545
sleep 10 &&
4646
curl -sf http://localhost:8080/api/v1/health &&
47-
curl -sf http://localhost:8080/api/v1/apps | jq '.[] | .name' &&
47+
curl -sf http://localhost:8080/api/v1/apps | jq '.items[] | .id' &&
4848
echo 'CI validation passed!'"

demos/sensor_diagnostics/include/sensor_diagnostics/simulated_sensor_base.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
// Copyright 2025 selfpatch
1+
// Copyright 2026 selfpatch
22
// SPDX-License-Identifier: Apache-2.0
33

44
/// @file simulated_sensor_base.hpp

demos/sensor_diagnostics/package.xml

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -19,6 +19,8 @@
1919

2020
<exec_depend>ros2launch</exec_depend>
2121
<exec_depend>ros2_medkit_gateway</exec_depend>
22+
<exec_depend>ros2_medkit_diagnostic_bridge</exec_depend>
23+
<exec_depend>ros2_medkit_fault_manager</exec_depend>
2224

2325
<test_depend>ament_lint_auto</test_depend>
2426
<test_depend>ament_lint_common</test_depend>

demos/sensor_diagnostics/restore-normal.sh

Lines changed: 4 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -49,14 +49,15 @@ curl -s -X PUT "${API_BASE}/apps/camera_sim/configurations/inject_black_frames"
4949
-H "Content-Type: application/json" -d '{"value": false}'
5050

5151
# Clear all faults from FaultManager
52-
# Legacy path faults (via diagnostic_bridge) - reported BY diagnostic_bridge
53-
# The fault_code is the name from DiagnosticStatus.name (e.g., LIDAR_SIM, CAMERA_SIM)
52+
# All sensors now publish to /diagnostics, so all faults come through diagnostic_bridge
5453
echo ""
5554
echo "Clearing all faults from FaultManager..."
5655
curl -s -X DELETE "${API_BASE}/apps/diagnostic_bridge/faults/LIDAR_SIM" > /dev/null 2>&1
5756
curl -s -X DELETE "${API_BASE}/apps/diagnostic_bridge/faults/CAMERA_SIM" > /dev/null 2>&1
57+
curl -s -X DELETE "${API_BASE}/apps/diagnostic_bridge/faults/IMU_SIM" > /dev/null 2>&1
58+
curl -s -X DELETE "${API_BASE}/apps/diagnostic_bridge/faults/GPS_SIM" > /dev/null 2>&1
5859

59-
# Modern path faults (via anomaly_detector direct service call)
60+
# Faults from anomaly_detector (modern path for anomaly detection)
6061
curl -s -X DELETE "${API_BASE}/apps/anomaly_detector/faults/SENSOR_TIMEOUT" > /dev/null 2>&1
6162
curl -s -X DELETE "${API_BASE}/apps/anomaly_detector/faults/SENSOR_NAN" > /dev/null 2>&1
6263
curl -s -X DELETE "${API_BASE}/apps/anomaly_detector/faults/SENSOR_OUT_OF_RANGE" > /dev/null 2>&1

demos/sensor_diagnostics/src/anomaly_detector_node.cpp

Lines changed: 8 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
// Copyright 2025 selfpatch
1+
// Copyright 2026 selfpatch
22
// SPDX-License-Identifier: Apache-2.0
33

44
/// @file anomaly_detector_node.cpp
@@ -43,12 +43,13 @@ class AnomalyDetectorNode : public rclcpp::Node
4343

4444
// Create subscribers for MODERN path sensors (IMU, GPS)
4545
// Note: LiDAR and Camera use LEGACY path via /diagnostics → diagnostic_bridge
46+
// Topics use absolute paths matching sensor namespace (/sensors/imu_sim/imu, /sensors/gps_sim/fix)
4647
imu_sub_ = this->create_subscription<sensor_msgs::msg::Imu>(
47-
"/sensors/imu", 10,
48+
"/sensors/imu_sim/imu", 10,
4849
std::bind(&AnomalyDetectorNode::imu_callback, this, std::placeholders::_1));
4950

5051
gps_sub_ = this->create_subscription<sensor_msgs::msg::NavSatFix>(
51-
"/sensors/fix", 10,
52+
"/sensors/gps_sim/fix", 10,
5253
std::bind(&AnomalyDetectorNode::gps_callback, this, std::placeholders::_1));
5354

5455
// Create publisher for detected faults (supplementary diagnostic topic)
@@ -173,8 +174,11 @@ class AnomalyDetectorNode : public rclcpp::Node
173174
const std::string & source, const std::string & code,
174175
const std::string & message, uint8_t severity = 2)
175176
{
176-
// Track active faults for later clearing
177+
// Skip if already reported (avoid spamming FaultManager)
177178
std::string fault_key = source + ":" + code;
179+
if (active_faults_.count(fault_key)) {
180+
return;
181+
}
178182
active_faults_.insert(fault_key);
179183

180184
// Publish to diagnostic topic (legacy)

demos/sensor_diagnostics/src/camera_sim_node.cpp

Lines changed: 1 addition & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
// Copyright 2025 selfpatch
1+
// Copyright 2026 selfpatch
22
// SPDX-License-Identifier: Apache-2.0
33

44
/// @file camera_sim_node.cpp
@@ -33,7 +33,6 @@ class CameraSimNode : public rclcpp::Node
3333
CameraSimNode()
3434
: Node("camera_sim"),
3535
rng_(std::random_device{}()),
36-
normal_dist_(0.0, 1.0),
3736
uniform_dist_(0.0, 1.0)
3837
{
3938
// Declare parameters
@@ -258,7 +257,6 @@ class CameraSimNode : public rclcpp::Node
258257

259258
// Random number generation
260259
std::mt19937 rng_;
261-
std::normal_distribution<double> normal_dist_;
262260
std::uniform_real_distribution<double> uniform_dist_;
263261

264262
// Parameters

demos/sensor_diagnostics/src/gps_sim_node.cpp

Lines changed: 12 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
// Copyright 2025 selfpatch
1+
// Copyright 2026 selfpatch
22
// SPDX-License-Identifier: Apache-2.0
33

44
/// @file gps_sim_node.cpp
@@ -13,6 +13,7 @@
1313
#include <memory>
1414
#include <random>
1515

16+
#include "diagnostic_msgs/msg/diagnostic_array.hpp"
1617
#include "diagnostic_msgs/msg/diagnostic_status.hpp"
1718
#include "diagnostic_msgs/msg/key_value.hpp"
1819
#include "rclcpp/rclcpp.hpp"
@@ -48,8 +49,9 @@ class GpsSimNode : public rclcpp::Node
4849

4950
// Create publishers
5051
fix_pub_ = this->create_publisher<sensor_msgs::msg::NavSatFix>("fix", 10);
51-
diag_pub_ = this->create_publisher<diagnostic_msgs::msg::DiagnosticStatus>(
52-
"diagnostics", 10);
52+
// Publish to absolute /diagnostics topic for legacy fault reporting via diagnostic_bridge
53+
diag_pub_ = this->create_publisher<diagnostic_msgs::msg::DiagnosticArray>(
54+
"/diagnostics", 10);
5355

5456
// Create timer (with rate validation)
5557
double rate = this->get_parameter("rate").as_double();
@@ -190,8 +192,12 @@ class GpsSimNode : public rclcpp::Node
190192

191193
void publish_diagnostics(const std::string & status, const std::string & message)
192194
{
195+
auto diag_array = diagnostic_msgs::msg::DiagnosticArray();
196+
diag_array.header.stamp = this->now();
197+
193198
auto diag = diagnostic_msgs::msg::DiagnosticStatus();
194199
diag.name = "gps_sim";
200+
diag.hardware_id = "gps_sensor";
195201

196202
if (status == "OK") {
197203
diag.level = diagnostic_msgs::msg::DiagnosticStatus::OK;
@@ -216,12 +222,13 @@ class GpsSimNode : public rclcpp::Node
216222
kv.value = std::to_string(position_noise_stddev_) + "m";
217223
diag.values.push_back(kv);
218224

219-
diag_pub_->publish(diag);
225+
diag_array.status.push_back(diag);
226+
diag_pub_->publish(diag_array);
220227
}
221228

222229
// Publishers
223230
rclcpp::Publisher<sensor_msgs::msg::NavSatFix>::SharedPtr fix_pub_;
224-
rclcpp::Publisher<diagnostic_msgs::msg::DiagnosticStatus>::SharedPtr diag_pub_;
231+
rclcpp::Publisher<diagnostic_msgs::msg::DiagnosticArray>::SharedPtr diag_pub_;
225232

226233
// Timer
227234
rclcpp::TimerBase::SharedPtr timer_;

demos/sensor_diagnostics/src/imu_sim_node.cpp

Lines changed: 12 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
// Copyright 2025 selfpatch
1+
// Copyright 2026 selfpatch
22
// SPDX-License-Identifier: Apache-2.0
33

44
/// @file imu_sim_node.cpp
@@ -13,6 +13,7 @@
1313
#include <memory>
1414
#include <random>
1515

16+
#include "diagnostic_msgs/msg/diagnostic_array.hpp"
1617
#include "diagnostic_msgs/msg/diagnostic_status.hpp"
1718
#include "diagnostic_msgs/msg/key_value.hpp"
1819
#include "rclcpp/rclcpp.hpp"
@@ -44,8 +45,9 @@ class ImuSimNode : public rclcpp::Node
4445

4546
// Create publishers
4647
imu_pub_ = this->create_publisher<sensor_msgs::msg::Imu>("imu", 10);
47-
diag_pub_ = this->create_publisher<diagnostic_msgs::msg::DiagnosticStatus>(
48-
"diagnostics", 10);
48+
// Publish to absolute /diagnostics topic for legacy fault reporting via diagnostic_bridge
49+
diag_pub_ = this->create_publisher<diagnostic_msgs::msg::DiagnosticArray>(
50+
"/diagnostics", 10);
4951

5052
// Create timer (with rate validation)
5153
double rate = this->get_parameter("rate").as_double();
@@ -172,8 +174,12 @@ class ImuSimNode : public rclcpp::Node
172174

173175
void publish_diagnostics(const std::string & status, const std::string & message)
174176
{
177+
auto diag_array = diagnostic_msgs::msg::DiagnosticArray();
178+
diag_array.header.stamp = this->now();
179+
175180
auto diag = diagnostic_msgs::msg::DiagnosticStatus();
176181
diag.name = "imu_sim";
182+
diag.hardware_id = "imu_sensor";
177183

178184
if (status == "OK") {
179185
diag.level = diagnostic_msgs::msg::DiagnosticStatus::OK;
@@ -194,12 +200,13 @@ class ImuSimNode : public rclcpp::Node
194200
kv.value = std::to_string(msg_count_);
195201
diag.values.push_back(kv);
196202

197-
diag_pub_->publish(diag);
203+
diag_array.status.push_back(diag);
204+
diag_pub_->publish(diag_array);
198205
}
199206

200207
// Publishers
201208
rclcpp::Publisher<sensor_msgs::msg::Imu>::SharedPtr imu_pub_;
202-
rclcpp::Publisher<diagnostic_msgs::msg::DiagnosticStatus>::SharedPtr diag_pub_;
209+
rclcpp::Publisher<diagnostic_msgs::msg::DiagnosticArray>::SharedPtr diag_pub_;
203210

204211
// Timer
205212
rclcpp::TimerBase::SharedPtr timer_;

demos/sensor_diagnostics/src/lidar_sim_node.cpp

Lines changed: 19 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
// Copyright 2025 selfpatch
1+
// Copyright 2026 selfpatch
22
// SPDX-License-Identifier: Apache-2.0
33

44
/// @file lidar_sim_node.cpp
@@ -91,6 +91,14 @@ class LidarSimNode : public rclcpp::Node
9191
angle_min_ = this->get_parameter("angle_min").as_double();
9292
angle_max_ = this->get_parameter("angle_max").as_double();
9393
num_readings_ = this->get_parameter("num_readings").as_int();
94+
if (num_readings_ <= 0) {
95+
RCLCPP_WARN(
96+
this->get_logger(),
97+
"Invalid num_readings parameter (%d). Using default 360.",
98+
num_readings_);
99+
num_readings_ = 360;
100+
this->set_parameters({rclcpp::Parameter("num_readings", num_readings_)});
101+
}
94102
noise_stddev_ = this->get_parameter("noise_stddev").as_double();
95103
failure_probability_ = this->get_parameter("failure_probability").as_double();
96104
inject_nan_ = this->get_parameter("inject_nan").as_bool();
@@ -121,8 +129,17 @@ class LidarSimNode : public rclcpp::Node
121129
drift_rate_ = param.as_double();
122130
RCLCPP_INFO(this->get_logger(), "Drift rate changed to %.4f", drift_rate_);
123131
} else if (param.get_name() == "scan_rate") {
124-
// Update timer with new rate
132+
// Update timer with new rate (with validation)
125133
double rate = param.as_double();
134+
if (rate <= 0.0) {
135+
RCLCPP_WARN(
136+
this->get_logger(),
137+
"Invalid scan_rate parameter value (%f Hz). Rejecting change.",
138+
rate);
139+
result.successful = false;
140+
result.reason = "scan_rate must be positive";
141+
return result;
142+
}
126143
auto period = std::chrono::duration<double>(1.0 / rate);
127144
timer_ = this->create_wall_timer(
128145
std::chrono::duration_cast<std::chrono::nanoseconds>(period),

0 commit comments

Comments
 (0)