From 70e31870af9b8e82f6cedae184a299a33f85fd77 Mon Sep 17 00:00:00 2001 From: Claudio Chies <61051109+Claudio-Chies@users.noreply.github.com> Date: Wed, 8 Apr 2026 18:07:47 +0200 Subject: [PATCH] feat(params): update max values for various parameters (#27002) --- src/drivers/actuators/voxl_esc/voxl_esc_params.yaml | 2 +- src/drivers/distance_sensor/teraranger/parameters.yaml | 2 +- src/drivers/gps/params.yaml | 2 +- src/lib/adsb/parameters.yaml | 2 +- src/modules/commander/commander_params.yaml | 2 +- src/modules/mavlink/mavlink_params.yaml | 2 +- src/modules/mc_pos_control/multicopter_autonomous_params.yaml | 2 +- 7 files changed, 7 insertions(+), 7 deletions(-) diff --git a/src/drivers/actuators/voxl_esc/voxl_esc_params.yaml b/src/drivers/actuators/voxl_esc/voxl_esc_params.yaml index 5dfd6613f0..1017e23027 100644 --- a/src/drivers/actuators/voxl_esc/voxl_esc_params.yaml +++ b/src/drivers/actuators/voxl_esc/voxl_esc_params.yaml @@ -49,7 +49,7 @@ parameters: default: 0 reboot_required: true min: 0 - max: 2 + max: 3 VOXL_ESC_SDIR1: description: short: UART ESC ID 1 Spin Direction Flag diff --git a/src/drivers/distance_sensor/teraranger/parameters.yaml b/src/drivers/distance_sensor/teraranger/parameters.yaml index 42235d574d..c587ce71f9 100644 --- a/src/drivers/distance_sensor/teraranger/parameters.yaml +++ b/src/drivers/distance_sensor/teraranger/parameters.yaml @@ -16,4 +16,4 @@ parameters: default: 0 reboot_required: true min: 0 - max: 3 + max: 5 diff --git a/src/drivers/gps/params.yaml b/src/drivers/gps/params.yaml index 9caa8ca75e..ec4cc1863a 100644 --- a/src/drivers/gps/params.yaml +++ b/src/drivers/gps/params.yaml @@ -126,7 +126,7 @@ parameters: 6: Ground Control Station (UART2 outputs NMEA) default: 0 min: 0 - max: 1 + max: 6 reboot_required: true GPS_UBX_BAUD2: description: diff --git a/src/lib/adsb/parameters.yaml b/src/lib/adsb/parameters.yaml index 21d41cb071..0ba0d224a8 100644 --- a/src/lib/adsb/parameters.yaml +++ b/src/lib/adsb/parameters.yaml @@ -93,7 +93,7 @@ parameters: default: 14 reboot_required: true min: 0 - max: 15 + max: 19 ADSB_MAX_SPEED: description: short: ADSB-Out Vehicle Max Speed diff --git a/src/modules/commander/commander_params.yaml b/src/modules/commander/commander_params.yaml index f265455db8..0352265131 100644 --- a/src/modules/commander/commander_params.yaml +++ b/src/modules/commander/commander_params.yaml @@ -507,7 +507,7 @@ parameters: 4: Terminate default: 0 min: 0 - max: 3 + max: 4 COM_PARACHUTE: description: short: Require MAVLink parachute system to be present and healthy diff --git a/src/modules/mavlink/mavlink_params.yaml b/src/modules/mavlink/mavlink_params.yaml index 10039647cd..87139d57f8 100644 --- a/src/modules/mavlink/mavlink_params.yaml +++ b/src/modules/mavlink/mavlink_params.yaml @@ -72,7 +72,7 @@ parameters: 23: VTOL Tailsitter default: 0 min: 0 - max: 22 + max: 23 MAV_USEHILGPS: description: short: Use/Accept HIL GPS message even if not in HIL mode diff --git a/src/modules/mc_pos_control/multicopter_autonomous_params.yaml b/src/modules/mc_pos_control/multicopter_autonomous_params.yaml index 49ea2ab8a9..e46f32388d 100644 --- a/src/modules/mc_pos_control/multicopter_autonomous_params.yaml +++ b/src/modules/mc_pos_control/multicopter_autonomous_params.yaml @@ -15,7 +15,7 @@ parameters: 5: yaw fixed default: 0 min: 0 - max: 4 + max: 5 - group: Multicopter Attitude Control definitions: MPC_YAWRAUTO_MAX: