Skip to content

Publish parameters to MQTT#270

Merged
rovo89 merged 4 commits intoClemensElflein:mainfrom
rovo89:feat/mqtt-params
Mar 14, 2026
Merged

Publish parameters to MQTT#270
rovo89 merged 4 commits intoClemensElflein:mainfrom
rovo89:feat/mqtt-params

Conversation

@rovo89
Copy link
Copy Markdown
Collaborator

@rovo89 rovo89 commented Mar 12, 2026

For now, this is done once at startup, might republish on changes in the future.

Summary by CodeRabbit

  • New Features
    • System parameters are now published as retained JSON to MQTT when the system connects, alongside other metadata.
    • Parameters are collected, sorted, and published; entries containing "password" are redacted (exported as null).
    • JSON conversion expanded to handle booleans, numbers, strings, arrays, objects, date/time, and base64-like values.
    • Added a capability flag indicating parameter-publishing support.

For now, this is done once at startup, might republish on changes in the future.
@coderabbitai
Copy link
Copy Markdown
Contributor

coderabbitai Bot commented Mar 12, 2026

Caution

Review failed

The pull request is closed.

ℹ️ Recent review info
⚙️ Run configuration

Configuration used: Organization UI

Review profile: CHILL

Plan: Pro

Run ID: d47891c1-75c6-4a72-9594-7aebb79fa58a

📥 Commits

Reviewing files that changed from the base of the PR and between 2ecf398 and f865e57.

📒 Files selected for processing (1)
  • src/lib/xbot_monitoring/src/capabilities.h

Walkthrough

Publishes all ROS parameters as retained JSON over MQTT on connect, adding xmlrpc_to_json(XmlRpc::XmlRpcValue) and publish_params(), and registers a new capability entry mqtt:params in capabilities.h.

Changes

Cohort / File(s) Summary
Parameter publishing
src/lib/xbot_monitoring/src/xbot_monitoring.cpp
Added publish_params() and helper xmlrpc_to_json(XmlRpc::XmlRpcValue) to collect all ROS parameters, mask entries containing "password" (export as null), sort names, convert XmlRpc types to JSON (Bool, Int, Double, String, Array, Struct, DateTime, Base64) and publish to params/json with retention; invoked from MqttCallback::connected.
Capabilities update
src/lib/xbot_monitoring/src/capabilities.h
Added capability entry {"mqtt:params", 1} to the CAPABILITIES list.

Estimated code review effort

🎯 2 (Simple) | ⏱️ ~10 minutes

Possibly related PRs

Poem

🐇 I hopped through params, row by row,
XmlRpc turned JSON — off they go,
Secrets masked where passwords hide,
Sorted leaves on MQTT’s tide,
A little rabbit keeps the flow. 🥕

🚥 Pre-merge checks | ✅ 2 | ❌ 1

❌ Failed checks (1 warning)

Check name Status Explanation Resolution
Docstring Coverage ⚠️ Warning Docstring coverage is 0.00% which is insufficient. The required threshold is 80.00%. Write docstrings for the functions missing them to satisfy the coverage threshold.
✅ Passed checks (2 passed)
Check name Status Explanation
Description Check ✅ Passed Check skipped - CodeRabbit’s high-level summary is enabled.
Title check ✅ Passed The pull request title 'Publish parameters to MQTT' directly and accurately summarizes the main change: adding functionality to publish ROS parameters to MQTT topics.

✏️ Tip: You can configure your own custom pre-merge checks in the settings.

✨ Finishing Touches
🧪 Generate unit tests (beta)
  • Create PR with unit tests
  • Post copyable unit tests in a comment
📝 Coding Plan
  • Generate coding plan for human review comments

Thanks for using CodeRabbit! It's free for OSS, and your support helps us grow. If you like it, consider giving us a shout-out.

❤️ Share

Comment @coderabbitai help to get the list of available commands and usage tips.

