|
|
|
@ -45,7 +45,7 @@ void Plane::set_control_channels(void)
@@ -45,7 +45,7 @@ void Plane::set_control_channels(void)
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
if (!quadplane.enable) { |
|
|
|
|
// setup correct scaling for ESCs like the UAVCAN PX4ESC which
|
|
|
|
|
// setup correct scaling for ESCs like the UAVCAN ESCs which
|
|
|
|
|
// take a proportion of speed. For quadplanes we use AP_Motors
|
|
|
|
|
// scaling
|
|
|
|
|
g2.servo_channels.set_esc_scaling_for(SRV_Channel::k_throttle); |
|
|
|
@ -84,7 +84,7 @@ void Plane::init_rc_out_main()
@@ -84,7 +84,7 @@ void Plane::init_rc_out_main()
|
|
|
|
|
SRV_Channels::set_failsafe_limit(SRV_Channel::k_throttle, SRV_Channel::SRV_CHANNEL_LIMIT_TRIM); |
|
|
|
|
SRV_Channels::set_failsafe_limit(SRV_Channel::k_rudder, SRV_Channel::SRV_CHANNEL_LIMIT_TRIM); |
|
|
|
|
|
|
|
|
|
// setup PX4 to output the min throttle when safety off if arming
|
|
|
|
|
// setup flight controller to output the min throttle when safety off if arming
|
|
|
|
|
// is setup for min on disarm
|
|
|
|
|
if (arming.arming_required() == AP_Arming::Required::YES_MIN_PWM) { |
|
|
|
|
SRV_Channels::set_safety_limit(SRV_Channel::k_throttle, have_reverse_thrust()?SRV_Channel::SRV_CHANNEL_LIMIT_TRIM:SRV_Channel::SRV_CHANNEL_LIMIT_MIN); |
|
|
|
|