mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
Copter: Ch7/8 switch to enable/disable feed forward and accel limiting
This commit is contained in:
parent
46f25c52a4
commit
810c87969c
@ -391,14 +391,14 @@ const AP_Param::Info var_info[] PROGMEM = {
|
||||
// @Param: CH7_OPT
|
||||
// @DisplayName: Channel 7 option
|
||||
// @Description: Select which function if performed when CH7 is above 1800 pwm
|
||||
// @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 8:Multi Mode, 9:Camera Trigger, 10:Sonar, 11:Fence, 12:ResetToArmedYaw, 13:Super Simple Mode, 14:Acro Trainer, 16:Auto, 17:AutoTune, 18:Land, 19:EPM, 20:EKF, 21:Parachute Enable, 22:Parachute Release, 23:Parachute 3pos, 24:Auto Mission Reset
|
||||
// @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 8:Multi Mode, 9:Camera Trigger, 10:Sonar, 11:Fence, 12:ResetToArmedYaw, 13:Super Simple Mode, 14:Acro Trainer, 16:Auto, 17:AutoTune, 18:Land, 19:EPM, 20:EKF, 21:Parachute Enable, 22:Parachute Release, 23:Parachute 3pos, 24:Auto Mission Reset, 25:AttCon Feed Forward, 26:AttCon Accel Limits
|
||||
// @User: Standard
|
||||
GSCALAR(ch7_option, "CH7_OPT", CH7_OPTION),
|
||||
|
||||
// @Param: CH8_OPT
|
||||
// @DisplayName: Channel 8 option
|
||||
// @Description: Select which function if performed when CH8 is above 1800 pwm
|
||||
// @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 8:Multi Mode, 9:Camera Trigger, 10:Sonar, 11:Fence, 12:ResetToArmedYaw, 13:Super Simple Mode, 14:Acro Trainer, 16:Auto, 17:AutoTune, 18:Land, 19:EPM, 20:EKF, 21:Parachute Enable, 22:Parachute Release, 23:Parachute 3pos, 24:Auto Mission Reset
|
||||
// @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 8:Multi Mode, 9:Camera Trigger, 10:Sonar, 11:Fence, 12:ResetToArmedYaw, 13:Super Simple Mode, 14:Acro Trainer, 16:Auto, 17:AutoTune, 18:Land, 19:EPM, 20:EKF, 21:Parachute Enable, 22:Parachute Release, 23:Parachute 3pos, 24:Auto Mission Reset, 25:AttCon Feed Forward, 26:AttCon Accel Limits
|
||||
// @User: Standard
|
||||
GSCALAR(ch8_option, "CH8_OPT", CH8_OPTION),
|
||||
|
||||
|
@ -113,6 +113,8 @@ static void init_aux_switches()
|
||||
case AUX_SWITCH_PARACHUTE_ENABLE:
|
||||
case AUX_SWITCH_PARACHUTE_3POS: // we trust the vehicle will be disarmed so even if switch is in release position the chute will not release
|
||||
case AUX_SWITCH_MISSIONRESET:
|
||||
case AUX_SWITCH_ATTCON_FEEDFWD:
|
||||
case AUX_SWITCH_ATTCON_ACCEL_LIM:
|
||||
do_aux_switch_function(g.ch7_option, ap.CH7_flag);
|
||||
break;
|
||||
}
|
||||
@ -131,6 +133,8 @@ static void init_aux_switches()
|
||||
case AUX_SWITCH_PARACHUTE_ENABLE:
|
||||
case AUX_SWITCH_PARACHUTE_3POS: // we trust the vehicle will be disarmed so even if switch is in release position the chute will not release
|
||||
case AUX_SWITCH_MISSIONRESET:
|
||||
case AUX_SWITCH_ATTCON_FEEDFWD:
|
||||
case AUX_SWITCH_ATTCON_ACCEL_LIM:
|
||||
do_aux_switch_function(g.ch8_option, ap.CH8_flag);
|
||||
break;
|
||||
}
|
||||
@ -409,6 +413,16 @@ static void do_aux_switch_function(int8_t ch_function, uint8_t ch_flag)
|
||||
mission.reset();
|
||||
}
|
||||
break;
|
||||
|
||||
case AUX_SWITCH_ATTCON_FEEDFWD:
|
||||
// enable or disable feed forward
|
||||
attitude_control.bf_feedforward(ch_flag == AUX_SWITCH_HIGH);
|
||||
break;
|
||||
|
||||
case AUX_SWITCH_ATTCON_ACCEL_LIM:
|
||||
// enable or disable accel limiting by restoring defaults
|
||||
attitude_control.accel_limiting(ch_flag == AUX_SWITCH_HIGH);
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -57,6 +57,8 @@
|
||||
#define AUX_SWITCH_PARACHUTE_RELEASE 22 // Parachute release
|
||||
#define AUX_SWITCH_PARACHUTE_3POS 23 // Parachute disable, enable, release with 3 position switch
|
||||
#define AUX_SWITCH_MISSIONRESET 24 // Reset auto mission to start from first command
|
||||
#define AUX_SWITCH_ATTCON_FEEDFWD 25 // enable/disable the roll and pitch rate feed forward
|
||||
#define AUX_SWITCH_ATTCON_ACCEL_LIM 26 // enable/disable the roll, pitch and yaw accel limiting
|
||||
|
||||
// values used by the ap.ch7_opt and ap.ch8_opt flags
|
||||
#define AUX_SWITCH_LOW 0 // indicates auxiliar switch is in the low position (pwm <1200)
|
||||
|
Loading…
Reference in New Issue
Block a user