mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-05-21 04:33:10 +08:00
PWM - Add PWM_MIN and PWM_MAX parameters for MAIN and AUX (#10452)
This commit is contained in:
@@ -262,6 +262,30 @@ then
|
||||
pwm disarmed -c 7 -p p:PWM_AUX_DIS7 -d ${OUTPUT_AUX_DEV}
|
||||
pwm disarmed -c 8 -p p:PWM_AUX_DIS8 -d ${OUTPUT_AUX_DEV}
|
||||
|
||||
#
|
||||
# Per channel min settings.
|
||||
#
|
||||
pwm min -c 1 -p p:PWM_AUX_MIN1 -d ${OUTPUT_AUX_DEV}
|
||||
pwm min -c 2 -p p:PWM_AUX_MIN2 -d ${OUTPUT_AUX_DEV}
|
||||
pwm min -c 3 -p p:PWM_AUX_MIN3 -d ${OUTPUT_AUX_DEV}
|
||||
pwm min -c 4 -p p:PWM_AUX_MIN4 -d ${OUTPUT_AUX_DEV}
|
||||
pwm min -c 5 -p p:PWM_AUX_MIN5 -d ${OUTPUT_AUX_DEV}
|
||||
pwm min -c 6 -p p:PWM_AUX_MIN6 -d ${OUTPUT_AUX_DEV}
|
||||
pwm min -c 7 -p p:PWM_AUX_MIN7 -d ${OUTPUT_AUX_DEV}
|
||||
pwm min -c 8 -p p:PWM_AUX_MIN8 -d ${OUTPUT_AUX_DEV}
|
||||
|
||||
#
|
||||
# Per channel max settings.
|
||||
#
|
||||
pwm max -c 1 -p p:PWM_AUX_MAX1 -d ${OUTPUT_AUX_DEV}
|
||||
pwm max -c 2 -p p:PWM_AUX_MAX2 -d ${OUTPUT_AUX_DEV}
|
||||
pwm max -c 3 -p p:PWM_AUX_MAX3 -d ${OUTPUT_AUX_DEV}
|
||||
pwm max -c 4 -p p:PWM_AUX_MAX4 -d ${OUTPUT_AUX_DEV}
|
||||
pwm max -c 5 -p p:PWM_AUX_MAX5 -d ${OUTPUT_AUX_DEV}
|
||||
pwm max -c 6 -p p:PWM_AUX_MAX6 -d ${OUTPUT_AUX_DEV}
|
||||
pwm max -c 7 -p p:PWM_AUX_MAX7 -d ${OUTPUT_AUX_DEV}
|
||||
pwm max -c 8 -p p:PWM_AUX_MAX8 -d ${OUTPUT_AUX_DEV}
|
||||
|
||||
if [ $FAILSAFE_AUX != none ]
|
||||
then
|
||||
pwm failsafe -c ${PWM_AUX_OUT} -p ${FAILSAFE} -d ${OUTPUT_AUX_DEV}
|
||||
@@ -318,6 +342,30 @@ then
|
||||
pwm disarmed -c 7 -p p:PWM_MAIN_DIS7
|
||||
pwm disarmed -c 8 -p p:PWM_MAIN_DIS8
|
||||
|
||||
#
|
||||
# Per channel min settings.
|
||||
#
|
||||
pwm min -c 1 -p p:PWM_MAIN_MIN1
|
||||
pwm min -c 2 -p p:PWM_MAIN_MIN2
|
||||
pwm min -c 3 -p p:PWM_MAIN_MIN3
|
||||
pwm min -c 4 -p p:PWM_MAIN_MIN4
|
||||
pwm min -c 5 -p p:PWM_MAIN_MIN5
|
||||
pwm min -c 6 -p p:PWM_MAIN_MIN6
|
||||
pwm min -c 7 -p p:PWM_MAIN_MIN7
|
||||
pwm min -c 8 -p p:PWM_MAIN_MIN8
|
||||
|
||||
#
|
||||
# Per channel max settings.
|
||||
#
|
||||
pwm max -c 1 -p p:PWM_MAIN_MAX1
|
||||
pwm max -c 2 -p p:PWM_MAIN_MAX2
|
||||
pwm max -c 3 -p p:PWM_MAIN_MAX3
|
||||
pwm max -c 4 -p p:PWM_MAIN_MAX4
|
||||
pwm max -c 5 -p p:PWM_MAIN_MAX5
|
||||
pwm max -c 6 -p p:PWM_MAIN_MAX6
|
||||
pwm max -c 7 -p p:PWM_MAIN_MAX7
|
||||
pwm max -c 8 -p p:PWM_MAIN_MAX8
|
||||
|
||||
if [ $FAILSAFE != none ]
|
||||
then
|
||||
pwm failsafe -c ${PWM_OUT} -p ${FAILSAFE} -d ${OUTPUT_DEV}
|
||||
|
||||
@@ -101,6 +101,252 @@ PARAM_DEFINE_INT32(PWM_AUX_MAX, 2000);
|
||||
*/
|
||||
PARAM_DEFINE_INT32(PWM_AUX_DISARMED, 1500);
|
||||
|
||||
/******************************************************************************
|
||||
* PWM_AUX_MIN *
|
||||
******************************************************************************/
|
||||
/**
|
||||
* Set the min PWM value for the auxiliary 1 output
|
||||
*
|
||||
* This is the minimum PWM pulse the autopilot is allowed to output.
|
||||
* When set to -1 the value for PWM_AUX_MIN will be used
|
||||
*
|
||||
* @reboot_required true
|
||||
*
|
||||
* @min -1
|
||||
* @max 2200
|
||||
* @unit us
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_INT32(PWM_AUX_MIN1, -1);
|
||||
|
||||
/**
|
||||
* Set the min PWM value for the auxiliary 2 output
|
||||
*
|
||||
* This is the minimum PWM pulse the autopilot is allowed to output.
|
||||
* When set to -1 the value for PWM_AUX_MIN will be used
|
||||
*
|
||||
* @reboot_required true
|
||||
*
|
||||
* @min -1
|
||||
* @max 2200
|
||||
* @unit us
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_INT32(PWM_AUX_MIN2, -1);
|
||||
|
||||
/**
|
||||
* Set the min PWM value for the auxiliary 3 output
|
||||
*
|
||||
* This is the minimum PWM pulse the autopilot is allowed to output.
|
||||
* When set to -1 the value for PWM_AUX_MIN will be used
|
||||
*
|
||||
* @reboot_required true
|
||||
*
|
||||
* @min -1
|
||||
* @max 2200
|
||||
* @unit us
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_INT32(PWM_AUX_MIN3, -1);
|
||||
|
||||
/**
|
||||
* Set the min PWM value for the auxiliary 4 output
|
||||
*
|
||||
* This is the minimum PWM pulse the autopilot is allowed to output.
|
||||
* When set to -1 the value for PWM_AUX_MIN will be used
|
||||
*
|
||||
* @reboot_required true
|
||||
*
|
||||
* @min -1
|
||||
* @max 2200
|
||||
* @unit us
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_INT32(PWM_AUX_MIN4, -1);
|
||||
|
||||
/**
|
||||
* Set the min PWM value for the auxiliary 5 output
|
||||
*
|
||||
* This is the minimum PWM pulse the autopilot is allowed to output.
|
||||
* When set to -1 the value for PWM_AUX_MIN will be used
|
||||
*
|
||||
* @reboot_required true
|
||||
*
|
||||
* @min -1
|
||||
* @max 2200
|
||||
* @unit us
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_INT32(PWM_AUX_MIN5, -1);
|
||||
|
||||
/**
|
||||
* Set the min PWM value for the auxiliary 6 output
|
||||
*
|
||||
* This is the minimum PWM pulse the autopilot is allowed to output.
|
||||
* When set to -1 the value for PWM_AUX_MIN will be used
|
||||
*
|
||||
* @reboot_required true
|
||||
*
|
||||
* @min -1
|
||||
* @max 2200
|
||||
* @unit us
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_INT32(PWM_AUX_MIN6, -1);
|
||||
|
||||
/**
|
||||
* Set the min PWM value for the auxiliary 7 output
|
||||
*
|
||||
* This is the minimum PWM pulse the autopilot is allowed to output.
|
||||
* When set to -1 the value for PWM_AUX_MIN will be used
|
||||
*
|
||||
* @reboot_required true
|
||||
*
|
||||
* @min -1
|
||||
* @max 2200
|
||||
* @unit us
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_INT32(PWM_AUX_MIN7, -1);
|
||||
|
||||
/**
|
||||
* Set the min PWM value for the auxiliary 8 output
|
||||
*
|
||||
* This is the minimum PWM pulse the autopilot is allowed to output.
|
||||
* When set to -1 the value for PWM_AUX_MIN will be used
|
||||
*
|
||||
* @reboot_required true
|
||||
*
|
||||
* @min -1
|
||||
* @max 2200
|
||||
* @unit us
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_INT32(PWM_AUX_MIN8, -1);
|
||||
|
||||
/******************************************************************************
|
||||
* PWM_AUX_MAX *
|
||||
******************************************************************************/
|
||||
/**
|
||||
* Set the max PWM value for the auxiliary 1 output
|
||||
*
|
||||
* This is the maximum PWM pulse the autopilot is allowed to output.
|
||||
* When set to -1 the value for PWM_AUX_MAX will be used
|
||||
*
|
||||
* @reboot_required true
|
||||
*
|
||||
* @min -1
|
||||
* @max 2200
|
||||
* @unit us
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_INT32(PWM_AUX_MAX1, -1);
|
||||
|
||||
/**
|
||||
* Set the max PWM value for the auxiliary 2 output
|
||||
*
|
||||
* This is the maximum PWM pulse the autopilot is allowed to output.
|
||||
* When set to -1 the value for PWM_AUX_MAX will be used
|
||||
*
|
||||
* @reboot_required true
|
||||
*
|
||||
* @min -1
|
||||
* @max 2200
|
||||
* @unit us
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_INT32(PWM_AUX_MAX2, -1);
|
||||
|
||||
/**
|
||||
* Set the max PWM value for the auxiliary 3 output
|
||||
*
|
||||
* This is the maximum PWM pulse the autopilot is allowed to output.
|
||||
* When set to -1 the value for PWM_AUX_MAX will be used
|
||||
*
|
||||
* @reboot_required true
|
||||
*
|
||||
* @min -1
|
||||
* @max 2200
|
||||
* @unit us
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_INT32(PWM_AUX_MAX3, -1);
|
||||
|
||||
/**
|
||||
* Set the max PWM value for the auxiliary 4 output
|
||||
*
|
||||
* This is the maximum PWM pulse the autopilot is allowed to output.
|
||||
* When set to -1 the value for PWM_AUX_MAX will be used
|
||||
*
|
||||
* @reboot_required true
|
||||
*
|
||||
* @min -1
|
||||
* @max 2200
|
||||
* @unit us
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_INT32(PWM_AUX_MAX4, -1);
|
||||
|
||||
/**
|
||||
* Set the max PWM value for the auxiliary 5 output
|
||||
*
|
||||
* This is the maximum PWM pulse the autopilot is allowed to output.
|
||||
* When set to -1 the value for PWM_AUX_MAX will be used
|
||||
*
|
||||
* @reboot_required true
|
||||
*
|
||||
* @min -1
|
||||
* @max 2200
|
||||
* @unit us
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_INT32(PWM_AUX_MAX5, -1);
|
||||
|
||||
/**
|
||||
* Set the max PWM value for the auxiliary 6 output
|
||||
*
|
||||
* This is the maximum PWM pulse the autopilot is allowed to output.
|
||||
* When set to -1 the value for PWM_AUX_MAX will be used
|
||||
*
|
||||
* @reboot_required true
|
||||
*
|
||||
* @min -1
|
||||
* @max 2200
|
||||
* @unit us
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_INT32(PWM_AUX_MAX6, -1);
|
||||
|
||||
/**
|
||||
* Set the max PWM value for the auxiliary 7 output
|
||||
*
|
||||
* This is the maximum PWM pulse the autopilot is allowed to output.
|
||||
* When set to -1 the value for PWM_AUX_MAX will be used
|
||||
*
|
||||
* @reboot_required true
|
||||
*
|
||||
* @min -1
|
||||
* @max 2200
|
||||
* @unit us
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_INT32(PWM_AUX_MAX7, -1);
|
||||
|
||||
/**
|
||||
* Set the max PWM value for the auxiliary 8 output
|
||||
*
|
||||
* This is the maximum PWM pulse the autopilot is allowed to output.
|
||||
* When set to -1 the value for PWM_AUX_MAX will be used
|
||||
*
|
||||
* @reboot_required true
|
||||
*
|
||||
* @min -1
|
||||
* @max 2200
|
||||
* @unit us
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_INT32(PWM_AUX_MAX8, -1);
|
||||
|
||||
/******************************************************************************
|
||||
* PWM_AUX_FAIL *
|
||||
******************************************************************************/
|
||||
|
||||
@@ -101,6 +101,252 @@ PARAM_DEFINE_INT32(PWM_MAX, 2000);
|
||||
*/
|
||||
PARAM_DEFINE_INT32(PWM_DISARMED, 900);
|
||||
|
||||
/******************************************************************************
|
||||
* PWM_MAIN_MIN *
|
||||
******************************************************************************/
|
||||
/**
|
||||
* Set the min PWM value for the main 1 output
|
||||
*
|
||||
* This is the minimum PWM pulse the autopilot is allowed to output.
|
||||
* When set to -1 the value for PWM_MIN will be used
|
||||
*
|
||||
* @reboot_required true
|
||||
*
|
||||
* @min -1
|
||||
* @max 2200
|
||||
* @unit us
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_INT32(PWM_MAIN_MIN1, -1);
|
||||
|
||||
/**
|
||||
* Set the min PWM value for the main 2 output
|
||||
*
|
||||
* This is the minimum PWM pulse the autopilot is allowed to output.
|
||||
* When set to -1 the value for PWM_MIN will be used
|
||||
*
|
||||
* @reboot_required true
|
||||
*
|
||||
* @min -1
|
||||
* @max 2200
|
||||
* @unit us
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_INT32(PWM_MAIN_MIN2, -1);
|
||||
|
||||
/**
|
||||
* Set the min PWM value for the main 3 output
|
||||
*
|
||||
* This is the minimum PWM pulse the autopilot is allowed to output.
|
||||
* When set to -1 the value for PWM_MIN will be used
|
||||
*
|
||||
* @reboot_required true
|
||||
*
|
||||
* @min -1
|
||||
* @max 2200
|
||||
* @unit us
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_INT32(PWM_MAIN_MIN3, -1);
|
||||
|
||||
/**
|
||||
* Set the min PWM value for the main 4 output
|
||||
*
|
||||
* This is the minimum PWM pulse the autopilot is allowed to output.
|
||||
* When set to -1 the value for PWM_MIN will be used
|
||||
*
|
||||
* @reboot_required true
|
||||
*
|
||||
* @min -1
|
||||
* @max 2200
|
||||
* @unit us
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_INT32(PWM_MAIN_MIN4, -1);
|
||||
|
||||
/**
|
||||
* Set the min PWM value for the main 5 output
|
||||
*
|
||||
* This is the minimum PWM pulse the autopilot is allowed to output.
|
||||
* When set to -1 the value for PWM_MIN will be used
|
||||
*
|
||||
* @reboot_required true
|
||||
*
|
||||
* @min -1
|
||||
* @max 2200
|
||||
* @unit us
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_INT32(PWM_MAIN_MIN5, -1);
|
||||
|
||||
/**
|
||||
* Set the min PWM value for the main 6 output
|
||||
*
|
||||
* This is the minimum PWM pulse the autopilot is allowed to output.
|
||||
* When set to -1 the value for PWM_MIN will be used
|
||||
*
|
||||
* @reboot_required true
|
||||
*
|
||||
* @min -1
|
||||
* @max 2200
|
||||
* @unit us
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_INT32(PWM_MAIN_MIN6, -1);
|
||||
|
||||
/**
|
||||
* Set the min PWM value for the main 7 output
|
||||
*
|
||||
* This is the minimum PWM pulse the autopilot is allowed to output.
|
||||
* When set to -1 the value for PWM_MIN will be used
|
||||
*
|
||||
* @reboot_required true
|
||||
*
|
||||
* @min -1
|
||||
* @max 2200
|
||||
* @unit us
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_INT32(PWM_MAIN_MIN7, -1);
|
||||
|
||||
/**
|
||||
* Set the min PWM value for the main 8 output
|
||||
*
|
||||
* This is the minimum PWM pulse the autopilot is allowed to output.
|
||||
* When set to -1 the value for PWM_MIN will be used
|
||||
*
|
||||
* @reboot_required true
|
||||
*
|
||||
* @min -1
|
||||
* @max 2200
|
||||
* @unit us
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_INT32(PWM_MAIN_MIN8, -1);
|
||||
|
||||
/******************************************************************************
|
||||
* PWM_MAIN_MAX *
|
||||
******************************************************************************/
|
||||
/**
|
||||
* Set the max PWM value for the main 1 output
|
||||
*
|
||||
* This is the maximum PWM pulse the autopilot is allowed to output.
|
||||
* When set to -1 the value for PWM_MAX will be used
|
||||
*
|
||||
* @reboot_required true
|
||||
*
|
||||
* @min -1
|
||||
* @max 2200
|
||||
* @unit us
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_INT32(PWM_MAIN_MAX1, -1);
|
||||
|
||||
/**
|
||||
* Set the max PWM value for the main 2 output
|
||||
*
|
||||
* This is the maximum PWM pulse the autopilot is allowed to output.
|
||||
* When set to -1 the value for PWM_MAX will be used
|
||||
*
|
||||
* @reboot_required true
|
||||
*
|
||||
* @min -1
|
||||
* @max 2200
|
||||
* @unit us
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_INT32(PWM_MAIN_MAX2, -1);
|
||||
|
||||
/**
|
||||
* Set the max PWM value for the main 3 output
|
||||
*
|
||||
* This is the maximum PWM pulse the autopilot is allowed to output.
|
||||
* When set to -1 the value for PWM_MAX will be used
|
||||
*
|
||||
* @reboot_required true
|
||||
*
|
||||
* @min -1
|
||||
* @max 2200
|
||||
* @unit us
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_INT32(PWM_MAIN_MAX3, -1);
|
||||
|
||||
/**
|
||||
* Set the max PWM value for the main 4 output
|
||||
*
|
||||
* This is the maximum PWM pulse the autopilot is allowed to output.
|
||||
* When set to -1 the value for PWM_MAX will be used
|
||||
*
|
||||
* @reboot_required true
|
||||
*
|
||||
* @min -1
|
||||
* @max 2200
|
||||
* @unit us
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_INT32(PWM_MAIN_MAX4, -1);
|
||||
|
||||
/**
|
||||
* Set the max PWM value for the main 5 output
|
||||
*
|
||||
* This is the maximum PWM pulse the autopilot is allowed to output.
|
||||
* When set to -1 the value for PWM_MAX will be used
|
||||
*
|
||||
* @reboot_required true
|
||||
*
|
||||
* @min -1
|
||||
* @max 2200
|
||||
* @unit us
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_INT32(PWM_MAIN_MAX5, -1);
|
||||
|
||||
/**
|
||||
* Set the max PWM value for the main 6 output
|
||||
*
|
||||
* This is the maximum PWM pulse the autopilot is allowed to output.
|
||||
* When set to -1 the value for PWM_MAX will be used
|
||||
*
|
||||
* @reboot_required true
|
||||
*
|
||||
* @min -1
|
||||
* @max 2200
|
||||
* @unit us
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_INT32(PWM_MAIN_MAX6, -1);
|
||||
|
||||
/**
|
||||
* Set the max PWM value for the main 7 output
|
||||
*
|
||||
* This is the maximum PWM pulse the autopilot is allowed to output.
|
||||
* When set to -1 the value for PWM_MAX will be used
|
||||
*
|
||||
* @reboot_required true
|
||||
*
|
||||
* @min -1
|
||||
* @max 2200
|
||||
* @unit us
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_INT32(PWM_MAIN_MAX7, -1);
|
||||
|
||||
/**
|
||||
* Set the max PWM value for the main 8 output
|
||||
*
|
||||
* This is the maximum PWM pulse the autopilot is allowed to output.
|
||||
* When set to -1 the value for PWM_MAX will be used
|
||||
*
|
||||
* @reboot_required true
|
||||
*
|
||||
* @min -1
|
||||
* @max 2200
|
||||
* @unit us
|
||||
* @group PWM Outputs
|
||||
*/
|
||||
PARAM_DEFINE_INT32(PWM_MAIN_MAX8, -1);
|
||||
|
||||
/******************************************************************************
|
||||
* PWM_MAIN_FAIL *
|
||||
******************************************************************************/
|
||||
|
||||
@@ -439,6 +439,10 @@ pwm_main(int argc, char *argv[])
|
||||
return 1;
|
||||
}
|
||||
|
||||
if (pwm_value < 0) {
|
||||
return 0;
|
||||
}
|
||||
|
||||
if (pwm_value == 0) {
|
||||
usage("min: no PWM value provided");
|
||||
return 1;
|
||||
@@ -491,6 +495,10 @@ pwm_main(int argc, char *argv[])
|
||||
return 1;
|
||||
}
|
||||
|
||||
if (pwm_value < 0) {
|
||||
return 0;
|
||||
}
|
||||
|
||||
if (pwm_value == 0) {
|
||||
usage("no PWM value provided");
|
||||
return 1;
|
||||
|
||||
Reference in New Issue
Block a user