forked from Archive/PX4-Autopilot
PWM parameters centralize under sensors and add aux 7&8
This commit is contained in:
parent
ab2d595224
commit
805dfc4312
|
@ -31,138 +31,6 @@
|
|||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* Invert direction of aux output channel 1
|
||||
*
|
||||
* Enable to invert the channel.
|
||||
*
|
||||
* @boolean
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_INT32(PWM_AUX_REV1, 0);
|
||||
|
||||
/**
|
||||
* Invert direction of aux output channel 2
|
||||
*
|
||||
* Enable to invert the channel.
|
||||
*
|
||||
* @boolean
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_INT32(PWM_AUX_REV2, 0);
|
||||
|
||||
/**
|
||||
* Invert direction of aux output channel 3
|
||||
*
|
||||
* Enable to invert the channel.
|
||||
*
|
||||
* @boolean
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_INT32(PWM_AUX_REV3, 0);
|
||||
|
||||
/**
|
||||
* Invert direction of aux output channel 4
|
||||
*
|
||||
* Enable to invert the channel.
|
||||
*
|
||||
* @boolean
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_INT32(PWM_AUX_REV4, 0);
|
||||
|
||||
/**
|
||||
* Invert direction of aux output channel 5
|
||||
*
|
||||
* Enable to invert the channel.
|
||||
*
|
||||
* @boolean
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_INT32(PWM_AUX_REV5, 0);
|
||||
|
||||
/**
|
||||
* Invert direction of aux output channel 6
|
||||
*
|
||||
* Enable to invert the channel.
|
||||
*
|
||||
* @boolean
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_INT32(PWM_AUX_REV6, 0);
|
||||
|
||||
/**
|
||||
* Trim value for FMU PWM output channel 1
|
||||
*
|
||||
* Set to normalized offset
|
||||
*
|
||||
* @min -0.2
|
||||
* @max 0.2
|
||||
* @decimal 2
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(PWM_AUX_TRIM1, 0);
|
||||
|
||||
/**
|
||||
* Trim value for FMU PWM output channel 2
|
||||
*
|
||||
* Set to normalized offset
|
||||
*
|
||||
* @min -0.2
|
||||
* @max 0.2
|
||||
* @decimal 2
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(PWM_AUX_TRIM2, 0);
|
||||
|
||||
/**
|
||||
* Trim value for FMU PWM output channel 3
|
||||
*
|
||||
* Set to normalized offset
|
||||
*
|
||||
* @min -0.2
|
||||
* @max 0.2
|
||||
* @decimal 2
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(PWM_AUX_TRIM3, 0);
|
||||
|
||||
/**
|
||||
* Trim value for FMU PWM output channel 4
|
||||
*
|
||||
* Set to normalized offset
|
||||
*
|
||||
* @min -0.2
|
||||
* @max 0.2
|
||||
* @decimal 2
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(PWM_AUX_TRIM4, 0);
|
||||
|
||||
/**
|
||||
* Trim value for FMU PWM output channel 5
|
||||
*
|
||||
* Set to normalized offset
|
||||
*
|
||||
* @min -0.2
|
||||
* @max 0.2
|
||||
* @decimal 2
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(PWM_AUX_TRIM5, 0);
|
||||
|
||||
/**
|
||||
* Trim value for FMU PWM output channel 6
|
||||
*
|
||||
* Set to normalized offset
|
||||
*
|
||||
* @min -0.2
|
||||
* @max 0.2
|
||||
* @decimal 2
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(PWM_AUX_TRIM6, 0);
|
||||
|
||||
/**
|
||||
* Thrust to PWM model parameter
|
||||
*
|
||||
|
|
|
@ -55,182 +55,6 @@
|
|||
*/
|
||||
PARAM_DEFINE_INT32(SYS_USE_IO, 1);
|
||||
|
||||
/**
|
||||
* Invert direction of main output channel 1
|
||||
*
|
||||
* Enable to invert the channel.
|
||||
*
|
||||
* @boolean
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_INT32(PWM_MAIN_REV1, 0);
|
||||
|
||||
/**
|
||||
* Invert direction of main output channel 2
|
||||
*
|
||||
* Enable to invert the channel.
|
||||
*
|
||||
* @boolean
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_INT32(PWM_MAIN_REV2, 0);
|
||||
|
||||
/**
|
||||
* Invert direction of main output channel 3
|
||||
*
|
||||
* Enable to invert the channel.
|
||||
*
|
||||
* @boolean
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_INT32(PWM_MAIN_REV3, 0);
|
||||
|
||||
/**
|
||||
* Invert direction of main output channel 4
|
||||
*
|
||||
* Enable to invert the channel.
|
||||
*
|
||||
* @boolean
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_INT32(PWM_MAIN_REV4, 0);
|
||||
|
||||
/**
|
||||
* Invert direction of main output channel 5
|
||||
*
|
||||
* Enable to invert the channel.
|
||||
*
|
||||
* @boolean
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_INT32(PWM_MAIN_REV5, 0);
|
||||
|
||||
/**
|
||||
* Invert direction of main output channel 6
|
||||
*
|
||||
* Enable to invert the channel.
|
||||
*
|
||||
* @boolean
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_INT32(PWM_MAIN_REV6, 0);
|
||||
|
||||
/**
|
||||
* Invert direction of main output channel 7
|
||||
*
|
||||
* Enable to invert the channel.
|
||||
*
|
||||
* @boolean
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_INT32(PWM_MAIN_REV7, 0);
|
||||
|
||||
/**
|
||||
* Invert direction of main output channel 8
|
||||
*
|
||||
* Enable to invert the channel.
|
||||
*
|
||||
* @boolean
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_INT32(PWM_MAIN_REV8, 0);
|
||||
|
||||
/**
|
||||
* Trim value for main output channel 1
|
||||
*
|
||||
* Set to normalized offset
|
||||
*
|
||||
* @min -0.2
|
||||
* @max 0.2
|
||||
* @decimal 2
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(PWM_MAIN_TRIM1, 0);
|
||||
|
||||
/**
|
||||
* Trim value for main output channel 2
|
||||
*
|
||||
* Set to normalized offset
|
||||
*
|
||||
* @min -0.2
|
||||
* @max 0.2
|
||||
* @decimal 2
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(PWM_MAIN_TRIM2, 0);
|
||||
|
||||
/**
|
||||
* Trim value for main output channel 3
|
||||
*
|
||||
* Set to normalized offset
|
||||
*
|
||||
* @min -0.2
|
||||
* @max 0.2
|
||||
* @decimal 2
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(PWM_MAIN_TRIM3, 0);
|
||||
|
||||
/**
|
||||
* Trim value for main output channel 4
|
||||
*
|
||||
* Set to normalized offset
|
||||
*
|
||||
* @min -0.2
|
||||
* @max 0.2
|
||||
* @decimal 2
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(PWM_MAIN_TRIM4, 0);
|
||||
|
||||
/**
|
||||
* Trim value for main output channel 5
|
||||
*
|
||||
* Set to normalized offset
|
||||
*
|
||||
* @min -0.2
|
||||
* @max 0.2
|
||||
* @decimal 2
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(PWM_MAIN_TRIM5, 0);
|
||||
|
||||
/**
|
||||
* Trim value for main output channel 6
|
||||
*
|
||||
* Set to normalized offset
|
||||
*
|
||||
* @min -0.2
|
||||
* @max 0.2
|
||||
* @decimal 2
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(PWM_MAIN_TRIM6, 0);
|
||||
|
||||
/**
|
||||
* Trim value for main output channel 7
|
||||
*
|
||||
* Set to normalized offset
|
||||
*
|
||||
* @min -0.2
|
||||
* @max 0.2
|
||||
* @decimal 2
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(PWM_MAIN_TRIM7, 0);
|
||||
|
||||
/**
|
||||
* Trim value for main output channel 8
|
||||
*
|
||||
* Set to normalized offset
|
||||
*
|
||||
* @min -0.2
|
||||
* @max 0.2
|
||||
* @decimal 2
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(PWM_MAIN_TRIM8, 0);
|
||||
|
||||
/**
|
||||
* S.BUS out
|
||||
*
|
||||
|
|
|
@ -0,0 +1,406 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2012-2016 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
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file pwm_params_aux.c
|
||||
*
|
||||
* Parameters defined for PWM output.
|
||||
*
|
||||
*/
|
||||
|
||||
/**
|
||||
* Set the PWM output frequency for the auxiliary outputs
|
||||
*
|
||||
* Set to 400 for industry default or 1000 for high frequency ESCs.
|
||||
*
|
||||
* Set to 0 for Oneshot125.
|
||||
*
|
||||
* @reboot_required true
|
||||
*
|
||||
* @min -1
|
||||
* @max 2000
|
||||
* @unit Hz
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_INT32(PWM_AUX_RATE, 50);
|
||||
|
||||
/**
|
||||
* Set the minimum PWM for the auxiliary outputs
|
||||
*
|
||||
* Set to 1000 for industry default or 900 to increase servo travel.
|
||||
*
|
||||
* @reboot_required true
|
||||
*
|
||||
* @min 800
|
||||
* @max 1400
|
||||
* @unit us
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_INT32(PWM_AUX_MIN, 1000);
|
||||
|
||||
/**
|
||||
* Set the maximum PWM for the auxiliary outputs
|
||||
*
|
||||
* Set to 2000 for industry default or 2100 to increase servo travel.
|
||||
*
|
||||
* @reboot_required true
|
||||
*
|
||||
* @min 1600
|
||||
* @max 2200
|
||||
* @unit us
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_INT32(PWM_AUX_MAX, 2000);
|
||||
|
||||
/**
|
||||
* Set the disarmed PWM for auxiliary outputs
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
* @reboot_required true
|
||||
*
|
||||
* @min 0
|
||||
* @max 2200
|
||||
* @unit us
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_INT32(PWM_AUX_DISARMED, 1500);
|
||||
|
||||
|
||||
|
||||
|
||||
/**
|
||||
* Set the disarmed PWM for the auxiliary 1 output
|
||||
*
|
||||
* This is the PWM pulse the autopilot is outputting if not armed.
|
||||
* When set to -1 the value for PWM_AUX_DISARMED will be used
|
||||
*
|
||||
* @reboot_required true
|
||||
*
|
||||
* @min -1
|
||||
* @max 2200
|
||||
* @unit us
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_INT32(PWM_AUX_DIS1, -1);
|
||||
|
||||
/**
|
||||
* Set the disarmed PWM for the auxiliary 2 output
|
||||
*
|
||||
* This is the PWM pulse the autopilot is outputting if not armed.
|
||||
* When set to -1 the value for PWM_AUX_DISARMED will be used
|
||||
*
|
||||
* @reboot_required true
|
||||
*
|
||||
* @min -1
|
||||
* @max 2200
|
||||
* @unit us
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_INT32(PWM_AUX_DIS2, -1);
|
||||
|
||||
/**
|
||||
* Set the disarmed PWM for the auxiliary 3 output
|
||||
*
|
||||
* This is the PWM pulse the autopilot is outputting if not armed.
|
||||
* When set to -1 the value for PWM_AUX_DISARMED will be used
|
||||
*
|
||||
* @reboot_required true
|
||||
*
|
||||
* @min -1
|
||||
* @max 2200
|
||||
* @unit us
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_INT32(PWM_AUX_DIS3, -1);
|
||||
|
||||
/**
|
||||
* Set the disarmed PWM for the auxiliary 4 output
|
||||
*
|
||||
* This is the PWM pulse the autopilot is outputting if not armed.
|
||||
* When set to -1 the value for PWM_AUX_DISARMED will be used
|
||||
*
|
||||
* @reboot_required true
|
||||
*
|
||||
* @min -1
|
||||
* @max 2200
|
||||
* @unit us
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_INT32(PWM_AUX_DIS4, -1);
|
||||
|
||||
/**
|
||||
* Set the disarmed PWM for the auxiliary 5 output
|
||||
*
|
||||
* This is the PWM pulse the autopilot is outputting if not armed.
|
||||
* When set to -1 the value for PWM_AUX_DISARMED will be used
|
||||
*
|
||||
* @reboot_required true
|
||||
*
|
||||
* @min -1
|
||||
* @max 2200
|
||||
* @unit us
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_INT32(PWM_AUX_DIS5, -1);
|
||||
|
||||
/**
|
||||
* Set the disarmed PWM for the auxiliary 6 output
|
||||
*
|
||||
* This is the PWM pulse the autopilot is outputting if not armed.
|
||||
* When set to -1 the value for PWM_AUX_DISARMED will be used
|
||||
*
|
||||
* @reboot_required true
|
||||
*
|
||||
* @min -1
|
||||
* @max 2200
|
||||
* @unit us
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_INT32(PWM_AUX_DIS6, -1);
|
||||
|
||||
/**
|
||||
* Set the disarmed PWM for the auxiliary 7 output
|
||||
*
|
||||
* This is the PWM pulse the autopilot is outputting if not armed.
|
||||
* When set to -1 the value for PWM_AUX_DISARMED will be used
|
||||
*
|
||||
* @reboot_required true
|
||||
*
|
||||
* @min -1
|
||||
* @max 2200
|
||||
* @unit us
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_INT32(PWM_AUX_DIS7, -1);
|
||||
|
||||
/**
|
||||
* Set the disarmed PWM for the auxiliary 8 output
|
||||
*
|
||||
* This is the PWM pulse the autopilot is outputting if not armed.
|
||||
* When set to -1 the value for PWM_AUX_DISARMED will be used
|
||||
*
|
||||
* @reboot_required true
|
||||
*
|
||||
* @min -1
|
||||
* @max 2200
|
||||
* @unit us
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_INT32(PWM_AUX_DIS8, -1);
|
||||
|
||||
|
||||
|
||||
|
||||
/**
|
||||
* Invert direction of auxiliary output channel 1
|
||||
*
|
||||
* Enable to invert the channel.
|
||||
*
|
||||
* @boolean
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_INT32(PWM_AUX_REV1, 0);
|
||||
|
||||
/**
|
||||
* Invert direction of auxiliary output channel 2
|
||||
*
|
||||
* Enable to invert the channel.
|
||||
*
|
||||
* @boolean
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_INT32(PWM_AUX_REV2, 0);
|
||||
|
||||
/**
|
||||
* Invert direction of auxiliary output channel 3
|
||||
*
|
||||
* Enable to invert the channel.
|
||||
*
|
||||
* @boolean
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_INT32(PWM_AUX_REV3, 0);
|
||||
|
||||
/**
|
||||
* Invert direction of auxiliary output channel 4
|
||||
*
|
||||
* Enable to invert the channel.
|
||||
*
|
||||
* @boolean
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_INT32(PWM_AUX_REV4, 0);
|
||||
|
||||
/**
|
||||
* Invert direction of auxiliary output channel 5
|
||||
*
|
||||
* Enable to invert the channel.
|
||||
*
|
||||
* @boolean
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_INT32(PWM_AUX_REV5, 0);
|
||||
|
||||
/**
|
||||
* Invert direction of auxiliary output channel 6
|
||||
*
|
||||
* Enable to invert the channel.
|
||||
*
|
||||
* @boolean
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_INT32(PWM_AUX_REV6, 0);
|
||||
|
||||
/**
|
||||
* Invert direction of auxiliary output channel 7
|
||||
*
|
||||
* Enable to invert the channel.
|
||||
*
|
||||
* @boolean
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_INT32(PWM_AUX_REV7, 0);
|
||||
|
||||
/**
|
||||
* Invert direction of auxiliary output channel 8
|
||||
*
|
||||
* Enable to invert the channel.
|
||||
*
|
||||
* @boolean
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_INT32(PWM_AUX_REV8, 0);
|
||||
|
||||
|
||||
|
||||
|
||||
/**
|
||||
* Trim value for auxiliary output channel 1
|
||||
*
|
||||
* Set to normalized offset
|
||||
*
|
||||
* @min -0.2
|
||||
* @max 0.2
|
||||
* @decimal 2
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(PWM_AUX_TRIM1, 0);
|
||||
|
||||
/**
|
||||
* Trim value for auxiliary output channel 2
|
||||
*
|
||||
* Set to normalized offset
|
||||
*
|
||||
* @min -0.2
|
||||
* @max 0.2
|
||||
* @decimal 2
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(PWM_AUX_TRIM2, 0);
|
||||
|
||||
/**
|
||||
* Trim value for auxiliary output channel 3
|
||||
*
|
||||
* Set to normalized offset
|
||||
*
|
||||
* @min -0.2
|
||||
* @max 0.2
|
||||
* @decimal 2
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(PWM_AUX_TRIM3, 0);
|
||||
|
||||
/**
|
||||
* Trim value for auxiliary output channel 4
|
||||
*
|
||||
* Set to normalized offset
|
||||
*
|
||||
* @min -0.2
|
||||
* @max 0.2
|
||||
* @decimal 2
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(PWM_AUX_TRIM4, 0);
|
||||
|
||||
/**
|
||||
* Trim value for auxiliary output channel 5
|
||||
*
|
||||
* Set to normalized offset
|
||||
*
|
||||
* @min -0.2
|
||||
* @max 0.2
|
||||
* @decimal 2
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(PWM_AUX_TRIM5, 0);
|
||||
|
||||
/**
|
||||
* Trim value for auxiliary output channel 6
|
||||
*
|
||||
* Set to normalized offset
|
||||
*
|
||||
* @min -0.2
|
||||
* @max 0.2
|
||||
* @decimal 2
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(PWM_AUX_TRIM6, 0);
|
||||
|
||||
/**
|
||||
* Trim value for auxiliary output channel 7
|
||||
*
|
||||
* Set to normalized offset
|
||||
*
|
||||
* @min -0.2
|
||||
* @max 0.2
|
||||
* @decimal 2
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(PWM_AUX_TRIM7, 0);
|
||||
|
||||
/**
|
||||
* Trim value for auxiliary output channel 8
|
||||
*
|
||||
* Set to normalized offset
|
||||
*
|
||||
* @min -0.2
|
||||
* @max 0.2
|
||||
* @decimal 2
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(PWM_AUX_TRIM8, 0);
|
||||
|
||||
|
||||
|
|
@ -32,7 +32,7 @@
|
|||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file pwm_params.c
|
||||
* @file pwm_params_main.c
|
||||
*
|
||||
* Parameters defined for PWM output.
|
||||
*
|
||||
|
@ -97,6 +97,9 @@ PARAM_DEFINE_INT32(PWM_MAX, 2000);
|
|||
*/
|
||||
PARAM_DEFINE_INT32(PWM_DISARMED, 900);
|
||||
|
||||
|
||||
|
||||
|
||||
/**
|
||||
* Set the disarmed PWM for the main 1 output
|
||||
*
|
||||
|
@ -217,135 +220,187 @@ PARAM_DEFINE_INT32(PWM_MAIN_DIS7, -1);
|
|||
*/
|
||||
PARAM_DEFINE_INT32(PWM_MAIN_DIS8, -1);
|
||||
|
||||
/**
|
||||
* Set the disarmed PWM for the AUX 1 output
|
||||
*
|
||||
* This is the PWM pulse the autopilot is outputting if not armed.
|
||||
* When set to -1 the value for PWM_AUX_DISARMED will be used
|
||||
*
|
||||
* @reboot_required true
|
||||
*
|
||||
* @min -1
|
||||
* @max 2200
|
||||
* @unit us
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_INT32(PWM_AUX_DIS1, -1);
|
||||
|
||||
|
||||
|
||||
/**
|
||||
* Set the disarmed PWM for the AUX 2 output
|
||||
* Invert direction of main output channel 1
|
||||
*
|
||||
* This is the PWM pulse the autopilot is outputting if not armed.
|
||||
* When set to -1 the value for PWM_AUX_DISARMED will be used
|
||||
* Enable to invert the channel.
|
||||
*
|
||||
* @reboot_required true
|
||||
*
|
||||
* @min -1
|
||||
* @max 2200
|
||||
* @unit us
|
||||
* @boolean
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_INT32(PWM_AUX_DIS2, -1);
|
||||
PARAM_DEFINE_INT32(PWM_MAIN_REV1, 0);
|
||||
|
||||
/**
|
||||
* Set the disarmed PWM for the AUX 3 output
|
||||
* Invert direction of main output channel 2
|
||||
*
|
||||
* This is the PWM pulse the autopilot is outputting if not armed.
|
||||
* When set to -1 the value for PWM_AUX_DISARMED will be used
|
||||
* Enable to invert the channel.
|
||||
*
|
||||
* @reboot_required true
|
||||
*
|
||||
* @min -1
|
||||
* @max 2200
|
||||
* @unit us
|
||||
* @boolean
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_INT32(PWM_AUX_DIS3, -1);
|
||||
PARAM_DEFINE_INT32(PWM_MAIN_REV2, 0);
|
||||
|
||||
/**
|
||||
* Set the disarmed PWM for the AUX 4 output
|
||||
* Invert direction of main output channel 3
|
||||
*
|
||||
* This is the PWM pulse the autopilot is outputting if not armed.
|
||||
* When set to -1 the value for PWM_AUX_DISARMED will be used
|
||||
* Enable to invert the channel.
|
||||
*
|
||||
* @reboot_required true
|
||||
*
|
||||
* @min -1
|
||||
* @max 2200
|
||||
* @unit us
|
||||
* @boolean
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_INT32(PWM_AUX_DIS4, -1);
|
||||
PARAM_DEFINE_INT32(PWM_MAIN_REV3, 0);
|
||||
|
||||
/**
|
||||
* Set the disarmed PWM for the AUX 5 output
|
||||
* Invert direction of main output channel 4
|
||||
*
|
||||
* This is the PWM pulse the autopilot is outputting if not armed.
|
||||
* When set to -1 the value for PWM_AUX_DISARMED will be used
|
||||
* Enable to invert the channel.
|
||||
*
|
||||
* @reboot_required true
|
||||
*
|
||||
* @min -1
|
||||
* @max 2200
|
||||
* @unit us
|
||||
* @boolean
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_INT32(PWM_AUX_DIS5, -1);
|
||||
PARAM_DEFINE_INT32(PWM_MAIN_REV4, 0);
|
||||
|
||||
/**
|
||||
* Set the disarmed PWM for the AUX 6 output
|
||||
* Invert direction of main output channel 5
|
||||
*
|
||||
* This is the PWM pulse the autopilot is outputting if not armed.
|
||||
* When set to -1 the value for PWM_AUX_DISARMED will be used
|
||||
* Enable to invert the channel.
|
||||
*
|
||||
* @reboot_required true
|
||||
*
|
||||
* @min -1
|
||||
* @max 2200
|
||||
* @unit us
|
||||
* @boolean
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_INT32(PWM_AUX_DIS6, -1);
|
||||
PARAM_DEFINE_INT32(PWM_MAIN_REV5, 0);
|
||||
|
||||
/**
|
||||
* Set the minimum PWM for the auxiliary outputs
|
||||
* Invert direction of main output channel 6
|
||||
*
|
||||
* Set to 1000 for default or 900 to increase servo travel
|
||||
* Enable to invert the channel.
|
||||
*
|
||||
* @reboot_required true
|
||||
*
|
||||
* @min 800
|
||||
* @max 1400
|
||||
* @unit us
|
||||
* @boolean
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_INT32(PWM_AUX_MIN, 1000);
|
||||
PARAM_DEFINE_INT32(PWM_MAIN_REV6, 0);
|
||||
|
||||
/**
|
||||
* Set the maximum PWM for the auxiliary outputs
|
||||
* Invert direction of main output channel 7
|
||||
*
|
||||
* Set to 2000 for default or 2100 to increase servo travel
|
||||
* Enable to invert the channel.
|
||||
*
|
||||
* @reboot_required true
|
||||
*
|
||||
* @min 1600
|
||||
* @max 2200
|
||||
* @unit us
|
||||
* @boolean
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_INT32(PWM_AUX_MAX, 2000);
|
||||
PARAM_DEFINE_INT32(PWM_MAIN_REV7, 0);
|
||||
|
||||
/**
|
||||
* Set the disarmed PWM for auxiliary outputs
|
||||
* Invert direction of main output channel 8
|
||||
*
|
||||
* 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.
|
||||
* Enable to invert the channel.
|
||||
*
|
||||
* @reboot_required true
|
||||
*
|
||||
* @min 0
|
||||
* @max 2200
|
||||
* @unit us
|
||||
* @boolean
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_INT32(PWM_AUX_DISARMED, 1500);
|
||||
PARAM_DEFINE_INT32(PWM_MAIN_REV8, 0);
|
||||
|
||||
|
||||
|
||||
|
||||
/**
|
||||
* Trim value for main output channel 1
|
||||
*
|
||||
* Set to normalized offset
|
||||
*
|
||||
* @min -0.2
|
||||
* @max 0.2
|
||||
* @decimal 2
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(PWM_MAIN_TRIM1, 0);
|
||||
|
||||
/**
|
||||
* Trim value for main output channel 2
|
||||
*
|
||||
* Set to normalized offset
|
||||
*
|
||||
* @min -0.2
|
||||
* @max 0.2
|
||||
* @decimal 2
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(PWM_MAIN_TRIM2, 0);
|
||||
|
||||
/**
|
||||
* Trim value for main output channel 3
|
||||
*
|
||||
* Set to normalized offset
|
||||
*
|
||||
* @min -0.2
|
||||
* @max 0.2
|
||||
* @decimal 2
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(PWM_MAIN_TRIM3, 0);
|
||||
|
||||
/**
|
||||
* Trim value for main output channel 4
|
||||
*
|
||||
* Set to normalized offset
|
||||
*
|
||||
* @min -0.2
|
||||
* @max 0.2
|
||||
* @decimal 2
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(PWM_MAIN_TRIM4, 0);
|
||||
|
||||
/**
|
||||
* Trim value for main output channel 5
|
||||
*
|
||||
* Set to normalized offset
|
||||
*
|
||||
* @min -0.2
|
||||
* @max 0.2
|
||||
* @decimal 2
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(PWM_MAIN_TRIM5, 0);
|
||||
|
||||
/**
|
||||
* Trim value for main output channel 6
|
||||
*
|
||||
* Set to normalized offset
|
||||
*
|
||||
* @min -0.2
|
||||
* @max 0.2
|
||||
* @decimal 2
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(PWM_MAIN_TRIM6, 0);
|
||||
|
||||
/**
|
||||
* Trim value for main output channel 7
|
||||
*
|
||||
* Set to normalized offset
|
||||
*
|
||||
* @min -0.2
|
||||
* @max 0.2
|
||||
* @decimal 2
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(PWM_MAIN_TRIM7, 0);
|
||||
|
||||
/**
|
||||
* Trim value for main output channel 8
|
||||
*
|
||||
* Set to normalized offset
|
||||
*
|
||||
* @min -0.2
|
||||
* @max 0.2
|
||||
* @decimal 2
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(PWM_MAIN_TRIM8, 0);
|
||||
|
||||
|
||||
|
Loading…
Reference in New Issue