@rovo89
Copy link
Copy Markdown
Collaborator Author

rovo89 commented Mar 12, 2026

Payload (pretty-printed):

{
    "/converter1/frame": "map",
    "/converter1/topic": "/ll/position/gps",
    "/joy/autorepeat_rate": 10.0,
    "/joy/coalesce_interval": 0.06,
    "/joy_teleop/enable_turbo_button": 4,
    "/joy_teleop/scale_angular": 1.5,
    "/joy_teleop/scale_angular_turbo": 3.0,
    "/joy_teleop/scale_linear": 0.5,
    "/joy_teleop/scale_linear_turbo": 1.0,
    "/ll/bind_ip": "0.0.0.0",
    "/ll/services/diff_drive/ticks_per_m": 1600.0,
    "/ll/services/diff_drive/wheel_distance_m": 0.325,
    "/ll/services/gps/absolute_coords": false,
    "/ll/services/gps/baud_rate": 921600,
    "/ll/services/gps/datum_height": 0,
    "/ll/services/gps/datum_lat": 48.0,
    "/ll/services/gps/datum_long": 11.0,
    "/ll/services/gps/protocol": "UBX",
    "/ll/services/imu/axis_config": "+X-Y-Z",
    "/ll/services/power/battery_critical_high_voltage": 29.0,
    "/ll/services/power/battery_critical_voltage": 23.0,
    "/ll/services/power/battery_empty_voltage": 24.0,
    "/ll/services/power/battery_full_voltage": 28.5,
    "/ll/services/power/charge_critical_high_current": 1.5,
    "/ll/services/power/charge_critical_high_voltage": 30.0,
    "/ll/services/sound/language": "en",
    "/ll/services/sound/volume": -1,
    "/move_base_flex/DockingFTCPlanner/acceleration": 1.0,
    "/move_base_flex/DockingFTCPlanner/check_obstacles": false,
    "/move_base_flex/DockingFTCPlanner/debug_pid": false,
    "/move_base_flex/DockingFTCPlanner/forward_only": false,
    "/move_base_flex/DockingFTCPlanner/goal_timeout": 20.0,
    "/move_base_flex/DockingFTCPlanner/kd_ang": 0.0,
    "/move_base_flex/DockingFTCPlanner/kd_lat": 0.0,
    "/move_base_flex/DockingFTCPlanner/kd_lon": 0.0,
    "/move_base_flex/DockingFTCPlanner/ki_ang": 0.0,
    "/move_base_flex/DockingFTCPlanner/ki_ang_max": 10.0,
    "/move_base_flex/DockingFTCPlanner/ki_lat": 0.0,
    "/move_base_flex/DockingFTCPlanner/ki_lat_max": 10.0,
    "/move_base_flex/DockingFTCPlanner/ki_lon": 0.0,
    "/move_base_flex/DockingFTCPlanner/ki_lon_max": 10.0,
    "/move_base_flex/DockingFTCPlanner/kp_ang": 1.0,
    "/move_base_flex/DockingFTCPlanner/kp_lat": 6.15,
    "/move_base_flex/DockingFTCPlanner/kp_lon": 4.0,
    "/move_base_flex/DockingFTCPlanner/max_cmd_vel_ang": 3.1,
    "/move_base_flex/DockingFTCPlanner/max_cmd_vel_speed": 0.6,
    "/move_base_flex/DockingFTCPlanner/max_follow_distance": 1.0,
    "/move_base_flex/DockingFTCPlanner/max_goal_angle_error": 20.0,
    "/move_base_flex/DockingFTCPlanner/max_goal_distance_error": 0.1,
    "/move_base_flex/DockingFTCPlanner/oscillation_recovery": false,
    "/move_base_flex/DockingFTCPlanner/restore_defaults": false,
    "/move_base_flex/DockingFTCPlanner/speed_angular": 40.0,
    "/move_base_flex/DockingFTCPlanner/speed_fast": 0.1,
    "/move_base_flex/DockingFTCPlanner/speed_fast_threshold": 5.0,
    "/move_base_flex/DockingFTCPlanner/speed_fast_threshold_angle": 5.0,
    "/move_base_flex/DockingFTCPlanner/speed_slow": 0.1,
    "/move_base_flex/FTCPlanner/acceleration": 0.1,
    "/move_base_flex/FTCPlanner/check_obstacles": false,
    "/move_base_flex/FTCPlanner/debug_pid": true,
    "/move_base_flex/FTCPlanner/forward_only": true,
    "/move_base_flex/FTCPlanner/goal_timeout": 20.0,
    "/move_base_flex/FTCPlanner/kd_ang": 0.5,
    "/move_base_flex/FTCPlanner/kd_lat": 1.23,
    "/move_base_flex/FTCPlanner/kd_lon": 0.0,
    "/move_base_flex/FTCPlanner/ki_ang": 0.0,
    "/move_base_flex/FTCPlanner/ki_ang_max": 62.0,
    "/move_base_flex/FTCPlanner/ki_lat": 0.06153,
    "/move_base_flex/FTCPlanner/ki_lat_max": 62.0,
    "/move_base_flex/FTCPlanner/ki_lon": 0.0,
    "/move_base_flex/FTCPlanner/ki_lon_max": 10.0,
    "/move_base_flex/FTCPlanner/kp_ang": 3.0,
    "/move_base_flex/FTCPlanner/kp_lat": 25.0,
    "/move_base_flex/FTCPlanner/kp_lon": 4.0,
    "/move_base_flex/FTCPlanner/max_cmd_vel_ang": 3.1,
    "/move_base_flex/FTCPlanner/max_cmd_vel_speed": 1.0,
    "/move_base_flex/FTCPlanner/max_follow_distance": 1.0,
    "/move_base_flex/FTCPlanner/max_goal_angle_error": 20.0,
    "/move_base_flex/FTCPlanner/max_goal_distance_error": 0.2,
    "/move_base_flex/FTCPlanner/oscillation_recovery": false,
    "/move_base_flex/FTCPlanner/restore_defaults": false,
    "/move_base_flex/FTCPlanner/speed_angular": 45.0,
    "/move_base_flex/FTCPlanner/speed_fast": 0.4,
    "/move_base_flex/FTCPlanner/speed_fast_threshold": 1.0,
    "/move_base_flex/FTCPlanner/speed_fast_threshold_angle": 20.0,
    "/move_base_flex/FTCPlanner/speed_slow": 0.15,
    "/move_base_flex/GlobalPlanner/orientation_mode": 1,
    "/move_base_flex/controller_frequency": 1.0,
    "/move_base_flex/controller_patience": 30.0,
    "/move_base_flex/controllers": [
        {
            "name": "FTCPlanner",
            "type": "ftc_local_planner/FTCPlanner"
        },
        {
            "name": "DockingFTCPlanner",
            "type": "ftc_local_planner/FTCPlanner"
        }
    ],
    "/move_base_flex/global_costmap/global_frame": "map",
    "/move_base_flex/global_costmap/inflation_layer/inflation_radius": 1.0,
    "/move_base_flex/global_costmap/obstacle_layer/max_obstacle_height": 1.0,
    "/move_base_flex/global_costmap/obstacle_layer/obstacle_range": 3.0,
    "/move_base_flex/global_costmap/obstacle_layer/raytrace_range": 4.0,
    "/move_base_flex/global_costmap/plugins": [
        {
            "name": "static_layer",
            "type": "costmap_2d::StaticLayer"
        },
        {
            "name": "obstacle_layer",
            "type": "costmap_2d::ObstacleLayer"
        },
        {
            "name": "inflation_layer",
            "type": "costmap_2d::InflationLayer"
        }
    ],
    "/move_base_flex/global_costmap/publish_frequency": 1.0,
    "/move_base_flex/global_costmap/resolution": 0.1,
    "/move_base_flex/global_costmap/robot_base_frame": "base_link",
    "/move_base_flex/global_costmap/robot_radius": 0.0,
    "/move_base_flex/global_costmap/rolling_window": false,
    "/move_base_flex/global_costmap/static_layer/map_topic": "mower_map_service/map",
    "/move_base_flex/global_costmap/update_frequency": 1.0,
    "/move_base_flex/local_costmap/global_frame": "map",
    "/move_base_flex/local_costmap/height": 1.5,
    "/move_base_flex/local_costmap/inflation_layer/inflation_radius": 0.0,
    "/move_base_flex/local_costmap/obstacle_layer/max_obstacle_height": 1.0,
    "/move_base_flex/local_costmap/obstacle_layer/obstacle_range": 3.0,
    "/move_base_flex/local_costmap/obstacle_layer/raytrace_range": 4.0,
    "/move_base_flex/local_costmap/plugins": [
        {
            "name": "static_layer",
            "type": "costmap_2d::StaticLayer"
        },
        {
            "name": "obstacle_layer",
            "type": "costmap_2d::ObstacleLayer"
        },
        {
            "name": "inflation_layer",
            "type": "costmap_2d::InflationLayer"
        }
    ],
    "/move_base_flex/local_costmap/publish_frequency": 2.0,
    "/move_base_flex/local_costmap/resolution": 0.15,
    "/move_base_flex/local_costmap/robot_base_frame": "base_link",
    "/move_base_flex/local_costmap/robot_radius": 0.0,
    "/move_base_flex/local_costmap/rolling_window": true,
    "/move_base_flex/local_costmap/static_layer/map_topic": "mower_map_service/map",
    "/move_base_flex/local_costmap/update_frequency": 5.0,
    "/move_base_flex/local_costmap/width": 1.5,
    "/move_base_flex/oscillation_distance": 0.2,
    "/move_base_flex/oscillation_timeout": 10.0,
    "/move_base_flex/planner_frequency": 1.0,
    "/move_base_flex/planner_patience": 5.0,
    "/move_base_flex/planners": [
        {
            "name": "GlobalPlanner",
            "type": "global_planner/GlobalPlanner"
        }
    ],
    "/move_base_legacy_relay/base_global_planner": "GlobalPlanner",
    "/move_base_legacy_relay/base_local_planner": "FTCPlanner",
    "/mower_comms_v2/dfp_is_5v": false,
    "/mower_comms_v2/language": "en",
    "/mower_comms_v2/volume": -1,
    "/mower_comms_v2/wheel_distance_m": 0,
    "/mower_comms_v2/wheel_ticks_per_m": 0,
    "/mower_logic/automatic_mode": 0,
    "/mower_logic/cu_rain_threshold": -1,
    "/mower_logic/docking_approach_distance": 1.0,
    "/mower_logic/docking_extra_time": 0.0,
    "/mower_logic/docking_redock": false,
    "/mower_logic/docking_retry_count": 4,
    "/mower_logic/emergency_lift_period": -1,
    "/mower_logic/emergency_tilt_period": -1,
    "/mower_logic/gps_timeout": 10.0,
    "/mower_logic/gps_wait_time": 2.0,
    "/mower_logic/ignore_charging_current": false,
    "/mower_logic/mow_angle_increment": 0.0,
    "/mower_logic/mow_angle_offset": 0.0,
    "/mower_logic/mow_angle_offset_is_absolute": false,
    "/mower_logic/outline_overlap_count": 0,
    "/mower_logic/rain_check_seconds": 20,
    "/mower_logic/rain_delay_minutes": 30,
    "/mower_logic/rain_mode": 0,
    "/mower_logic/undock_angle": 0.0,
    "/mower_logic/undock_angled_distance": 0.0,
    "/mower_logic/undock_distance": 1.0,
    "/mower_logic/undock_fixed_angle": true,
    "/mower_logic/undock_use_curve": true,
    "/mower_simulation/battery_voltage": 28.0,
    "/mower_simulation/emergency_stop": false,
    "/mower_simulation/is_charging": false,
    "/mower_simulation/mower_error": false,
    "/mower_simulation/mower_running": false,
    "/mower_simulation/rain": false,
    "/mower_simulation/temperature_mower": 40.0,
    "/mower_simulation/wheels_stalled": false,
    "/ntrip_client/reconnect_attempt_max": 5,
    "/ntrip_client/reconnect_attempt_wait_seconds": 99999,
    "/rosdistro": "noetic\n",
    "/roslaunch/uris/host_974bcf26ecaa__39599": "http://974bcf26ecaa:39599/",
    "/rosversion": "1.17.4\n",
    "/run_id": "e5c2a810-1de3-11f1-81f8-c2c4884f8add",
    "/twist_mux/topics": [
        {
            "name": "navigation",
            "priority": 10,
            "timeout": 0.5,
            "topic": "nav_vel"
        },
        {
            "name": "logic",
            "priority": 50,
            "timeout": 0.5,
            "topic": "logic_vel"
        },
        {
            "name": "logic",
            "priority": 100,
            "timeout": 0.5,
            "topic": "override_vel"
        }
    ],
    "/xbot_monitoring/external_mqtt_enable": false,
    "/xbot_monitoring/external_mqtt_hostname": "",
    "/xbot_monitoring/external_mqtt_password": null,
    "/xbot_monitoring/external_mqtt_port": "",
    "/xbot_monitoring/external_mqtt_topic_prefix": "",
    "/xbot_monitoring/external_mqtt_username": "",
    "/xbot_positioning/antenna_offset_x": 0.3,
    "/xbot_positioning/antenna_offset_y": 0.0,
    "/xbot_positioning/debug": false,
    "/xbot_positioning/max_gps_accuracy": 0.2
}

