mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-08 08:53:56 -04:00
Plane: added THR_PASS_STAB parameter
this allows direct passthru of throttle in STABILIZE and FBWA, which is useful for nitro planes wher you have a throttle cut switch that drops the throttle below normal minimum.
This commit is contained in:
parent
d33d884f69
commit
2446b986c5
@ -454,6 +454,7 @@ static void set_servos(void)
|
|||||||
g.throttle_max.get());
|
g.throttle_max.get());
|
||||||
|
|
||||||
if (suppress_throttle()) {
|
if (suppress_throttle()) {
|
||||||
|
// throttle is suppressed in auto mode
|
||||||
g.channel_throttle.servo_out = 0;
|
g.channel_throttle.servo_out = 0;
|
||||||
if (g.throttle_suppress_manual) {
|
if (g.throttle_suppress_manual) {
|
||||||
// manual pass through of throttle while throttle is suppressed
|
// manual pass through of throttle while throttle is suppressed
|
||||||
@ -461,7 +462,13 @@ static void set_servos(void)
|
|||||||
} else {
|
} else {
|
||||||
g.channel_throttle.calc_pwm();
|
g.channel_throttle.calc_pwm();
|
||||||
}
|
}
|
||||||
|
} else if (g.throttle_passthru_stabilize &&
|
||||||
|
(control_mode == STABILIZE || control_mode == FLY_BY_WIRE_A)) {
|
||||||
|
// manual pass through of throttle while in FBWA or
|
||||||
|
// STABILIZE mode with THR_PASS_STAB set
|
||||||
|
g.channel_throttle.radio_out = g.channel_throttle.radio_in;
|
||||||
} else {
|
} else {
|
||||||
|
// normal throttle calculation based on servo_out
|
||||||
g.channel_throttle.calc_pwm();
|
g.channel_throttle.calc_pwm();
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
@ -170,6 +170,7 @@ public:
|
|||||||
k_param_gcs_heartbeat_fs_enabled,
|
k_param_gcs_heartbeat_fs_enabled,
|
||||||
k_param_throttle_slewrate,
|
k_param_throttle_slewrate,
|
||||||
k_param_throttle_suppress_manual,
|
k_param_throttle_suppress_manual,
|
||||||
|
k_param_throttle_passthru_stabilize,
|
||||||
|
|
||||||
//
|
//
|
||||||
// 200: Feed-forward gains
|
// 200: Feed-forward gains
|
||||||
@ -286,6 +287,7 @@ public:
|
|||||||
AP_Int8 throttle_max;
|
AP_Int8 throttle_max;
|
||||||
AP_Int8 throttle_slewrate;
|
AP_Int8 throttle_slewrate;
|
||||||
AP_Int8 throttle_suppress_manual;
|
AP_Int8 throttle_suppress_manual;
|
||||||
|
AP_Int8 throttle_passthru_stabilize;
|
||||||
AP_Int8 throttle_fs_enabled;
|
AP_Int8 throttle_fs_enabled;
|
||||||
AP_Int16 throttle_fs_value;
|
AP_Int16 throttle_fs_value;
|
||||||
AP_Int8 throttle_cruise;
|
AP_Int8 throttle_cruise;
|
||||||
|
@ -288,6 +288,13 @@ const AP_Param::Info var_info[] PROGMEM = {
|
|||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
GSCALAR(throttle_suppress_manual,"THR_SUPP_MAN", 0),
|
GSCALAR(throttle_suppress_manual,"THR_SUPP_MAN", 0),
|
||||||
|
|
||||||
|
// @Param: THR_PASS_STAB
|
||||||
|
// @DisplayName: Throttle passthru in stabilize
|
||||||
|
// @Description: If this is set then when in STABILIZE or FBWA mode the throttle is a direct passthru from the transmitter. This means the THR_MIN and THR_MAX settings are not used in these modes. This is useful for petrol engines where you setup a throttle cut switch that suppresses the throttle below the normal minimum.
|
||||||
|
// @Values: 0:Disabled,1:Enabled
|
||||||
|
// @User: Advanced
|
||||||
|
GSCALAR(throttle_passthru_stabilize,"THR_PASS_STAB", 0),
|
||||||
|
|
||||||
// @Param: THR_FAILSAFE
|
// @Param: THR_FAILSAFE
|
||||||
// @DisplayName: Throttle Failsafe Enable
|
// @DisplayName: Throttle Failsafe Enable
|
||||||
// @Description: The throttle failsafe allows you to configure a software failsafe activated by a setting on the throttle input channel
|
// @Description: The throttle failsafe allows you to configure a software failsafe activated by a setting on the throttle input channel
|
||||||
|
Loading…
Reference in New Issue
Block a user