diff --git a/docs/assets/airframes/multicopter/amovlab_f410/amovlabf410_drone_v1.15.4.params b/docs/assets/airframes/multicopter/amovlab_f410/amovlabf410_drone_v1.15.4.params
index 3a27322f74..53b68cdeb4 100644
--- a/docs/assets/airframes/multicopter/amovlab_f410/amovlabf410_drone_v1.15.4.params
+++ b/docs/assets/airframes/multicopter/amovlab_f410/amovlabf410_drone_v1.15.4.params
@@ -803,92 +803,74 @@
1 1 PWM_MAIN_TIM1 400 6
1 1 PWM_MAIN_TIM2 -1 6
1 1 PWM_SBUS_MODE 0 6
-1 1 RC10_DZ 0.000000000000000000 9
1 1 RC10_MAX 2000.000000000000000000 9
1 1 RC10_MIN 1000.000000000000000000 9
1 1 RC10_REV 1.000000000000000000 9
1 1 RC10_TRIM 1500.000000000000000000 9
-1 1 RC11_DZ 0.000000000000000000 9
1 1 RC11_MAX 2000.000000000000000000 9
1 1 RC11_MIN 1000.000000000000000000 9
1 1 RC11_REV 1.000000000000000000 9
1 1 RC11_TRIM 1500.000000000000000000 9
-1 1 RC12_DZ 0.000000000000000000 9
1 1 RC12_MAX 2000.000000000000000000 9
1 1 RC12_MIN 1000.000000000000000000 9
1 1 RC12_REV 1.000000000000000000 9
1 1 RC12_TRIM 1500.000000000000000000 9
-1 1 RC13_DZ 0.000000000000000000 9
1 1 RC13_MAX 2000.000000000000000000 9
1 1 RC13_MIN 1000.000000000000000000 9
1 1 RC13_REV 1.000000000000000000 9
1 1 RC13_TRIM 1500.000000000000000000 9
-1 1 RC14_DZ 0.000000000000000000 9
1 1 RC14_MAX 2000.000000000000000000 9
1 1 RC14_MIN 1000.000000000000000000 9
1 1 RC14_REV 1.000000000000000000 9
1 1 RC14_TRIM 1500.000000000000000000 9
-1 1 RC15_DZ 0.000000000000000000 9
1 1 RC15_MAX 2000.000000000000000000 9
1 1 RC15_MIN 1000.000000000000000000 9
1 1 RC15_REV 1.000000000000000000 9
1 1 RC15_TRIM 1500.000000000000000000 9
-1 1 RC16_DZ 0.000000000000000000 9
1 1 RC16_MAX 2000.000000000000000000 9
1 1 RC16_MIN 1000.000000000000000000 9
1 1 RC16_REV 1.000000000000000000 9
1 1 RC16_TRIM 1500.000000000000000000 9
-1 1 RC17_DZ 0.000000000000000000 9
1 1 RC17_MAX 2000.000000000000000000 9
1 1 RC17_MIN 1000.000000000000000000 9
1 1 RC17_REV 1.000000000000000000 9
1 1 RC17_TRIM 1500.000000000000000000 9
-1 1 RC18_DZ 0.000000000000000000 9
1 1 RC18_MAX 2000.000000000000000000 9
1 1 RC18_MIN 1000.000000000000000000 9
1 1 RC18_REV 1.000000000000000000 9
1 1 RC18_TRIM 1500.000000000000000000 9
-1 1 RC1_DZ 10.000000000000000000 9
1 1 RC1_MAX 1996.000000000000000000 9
1 1 RC1_MIN 999.000000000000000000 9
1 1 RC1_REV 1.000000000000000000 9
1 1 RC1_TRIM 1498.000000000000000000 9
-1 1 RC2_DZ 10.000000000000000000 9
1 1 RC2_MAX 1998.000000000000000000 9
1 1 RC2_MIN 1000.000000000000000000 9
1 1 RC2_REV 1.000000000000000000 9
1 1 RC2_TRIM 1499.000000000000000000 9
-1 1 RC3_DZ 10.000000000000000000 9
1 1 RC3_MAX 1997.000000000000000000 9
1 1 RC3_MIN 1000.000000000000000000 9
1 1 RC3_REV 1.000000000000000000 9
1 1 RC3_TRIM 1000.000000000000000000 9
-1 1 RC4_DZ 10.000000000000000000 9
1 1 RC4_MAX 1997.000000000000000000 9
1 1 RC4_MIN 1000.000000000000000000 9
1 1 RC4_REV 1.000000000000000000 9
1 1 RC4_TRIM 1498.000000000000000000 9
-1 1 RC5_DZ 10.000000000000000000 9
1 1 RC5_MAX 2000.000000000000000000 9
1 1 RC5_MIN 1000.000000000000000000 9
1 1 RC5_REV 1.000000000000000000 9
1 1 RC5_TRIM 1500.000000000000000000 9
-1 1 RC6_DZ 10.000000000000000000 9
1 1 RC6_MAX 2000.000000000000000000 9
1 1 RC6_MIN 1000.000000000000000000 9
1 1 RC6_REV 1.000000000000000000 9
1 1 RC6_TRIM 1500.000000000000000000 9
-1 1 RC7_DZ 10.000000000000000000 9
1 1 RC7_MAX 2000.000000000000000000 9
1 1 RC7_MIN 1000.000000000000000000 9
1 1 RC7_REV 1.000000000000000000 9
1 1 RC7_TRIM 1500.000000000000000000 9
-1 1 RC8_DZ 10.000000000000000000 9
1 1 RC8_MAX 2000.000000000000000000 9
1 1 RC8_MIN 1000.000000000000000000 9
1 1 RC8_REV 1.000000000000000000 9
1 1 RC8_TRIM 1500.000000000000000000 9
-1 1 RC9_DZ 0.000000000000000000 9
1 1 RC9_MAX 2000.000000000000000000 9
1 1 RC9_MIN 1000.000000000000000000 9
1 1 RC9_REV 1.000000000000000000 9
diff --git a/docs/en/flight_modes_mc/altitude.md b/docs/en/flight_modes_mc/altitude.md
index fda7dde9bb..7d35590443 100644
--- a/docs/en/flight_modes_mc/altitude.md
+++ b/docs/en/flight_modes_mc/altitude.md
@@ -47,5 +47,4 @@ The mode is affected by the following parameters:
| ----------------------------------------------------------------------------------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- |
| [MPC_Z_VEL_MAX_UP](../advanced_config/parameter_reference.md#MPC_Z_VEL_MAX_UP) | Maximum vertical ascent velocity. Default: 3 m/s. |
| [MPC_Z_VEL_MAX_DN](../advanced_config/parameter_reference.md#MPC_Z_VEL_MAX_DN) | Maximum vertical descent velocity. Default: 1 m/s. |
-| `RCX_DZ` | RC dead zone for channel X. The value of X for throttle will depend on the value of [RC_MAP_THROTTLE](../advanced_config/parameter_reference.md#RC_MAP_THROTTLE). For example, if the throttle is channel 4 then [RC4_DZ](../advanced_config/parameter_reference.md#RC4_DZ) specifies the deadzone. |
| `MPC_XXXX` | Most of the MPC_xxx parameters affect flight behaviour in this mode (at least to some extent). For example, [MPC_THR_HOVER](../advanced_config/parameter_reference.md#MPC_THR_HOVER) defines the thrust at which a vehicle will hover. |
diff --git a/docs/en/flight_modes_mc/position.md b/docs/en/flight_modes_mc/position.md
index 69367bc4b1..75fae4ab21 100644
--- a/docs/en/flight_modes_mc/position.md
+++ b/docs/en/flight_modes_mc/position.md
@@ -67,7 +67,6 @@ All the parameters in the [Multicopter Position Control](../advanced_config/para
| [MPC_Z_VEL_MAX_DN](../advanced_config/parameter_reference.md#MPC_Z_VEL_MAX_DN) | Maximum vertical descent velocity. Default: 1 m/s. |
| [MPC_LAND_ALT1](../advanced_config/parameter_reference.md#MPC_LAND_ALT1) | Altitude for triggering first phase of slow landing. Below this altitude descending velocity gets limited to a value between [MPC_Z_VEL_MAX_DN](#MPC_Z_VEL_MAX_DN) (or `MPC_Z_V_AUTO_DN`) and [MPC_LAND_SPEED](#MPC_LAND_SPEED). Value needs to be higher than [MPC_LAND_ALT2](#MPC_LAND_ALT2). Default 10m. |
| [MPC_LAND_ALT2](../advanced_config/parameter_reference.md#MPC_LAND_ALT2) | Altitude for second phase of slow landing. Below this altitude descending velocity gets limited to [`MPC_LAND_SPEED`](#MPC_LAND_SPEED). Value needs to be lower than "MPC_LAND_ALT1". Default 5m. |
-| `RCX_DZ` | RC dead zone for channel X. The value of X for throttle will depend on the value of [RC_MAP_THROTTLE](../advanced_config/parameter_reference.md#RC_MAP_THROTTLE). For example, if the throttle is channel 4 then [RC4_DZ](../advanced_config/parameter_reference.md#RC4_DZ) specifies the deadzone. |
| `MPC_XXXX` | Most of the MPC_xxx parameters affect flight behaviour in this mode (at least to some extent). For example, [MPC_THR_HOVER](../advanced_config/parameter_reference.md#MPC_THR_HOVER) defines the thrust at which a vehicle will hover. |
| [MPC_POS_MODE](../advanced_config/parameter_reference.md#MPC_POS_MODE) | Stick input to movement translation strategy. From PX4 v1.12 the default (`Acceleration based`) is that stick position controls acceleration (in a similar way to a car accelerator pedal). Other options allow stick deflection to directly control speed over ground, with and without smoothing and acceleration limits. |
| [MPC_ACC_HOR_MAX](../advanced_config/parameter_reference.md#MPC_ACC_HOR_MAX) | Maximum horizontal acceleration. |
diff --git a/src/modules/commander/HealthAndArmingChecks/checks/rcCalibrationCheck.cpp b/src/modules/commander/HealthAndArmingChecks/checks/rcCalibrationCheck.cpp
index d1008d3253..f16505e4a2 100644
--- a/src/modules/commander/HealthAndArmingChecks/checks/rcCalibrationCheck.cpp
+++ b/src/modules/commander/HealthAndArmingChecks/checks/rcCalibrationCheck.cpp
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (c) 2019 PX4 Development Team. All rights reserved.
+ * Copyright (c) 2025 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -33,11 +33,6 @@
#include "rcCalibrationCheck.hpp"
-/**
- * Maximum deadzone value
- */
-#define RC_INPUT_MAX_DEADZONE_US 500
-
/**
* Minimum value
*/
@@ -61,9 +56,6 @@ RcCalibrationChecks::RcCalibrationChecks()
snprintf(nbuf, sizeof(nbuf), "RC%d_MAX", i + 1);
_param_handles[i].max = param_find(nbuf);
-
- snprintf(nbuf, sizeof(nbuf), "RC%d_DZ", i + 1);
- _param_handles[i].dz = param_find(nbuf);
}
updateParams();
@@ -84,7 +76,6 @@ void RcCalibrationChecks::checkAndReport(const Context &context, Report &reporte
float param_min = _param_values[i].min;
float param_max = _param_values[i].max;
float param_trim = _param_values[i].trim;
- float param_dz = _param_values[i].dz;
/* assert min..center..max ordering */
if (param_min < RC_INPUT_LOWEST_MIN_US) {
@@ -148,22 +139,6 @@ void RcCalibrationChecks::checkAndReport(const Context &context, Report &reporte
(int)param_trim, (int)param_max);
}
}
-
- /* assert deadzone is sane */
- if (param_dz > RC_INPUT_MAX_DEADZONE_US) {
- /* EVENT
- * @description
- * Recalibrate the RC.
- */
- reporter.armingCheckFailure(NavModes::All, health_component_t::remote_control,
- events::ID("check_rc_dz_too_high"),
- events::Log::Error, "RC calibration for channel {1} invalid: DZ greater than {2}", i + 1, RC_INPUT_MAX_DEADZONE_US);
-
- if (reporter.mavlink_log_pub()) {
- mavlink_log_critical(reporter.mavlink_log_pub(), "Preflight Fail: RC ERROR: RC%d_DZ > %u", i + 1,
- RC_INPUT_MAX_DEADZONE_US);
- }
- }
}
}
@@ -176,11 +151,9 @@ void RcCalibrationChecks::updateParams()
_param_values[i].min = 0.0f;
_param_values[i].max = 0.0f;
_param_values[i].trim = 0.0f;
- _param_values[i].dz = RC_INPUT_MAX_DEADZONE_US * 2.0f;
param_get(_param_handles[i].min, &_param_values[i].min);
param_get(_param_handles[i].trim, &_param_values[i].trim);
param_get(_param_handles[i].max, &_param_values[i].max);
- param_get(_param_handles[i].dz, &_param_values[i].dz);
}
}
diff --git a/src/modules/commander/HealthAndArmingChecks/checks/rcCalibrationCheck.hpp b/src/modules/commander/HealthAndArmingChecks/checks/rcCalibrationCheck.hpp
index 6a2d30a83f..d0b4a80d8d 100644
--- a/src/modules/commander/HealthAndArmingChecks/checks/rcCalibrationCheck.hpp
+++ b/src/modules/commander/HealthAndArmingChecks/checks/rcCalibrationCheck.hpp
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (c) 2022 PX4 Development Team. All rights reserved.
+ * Copyright (c) 2025 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -53,13 +53,11 @@ private:
param_t min;
param_t trim;
param_t max;
- param_t dz;
};
struct ParamValues {
float min;
float trim;
float max;
- float dz;
};
ParamHandles _param_handles[input_rc_s::RC_INPUT_MAX_CHANNELS];
diff --git a/src/modules/rc_update/params.c b/src/modules/rc_update/params.c
index d764ae5d34..3709a3a841 100644
--- a/src/modules/rc_update/params.c
+++ b/src/modules/rc_update/params.c
@@ -87,18 +87,6 @@ PARAM_DEFINE_FLOAT(RC1_MAX, 2000.0f);
*/
PARAM_DEFINE_FLOAT(RC1_REV, 1.0f);
-/**
- * RC channel 1 dead zone
- *
- * The +- range of this value around the trim value will be considered as zero.
- *
- * @min 0.0
- * @max 100.0
- * @unit us
- * @group Radio Calibration
- */
-PARAM_DEFINE_FLOAT(RC1_DZ, 10.0f);
-
/**
* RC channel 2 minimum
*
@@ -148,18 +136,6 @@ PARAM_DEFINE_FLOAT(RC2_MAX, 2000.0f);
*/
PARAM_DEFINE_FLOAT(RC2_REV, 1.0f);
-/**
- * RC channel 2 dead zone
- *
- * The +- range of this value around the trim value will be considered as zero.
- *
- * @min 0.0
- * @max 100.0
- * @unit us
- * @group Radio Calibration
- */
-PARAM_DEFINE_FLOAT(RC2_DZ, 10.0f);
-
/**
* RC channel 3 minimum
*
@@ -209,18 +185,6 @@ PARAM_DEFINE_FLOAT(RC3_MAX, 2000);
*/
PARAM_DEFINE_FLOAT(RC3_REV, 1.0f);
-/**
- * RC channel 3 dead zone
- *
- * The +- range of this value around the trim value will be considered as zero.
- *
- * @min 0.0
- * @max 100.0
- * @unit us
- * @group Radio Calibration
- */
-PARAM_DEFINE_FLOAT(RC3_DZ, 10.0f);
-
/**
* RC channel 4 minimum
*
@@ -270,18 +234,6 @@ PARAM_DEFINE_FLOAT(RC4_MAX, 2000);
*/
PARAM_DEFINE_FLOAT(RC4_REV, 1.0f);
-/**
- * RC channel 4 dead zone
- *
- * The +- range of this value around the trim value will be considered as zero.
- *
- * @min 0.0
- * @max 100.0
- * @unit us
- * @group Radio Calibration
- */
-PARAM_DEFINE_FLOAT(RC4_DZ, 10.0f);
-
/**
* RC channel 5 minimum
*
@@ -331,17 +283,6 @@ PARAM_DEFINE_FLOAT(RC5_MAX, 2000);
*/
PARAM_DEFINE_FLOAT(RC5_REV, 1.0f);
-/**
- * RC channel 5 dead zone
- *
- * The +- range of this value around the trim value will be considered as zero.
- *
- * @min 0.0
- * @max 100.0
- * @group Radio Calibration
- */
-PARAM_DEFINE_FLOAT(RC5_DZ, 10.0f);
-
/**
* RC channel 6 minimum
*
@@ -391,17 +332,6 @@ PARAM_DEFINE_FLOAT(RC6_MAX, 2000);
*/
PARAM_DEFINE_FLOAT(RC6_REV, 1.0f);
-/**
- * RC channel 6 dead zone
- *
- * The +- range of this value around the trim value will be considered as zero.
- *
- * @min 0.0
- * @max 100.0
- * @group Radio Calibration
- */
-PARAM_DEFINE_FLOAT(RC6_DZ, 10.0f);
-
/**
* RC channel 7 minimum
*
@@ -451,17 +381,6 @@ PARAM_DEFINE_FLOAT(RC7_MAX, 2000);
*/
PARAM_DEFINE_FLOAT(RC7_REV, 1.0f);
-/**
- * RC channel 7 dead zone
- *
- * The +- range of this value around the trim value will be considered as zero.
- *
- * @min 0.0
- * @max 100.0
- * @group Radio Calibration
- */
-PARAM_DEFINE_FLOAT(RC7_DZ, 10.0f);
-
/**
* RC channel 8 minimum
*
@@ -511,17 +430,6 @@ PARAM_DEFINE_FLOAT(RC8_MAX, 2000);
*/
PARAM_DEFINE_FLOAT(RC8_REV, 1.0f);
-/**
- * RC channel 8 dead zone
- *
- * The +- range of this value around the trim value will be considered as zero.
- *
- * @min 0.0
- * @max 100.0
- * @group Radio Calibration
- */
-PARAM_DEFINE_FLOAT(RC8_DZ, 10.0f);
-
/**
* RC channel 9 minimum
*
@@ -571,17 +479,6 @@ PARAM_DEFINE_FLOAT(RC9_MAX, 2000);
*/
PARAM_DEFINE_FLOAT(RC9_REV, 1.0f);
-/**
- * RC channel 9 dead zone
- *
- * The +- range of this value around the trim value will be considered as zero.
- *
- * @min 0.0
- * @max 100.0
- * @group Radio Calibration
- */
-PARAM_DEFINE_FLOAT(RC9_DZ, 0.0f);
-
/**
* RC channel 10 minimum
*
@@ -631,17 +528,6 @@ PARAM_DEFINE_FLOAT(RC10_MAX, 2000);
*/
PARAM_DEFINE_FLOAT(RC10_REV, 1.0f);
-/**
- * RC channel 10 dead zone
- *
- * The +- range of this value around the trim value will be considered as zero.
- *
- * @min 0.0
- * @max 100.0
- * @group Radio Calibration
- */
-PARAM_DEFINE_FLOAT(RC10_DZ, 0.0f);
-
/**
* RC channel 11 minimum
*
@@ -691,17 +577,6 @@ PARAM_DEFINE_FLOAT(RC11_MAX, 2000);
*/
PARAM_DEFINE_FLOAT(RC11_REV, 1.0f);
-/**
- * RC channel 11 dead zone
- *
- * The +- range of this value around the trim value will be considered as zero.
- *
- * @min 0.0
- * @max 100.0
- * @group Radio Calibration
- */
-PARAM_DEFINE_FLOAT(RC11_DZ, 0.0f);
-
/**
* RC channel 12 minimum
*
@@ -751,17 +626,6 @@ PARAM_DEFINE_FLOAT(RC12_MAX, 2000);
*/
PARAM_DEFINE_FLOAT(RC12_REV, 1.0f);
-/**
- * RC channel 12 dead zone
- *
- * The +- range of this value around the trim value will be considered as zero.
- *
- * @min 0.0
- * @max 100.0
- * @group Radio Calibration
- */
-PARAM_DEFINE_FLOAT(RC12_DZ, 0.0f);
-
/**
* RC channel 13 minimum
*
@@ -811,17 +675,6 @@ PARAM_DEFINE_FLOAT(RC13_MAX, 2000);
*/
PARAM_DEFINE_FLOAT(RC13_REV, 1.0f);
-/**
- * RC channel 13 dead zone
- *
- * The +- range of this value around the trim value will be considered as zero.
- *
- * @min 0.0
- * @max 100.0
- * @group Radio Calibration
- */
-PARAM_DEFINE_FLOAT(RC13_DZ, 0.0f);
-
/**
* RC channel 14 minimum
*
@@ -871,17 +724,6 @@ PARAM_DEFINE_FLOAT(RC14_MAX, 2000);
*/
PARAM_DEFINE_FLOAT(RC14_REV, 1.0f);
-/**
- * RC channel 14 dead zone
- *
- * The +- range of this value around the trim value will be considered as zero.
- *
- * @min 0.0
- * @max 100.0
- * @group Radio Calibration
- */
-PARAM_DEFINE_FLOAT(RC14_DZ, 0.0f);
-
/**
* RC channel 15 minimum
*
@@ -931,17 +773,6 @@ PARAM_DEFINE_FLOAT(RC15_MAX, 2000);
*/
PARAM_DEFINE_FLOAT(RC15_REV, 1.0f);
-/**
- * RC channel 15 dead zone
- *
- * The +- range of this value around the trim value will be considered as zero.
- *
- * @min 0.0
- * @max 100.0
- * @group Radio Calibration
- */
-PARAM_DEFINE_FLOAT(RC15_DZ, 0.0f);
-
/**
* RC channel 16 minimum
*
@@ -991,17 +822,6 @@ PARAM_DEFINE_FLOAT(RC16_MAX, 2000);
*/
PARAM_DEFINE_FLOAT(RC16_REV, 1.0f);
-/**
- * RC channel 16 dead zone
- *
- * The +- range of this value around the trim value will be considered as zero.
- *
- * @min 0.0
- * @max 100.0
- * @group Radio Calibration
- */
-PARAM_DEFINE_FLOAT(RC16_DZ, 0.0f);
-
/**
* RC channel 17 minimum
*
@@ -1051,17 +871,6 @@ PARAM_DEFINE_FLOAT(RC17_MAX, 2000);
*/
PARAM_DEFINE_FLOAT(RC17_REV, 1.0f);
-/**
- * RC channel 17 dead zone
- *
- * The +- range of this value around the trim value will be considered as zero.
- *
- * @min 0.0
- * @max 100.0
- * @group Radio Calibration
- */
-PARAM_DEFINE_FLOAT(RC17_DZ, 0.0f);
-
/**
* RC channel 18 minimum
*
@@ -1111,17 +920,6 @@ PARAM_DEFINE_FLOAT(RC18_MAX, 2000);
*/
PARAM_DEFINE_FLOAT(RC18_REV, 1.0f);
-/**
- * RC channel 18 dead zone
- *
- * The +- range of this value around the trim value will be considered as zero.
- *
- * @min 0.0
- * @max 100.0
- * @group Radio Calibration
- */
-PARAM_DEFINE_FLOAT(RC18_DZ, 0.0f);
-
/**
* RC channel count
*
diff --git a/src/modules/rc_update/rc_update.cpp b/src/modules/rc_update/rc_update.cpp
index 7c8960a357..52d65bf915 100644
--- a/src/modules/rc_update/rc_update.cpp
+++ b/src/modules/rc_update/rc_update.cpp
@@ -87,10 +87,6 @@ RCUpdate::RCUpdate() :
/* channel reverse */
snprintf(nbuf, sizeof(nbuf), "RC%d_REV", i + 1);
_parameter_handles.rev[i] = param_find(nbuf);
-
- /* channel deadzone */
- snprintf(nbuf, sizeof(nbuf), "RC%d_DZ", i + 1);
- _parameter_handles.dz[i] = param_find(nbuf);
}
// RC to parameter mapping for changing parameters with RC
@@ -145,10 +141,6 @@ void RCUpdate::updateParams()
float rev = 0.f;
param_get(_parameter_handles.rev[i], &rev);
_parameters.rev[i] = (rev < 0.f);
-
- float dz = 0.f;
- param_get(_parameter_handles.dz[i], &dz);
- _parameters.dz[i] = dz;
}
for (int i = 0; i < rc_parameter_map_s::RC_PARAM_MAP_NCHAN; i++) {
@@ -449,12 +441,9 @@ void RCUpdate::Run()
const float min = _parameters.min[i];
const float trim = _parameters.trim[i];
const float max = _parameters.max[i];
- const float dz = _parameters.dz[i];
// piecewise linear function to apply RC calibration
- _rc.channels[i] = math::interpolateNXY(value,
- {min, trim - dz, trim + dz, max},
- {-1.f, 0.f, 0.f, 1.f});
+ _rc.channels[i] = math::interpolateNXY(value, {min, trim, max}, {-1.f, 0.f, 1.f});
if (_parameters.rev[i]) {
_rc.channels[i] = -_rc.channels[i];
@@ -725,11 +714,11 @@ int RCUpdate::print_status()
PX4_INFO_RAW("Running\n");
if (_channel_count_max > 0) {
- PX4_INFO_RAW(" # MIN MAX TRIM DZ REV\n");
+ PX4_INFO_RAW(" # MIN MAX TRIM REV\n");
for (int i = 0; i < _channel_count_max; i++) {
- PX4_INFO_RAW("%2d %4d %4d %4d %3d %3d\n", i, _parameters.min[i], _parameters.max[i], _parameters.trim[i],
- _parameters.dz[i], _parameters.rev[i]);
+ PX4_INFO_RAW("%2d %4d %4d %4d %3d\n",
+ i, _parameters.min[i], _parameters.max[i], _parameters.trim[i], _parameters.rev[i]);
}
}
diff --git a/src/modules/rc_update/rc_update.h b/src/modules/rc_update/rc_update.h
index 812408debe..2ebdebb4c0 100644
--- a/src/modules/rc_update/rc_update.h
+++ b/src/modules/rc_update/rc_update.h
@@ -148,7 +148,6 @@ protected:
uint16_t min[RC_MAX_CHAN_COUNT];
uint16_t trim[RC_MAX_CHAN_COUNT];
uint16_t max[RC_MAX_CHAN_COUNT];
- uint16_t dz[RC_MAX_CHAN_COUNT];
bool rev[RC_MAX_CHAN_COUNT];
int32_t rc_map_param[rc_parameter_map_s::RC_PARAM_MAP_NCHAN];
@@ -159,7 +158,6 @@ protected:
param_t trim[RC_MAX_CHAN_COUNT];
param_t max[RC_MAX_CHAN_COUNT];
param_t rev[RC_MAX_CHAN_COUNT];
- param_t dz[RC_MAX_CHAN_COUNT];
param_t rc_map_param[rc_parameter_map_s::RC_PARAM_MAP_NCHAN];
param_t rc_param[rc_parameter_map_s::RC_PARAM_MAP_NCHAN]; /**< param handles for the parameters which are bound