Copy link
Copy Markdown
Contributor

@coderabbitai coderabbitai Bot left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Actionable comments posted: 1

🧹 Nitpick comments (1)
src/lib/xbot_monitoring/src/xbot_monitoring.cpp (1)

279-304: Remove the const reference suggestion — it would break the struct case.

The parameter must remain passed by value because XmlRpc::XmlRpcValue does not define const overloads for begin() and end(), which are required for the TypeStruct case. The current implementation is correct.

The suggestion to log unhandled types remains valid: the default case silently returns nullptr, which could mask unexpected parameter types during debugging. Consider logging a warning for types like TypeDateTime or TypeBase64 if they appear.

🤖 Prompt for AI Agents
Verify each finding against the current code and only fix it if needed.

In `@src/lib/xbot_monitoring/src/xbot_monitoring.cpp` around lines 279 - 304, Keep
the parameter of xmlrpc_to_json(XmlRpc::XmlRpcValue value) by value (do not
change to const reference) because XmlRpc::XmlRpcValue does not provide const
begin()/end() overloads required by the TypeStruct handling; instead, add a
warning/log in the default branch of xmlrpc_to_json that reports the unexpected
value.getType() (and specifically mention TypeDateTime/TypeBase64 as examples)
so unhandled XML-RPC types are visible during debugging—use the project logger
or e.g. ROS_WARN_STREAM / std::cerr to emit the type integer/name in that
default case.
🤖 Prompt for all review comments with AI agents
Verify each finding against the current code and only fix it if needed.

Inline comments:
In `@src/lib/xbot_monitoring/src/xbot_monitoring.cpp`:
- Around line 306-319: publish_params currently serializes and publishes all ROS
parameters which can leak credentials (e.g., external_mqtt_username,
external_mqtt_password); modify publish_params to filter out sensitive entries
before building the JSON by applying a denylist of patterns (e.g., "password",
"secret", "token", "key", "credential") or an allowlist of safe prefixes, and
skip any param name matching those patterns when iterating param_names; ensure
the filtering logic is centralized (e.g., a helper like is_sensitive_param(const
std::string&)) and used right before calling xmlrpc_to_json and
try_publish("params/json", ...) so sensitive values are never added to params or
sent over MQTT.

---

Nitpick comments:
In `@src/lib/xbot_monitoring/src/xbot_monitoring.cpp`:
- Around line 279-304: Keep the parameter of xmlrpc_to_json(XmlRpc::XmlRpcValue
value) by value (do not change to const reference) because XmlRpc::XmlRpcValue
does not provide const begin()/end() overloads required by the TypeStruct
handling; instead, add a warning/log in the default branch of xmlrpc_to_json
that reports the unexpected value.getType() (and specifically mention
TypeDateTime/TypeBase64 as examples) so unhandled XML-RPC types are visible
during debugging—use the project logger or e.g. ROS_WARN_STREAM / std::cerr to
emit the type integer/name in that default case.

