Copter: land detector allows larger lean angle request in land mode

This commit is contained in:
Randy Mackay 2020-04-28 17:34:32 +09:00
parent a7aa43f5d5
commit 64360f263c
1 changed files with 4 additions and 1 deletions

View File

@ -173,7 +173,10 @@ void Copter::update_throttle_mix()
// check for requested decent
bool descent_not_demanded = pos_control->get_desired_velocity().z >= 0.0f;
if (large_angle_request || large_angle_error || accel_moving || descent_not_demanded) {
// check if landing
const bool landing = flightmode->is_landing();
if ((large_angle_request && !landing) || large_angle_error || accel_moving || descent_not_demanded) {
attitude_control->set_throttle_mix_max(pos_control->get_vel_z_control_ratio());
} else {
attitude_control->set_throttle_mix_min();