-
Notifications
You must be signed in to change notification settings - Fork 1.7k
Description
Security Summary
Severity
Medium (DoS from authenticated parameter client)
Impact
- AMCL: Process crash via unhandled exception (std::overflow_error) → Node termination → Localization failure
- Velocity Smoother: Process crash via unhandled exception (rclcpp::exceptions::RCLInvalidArgument) → Node termination → Loss of velocity control
Exploitability
Any client with parameter setting permissions can trigger the crash. Exploitable over local network/remote depending on ROS network configuration.
Suggested fix (short)
- Add parameter validation to reject zero or negative values for
save_pose_rate. - Add parameter validation to reject zero or negative values for
smoothing_frequency.
Patch preview for save_pose_rate
} else if (param_name == "save_pose_rate") {
double rate = parameter.as_double();
if (rate <= 0.0) {
RCLCPP_ERROR(get_logger(),
"save_pose_rate must be positive, received: %f", rate);
result.successful = false;
result.reason = "save_pose_rate must be greater than 0.0";
return result;
}
save_pose_rate = rate;
save_pose_period_ = tf2::durationFromSec(1.0 / save_pose_rate);
}Patch preview for smoothing_frequency
if (name == "smoothing_frequency") {
double frequency = parameter.as_double();
if (frequency <= 0.0) {
RCLCPP_ERROR(get_logger(),
"smoothing_frequency must be positive, received: %f", frequency);
result.successful = false;
result.reason = "smoothing_frequency must be greater than 0.0";
return result;
}
smoothing_frequency_ = frequency;
double timer_duration_ms = 1000.0 / smoothing_frequency_;
timer_ = create_wall_timer(
std::chrono::milliseconds(static_cast<int64_t>(timer_duration_ms)),
std::bind(&VelocitySmoother::smootherTimer, this));Tests added
- Unit test that attempts to set
save_pose_rateto 0.0 and asserts that parameter update is rejected with appropriate error message. - Unit test that attempts to set
smoothing_frequencyto 0.0 and asserts that parameter update is rejected with appropriate error message.
Labels
security, bug, needs-backport, parameter-validation
Bug report for save_pose_rate
Required Info:
- Operating System:
- Ubuntu 22.04
- ROS2 Version:
- ROS2 Humble
- Version or commit hash:
- 1.1.19 / bf40e4d
- DDS implementation:
- Fast DDS (rmw_fastrtps_cpp)
Steps to reproduce issue
-
Build nav2_amcl
-
Run amcl node:
ros2 run nav2_amcl amcl --ros-args -p use_sim_time:=false
-
Configure and activate the node:
ros2 lifecycle set /amcl configure ros2 lifecycle set /amcl activate
-
Set the save_pose_rate parameter to 0.0:
ros2 param set /amcl save_pose_rate 0.0
Expected behavior
The node should validate the parameter and reject it with an appropriate error message.
Actual behavior
terminate called after throwing an instance of 'std::overflow_error'
what(): Input t_sec is too large or too small for tf2::Duration
[ros2run]: AbortedRoot Cause Analysis
Vulnerability Location: nav2_amcl/src/amcl_node.cpp:1254 in AmclNode::dynamicParametersCallback()
Attack Surface: The dynamicParametersCallback
Issue Details:
-
No Validation for 0:
navigation2/nav2_amcl/src/amcl_node.cpp
Lines 1249 to 1250 in bf40e4d
} else if (param_name == "recovery_alpha_slow") { alpha_slow_ = parameter.as_double(); -
Zero division:
navigation2/nav2_amcl/src/amcl_node.cpp
Line 1254 in bf40e4d
save_pose_period_ = tf2::durationFromSec(1.0 / save_pose_rate); -
Unhandled exception:
https://github.com/ros2/geometry2/blob/ba19c34c3fd34a642d7b53928c848c2994a26748/tf2/src/time.cpp#L44-L56
Bug report for smoothing_frequency
Required Info:
- Operating System:
- Ubuntu 22.04
- ROS2 Version:
- ROS2 Humble
- Version or commit hash:
- 1.1.19 / bf40e4d
- DDS implementation:
- Fast DDS (rmw_fastrtps_cpp)
Steps to reproduce issue
-
Build nav2_velocity_smoother
-
yaml
velocity_smoother: ros__parameters: smoothing_frequency: 20.0 scale_velocities: true feedback: "OPEN_LOOP" max_velocity: [0.5, 0.0, 2.5] min_velocity: [-0.5, 0.0, -2.5] max_accel: [2.5, 0.0, 3.2] max_decel: [-2.5, 0.0, -3.2] odom_topic: "odom" odom_duration: 0.1 deadband_velocity: [0.0, 0.0, 0.0] velocity_timeout: 1.0
-
Run velocity_smoother node:
ros2 run nav2_velocity_smoother velocity_smoother \ --ros-args --params-file ros/zero_division_test/velocity_smoother_test.yaml -
Configure and activate the node:
ros2 lifecycle set /velocity_smoother configure ros2 lifecycle set /velocity_smoother activate
-
Set the smoothing_frequency parameter to 0.0:
ros2 param set /velocity_smoother smoothing_frequency 0.0
Expected behavior
The node should validate the parameter and reject it with an appropriate error message:
- Invalid parameter values should be rejected before computation
- The parameter update should fail gracefully with a descriptive error
- The node should remain operational after the rejected parameter change
Actual behavior
>>> [rcutils|error_handling.c:108] rcutils_set_error_state()
This error state is being overwritten:
'timer is canceled, at ./src/rcl/timer.c:249'
with this new error message:
'timer period must be non-negative, at ./src/rcl/timer.c:139'
rcutils_reset_error() should be called after error handling to avoid this.
<<<
terminate called after throwing an instance of 'rclcpp::exceptions::RCLInvalidArgument'
what(): Couldn't initialize rcl timer handle: timer period must be non-negative, at ./src/rcl/timer.c:139
[ros2run]: AbortedRoot Cause Analysis
Vulnerability Location: nav2_velocity_smoother/src/velocity_smoother.cpp:344 in VelocitySmoother::dynamicParametersCallback()
Attack Surface: The dynamicParametersCallback
Issue Details:
-
No Validation for 0:
navigation2/nav2_velocity_smoother/src/velocity_smoother.cpp
Lines 337 to 338 in bf40e4d
if (name == "smoothing_frequency") { smoothing_frequency_ = parameter.as_double(); -
Zero division:
double timer_duration_ms = 1000.0 / smoothing_frequency_; -
Unhandled Exception:
When
static_cast<int64_t>(inf)converts infinity to int64_t, it produces a negative value (implementation-defined behavior).
The rcl timer creation then validates the period and throws:rclcpp::exceptions::RCLInvalidArgument: timer period must be non-negative
https://github.com/ros2/rcl/blob/90f5538f4a6414e3e18ec3a4b4a7864dbd13405c/rcl/src/rcl/timer.c#L126-L141