ℹ️ Review info
⚙️ Run configuration

Configuration used: Organization UI

Review profile: CHILL

Plan: Pro

Run ID: f8138377-26d0-43bc-ae98-28e6b050607b

📥 Commits

Reviewing files that changed from the base of the PR and between 303a0e1 and bb0e3d3.

📒 Files selected for processing (1)
  • src/lib/xbot_monitoring/src/xbot_monitoring.cpp

Comment thread src/lib/xbot_monitoring/src/xbot_monitoring.cpp
rovo89 added 2 commits March 12, 2026 08:00
Just for completeness - I have neither of them in my params. Also ensure that all types are handled.
We'll need to think about authentication when we let users manage config via app/MQTT... but better start with this gap closed.
Copy link
Copy Markdown
Contributor

@coderabbitai coderabbitai Bot left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

♻️ Duplicate comments (1)
src/lib/xbot_monitoring/src/xbot_monitoring.cpp (1)

339-341: ⚠️ Potential issue | 🟡 Minor

Password filter is case-sensitive.

The substring check name.find("password") won't match "Password" or "PASSWORD". While ROS parameters in this codebase follow a consistent lowercase naming convention, consider a case-insensitive match for defensive filtering against parameter naming variations.

🔒 Proposed fix for case-insensitive matching
     for (const auto &name : param_names) {
+        std::string lower_name = name;
+        std::transform(lower_name.begin(), lower_name.end(), lower_name.begin(), ::tolower);
-        if (name.find("password") != std::string::npos) {
+        if (lower_name.find("password") != std::string::npos) {
             params[name] = nullptr;
             continue;
         }

Requires adding #include <algorithm> at the top of the file.

🤖 Prompt for AI Agents
Verify each finding against the current code and only fix it if needed.

In `@src/lib/xbot_monitoring/src/xbot_monitoring.cpp` around lines 339 - 341, The
current check using name.find("password") is case-sensitive; change it to a
case-insensitive test by making a lowercase copy of the parameter name (e.g.,
lowerName) and searching lowerName.find("password") instead, then keep the
existing behavior of setting params[name] = nullptr on match; add the necessary
includes (e.g., `#include` <algorithm> and `#include` <cctype>) so std::transform
and std::tolower can be used.
🧹 Nitpick comments (1)
src/lib/xbot_monitoring/src/xbot_monitoring.cpp (1)

279-330: Implementation is correct; consider efficiency for large nested structures.

The function correctly handles all XmlRpcValue types. The #pragma to enforce -Wswitch-enum is a nice touch for maintainability.

Passing value by-value creates copies at each recursion level. For typical ROS parameters this is fine, but deeply nested or large structures could incur overhead. Since XmlRpcValue's accessors are non-const, accepting a non-const reference and documenting that it may be mutated would be an alternative if performance becomes a concern.

🤖 Prompt for AI Agents
Verify each finding against the current code and only fix it if needed.

In `@src/lib/xbot_monitoring/src/xbot_monitoring.cpp` around lines 279 - 330, The
function currently copies XmlRpc::XmlRpcValue on each recursive call (signature
xmlrpc_to_json(XmlRpc::XmlRpcValue value)); change the signature to take a
reference (e.g., xmlrpc_to_json(XmlRpc::XmlRpcValue& value)) to avoid costly
copies for large/deep structures, update all call sites/recursions accordingly
(xmlrpc_to_json(value[i]), xmlrpc_to_json(it->second) still work) and add a
brief comment above xmlrpc_to_json documenting that a non-const reference is
used and callers may have their XmlRpc::XmlRpcValue mutated.
🤖 Prompt for all review comments with AI agents
Verify each finding against the current code and only fix it if needed.

Duplicate comments:
In `@src/lib/xbot_monitoring/src/xbot_monitoring.cpp`:
- Around line 339-341: The current check using name.find("password") is
case-sensitive; change it to a case-insensitive test by making a lowercase copy
of the parameter name (e.g., lowerName) and searching lowerName.find("password")
instead, then keep the existing behavior of setting params[name] = nullptr on
match; add the necessary includes (e.g., `#include` <algorithm> and `#include`
<cctype>) so std::transform and std::tolower can be used.

---

Nitpick comments:
In `@src/lib/xbot_monitoring/src/xbot_monitoring.cpp`:
- Around line 279-330: The function currently copies XmlRpc::XmlRpcValue on each
recursive call (signature xmlrpc_to_json(XmlRpc::XmlRpcValue value)); change the
signature to take a reference (e.g., xmlrpc_to_json(XmlRpc::XmlRpcValue& value))
to avoid costly copies for large/deep structures, update all call
sites/recursions accordingly (xmlrpc_to_json(value[i]),
xmlrpc_to_json(it->second) still work) and add a brief comment above
xmlrpc_to_json documenting that a non-const reference is used and callers may
have their XmlRpc::XmlRpcValue mutated.

ℹ️ Review info
⚙️ Run configuration

Configuration used: Organization UI

Review profile: CHILL

Plan: Pro

Run ID: d80e5495-f23b-48d4-addc-36762ec35114

📥 Commits

Reviewing files that changed from the base of the PR and between bb0e3d3 and 2ecf398.

📒 Files selected for processing (1)
  • src/lib/xbot_monitoring/src/xbot_monitoring.cpp

Copy link
Copy Markdown
Collaborator

@Apehaenger Apehaenger left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

LGTM 👍

Comment on lines +279 to +280
#pragma GCC diagnostic push
#pragma GCC diagnostic warning "-Wswitch-enum"
Copy link
Copy Markdown
Owner

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

why the pragma instead of a default case? I assume the cases are actually exhaustive and the default would only be to silence the warning? In that case the default with an error log would still be beneficial in case new types get added?

Copy link
Copy Markdown
Collaborator Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Originally, I didn't have support for dates and base64. So I made the AI rabbit happy by asking my AI to implement that. Then I asked if all types are implemented now and they almost were, except for "invalid". So I thought "why not statically ensure that all". I have tested various variants, with the goal to trigger a warning if one type is missing and no warning of all is implemented. The default case would always qualify as "all implemented" for the compiler, so it had to go away. The fallback return is after the switch, otherwise there is another warning, even if all types are handled. The alternative to the pragma was to add it to the compiler options, but that would affect other code as well. A log in the default case would only be executed at runtime...

@rovo89 rovo89 merged commit 7596011 into ClemensElflein:main Mar 14, 2026
4 of 5 checks passed
@rovo89 rovo89 deleted the feat/mqtt-params branch March 14, 2026 23:44
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Labels

None yet

Projects

None yet

Development

Successfully merging this pull request may close these issues.

3 participants