Plane: restrict rudder arming where reverse_thrust is enabled and commanding negative
This commit is contained in:
parent
a920b7322d
commit
f369899509
@ -10,7 +10,7 @@ const AP_Param::GroupInfo AP_Arming_Plane::var_info[] = {
|
|||||||
|
|
||||||
// @Param: RUDDER
|
// @Param: RUDDER
|
||||||
// @DisplayName: Rudder Arming
|
// @DisplayName: Rudder Arming
|
||||||
// @Description: Control arm/disarm by rudder input. When enabled arming is done with right rudder, disarming with left rudder. Rudder arming only works in manual throttle modes with throttle at zero
|
// @Description: Control arm/disarm by rudder input. When enabled arming is done with right rudder, disarming with left rudder. Rudder arming only works in manual throttle modes with throttle at zero +- deadzone (RCx_DZ)
|
||||||
// @Values: 0:Disabled,1:ArmingOnly,2:ArmOrDisarm
|
// @Values: 0:Disabled,1:ArmingOnly,2:ArmOrDisarm
|
||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
AP_GROUPINFO("RUDDER", 3, AP_Arming_Plane, rudder_arming_value, ARMING_RUDDER_ARMONLY),
|
AP_GROUPINFO("RUDDER", 3, AP_Arming_Plane, rudder_arming_value, ARMING_RUDDER_ARMONLY),
|
||||||
|
@ -102,7 +102,7 @@ void Plane::rudder_arm_disarm_check()
|
|||||||
}
|
}
|
||||||
|
|
||||||
// if throttle is not down, then pilot cannot rudder arm/disarm
|
// if throttle is not down, then pilot cannot rudder arm/disarm
|
||||||
if (channel_throttle->control_in > 0) {
|
if (channel_throttle->control_in != 0){
|
||||||
rudder_arm_timer = 0;
|
rudder_arm_timer = 0;
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user