From 20d735701f6c4806d246e4d8fd75758f698b40bb Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Fri, 12 Jun 2015 10:40:12 +0200 Subject: [PATCH] sensor params: Add hint to reboot system after changing PWM params --- src/modules/sensors/sensor_params.c | 24 ++++++++++++++++++++++++ 1 file changed, 24 insertions(+) diff --git a/src/modules/sensors/sensor_params.c b/src/modules/sensors/sensor_params.c index 83568c0069..72d139b113 100644 --- a/src/modules/sensors/sensor_params.c +++ b/src/modules/sensors/sensor_params.c @@ -1414,6 +1414,10 @@ PARAM_DEFINE_INT32(SENS_EN_LL40LS, 0); /** * Set the minimum PWM for the MAIN outputs * + * IMPORTANT: CHANGING THIS PARAMETER REQUIRES A COMPLETE SYSTEM + * REBOOT IN ORDER TO APPLY THE CHANGES. COMPLETELY POWER-CYCLE + * THE SYSTEM TO PUT CHANGES INTO EFFECT. + * * Set to 1000 for default or 900 to increase servo travel * * @min 800 @@ -1426,6 +1430,10 @@ PARAM_DEFINE_INT32(PWM_MIN, 1000); /** * Set the maximum PWM for the MAIN outputs * + * IMPORTANT: CHANGING THIS PARAMETER REQUIRES A COMPLETE SYSTEM + * REBOOT IN ORDER TO APPLY THE CHANGES. COMPLETELY POWER-CYCLE + * THE SYSTEM TO PUT CHANGES INTO EFFECT. + * * Set to 2000 for default or 2100 to increase servo travel * * @min 1600 @@ -1438,6 +1446,10 @@ PARAM_DEFINE_INT32(PWM_MAX, 2000); /** * Set the disarmed PWM for MAIN outputs * + * IMPORTANT: CHANGING THIS PARAMETER REQUIRES A COMPLETE SYSTEM + * REBOOT IN ORDER TO APPLY THE CHANGES. COMPLETELY POWER-CYCLE + * THE SYSTEM TO PUT CHANGES INTO EFFECT. + * * This is the PWM pulse the autopilot is outputting if not armed. * The main use of this parameter is to silence ESCs when they are disarmed. * @@ -1451,6 +1463,10 @@ PARAM_DEFINE_INT32(PWM_DISARMED, 0); /** * Set the minimum PWM for the MAIN outputs * + * IMPORTANT: CHANGING THIS PARAMETER REQUIRES A COMPLETE SYSTEM + * REBOOT IN ORDER TO APPLY THE CHANGES. COMPLETELY POWER-CYCLE + * THE SYSTEM TO PUT CHANGES INTO EFFECT. + * * Set to 1000 for default or 900 to increase servo travel * * @min 800 @@ -1463,6 +1479,10 @@ PARAM_DEFINE_INT32(PWM_AUX_MIN, 1000); /** * Set the maximum PWM for the MAIN outputs * + * IMPORTANT: CHANGING THIS PARAMETER REQUIRES A COMPLETE SYSTEM + * REBOOT IN ORDER TO APPLY THE CHANGES. COMPLETELY POWER-CYCLE + * THE SYSTEM TO PUT CHANGES INTO EFFECT. + * * Set to 2000 for default or 2100 to increase servo travel * * @min 1600 @@ -1475,6 +1495,10 @@ PARAM_DEFINE_INT32(PWM_AUX_MAX, 2000); /** * Set the disarmed PWM for AUX outputs * + * IMPORTANT: CHANGING THIS PARAMETER REQUIRES A COMPLETE SYSTEM + * REBOOT IN ORDER TO APPLY THE CHANGES. COMPLETELY POWER-CYCLE + * THE SYSTEM TO PUT CHANGES INTO EFFECT. + * * This is the PWM pulse the autopilot is outputting if not armed. * The main use of this parameter is to silence ESCs when they are disarmed. *