Copter: manual modes set_land_complete to false

This commit is contained in:
Randy Mackay 2016-08-05 13:36:39 +09:00
parent c3d71f733c
commit 5b5385715e
5 changed files with 21 additions and 0 deletions

View File

@ -33,6 +33,9 @@ void Copter::acro_run()
return;
}
// clear landing flag
set_land_complete(false);
motors.set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
// convert the input to the desired body frame rate

View File

@ -55,6 +55,11 @@ void Copter::drift_run()
return;
}
// clear landing flag above zero throttle
if (!ap.throttle_zero) {
set_land_complete(false);
}
// convert pilot input to lean angles
get_pilot_desired_lean_angles(channel_roll->get_control_in(), channel_pitch->get_control_in(), target_roll, target_pitch, aparm.angle_max);

View File

@ -34,6 +34,9 @@ void Copter::stabilize_run()
return;
}
// clear landing flag
set_land_complete(false);
motors.set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
// apply SIMPLE mode transform to pilot inputs

View File

@ -47,6 +47,11 @@ void Copter::heli_acro_run()
}
}
// clear landing flag above zero throttle
if (motors.armed() && motors.get_interlock() && motors.rotor_runup_complete() && !ap.throttle_zero) {
set_land_complete(false);
}
if (!motors.has_flybar()){
// convert the input to the desired body frame rate
get_pilot_desired_angle_rates(channel_roll->get_control_in(), channel_pitch->get_control_in(), channel_yaw->get_control_in(), target_roll, target_pitch, target_yaw);

View File

@ -46,6 +46,11 @@ void Copter::heli_stabilize_run()
}
}
// clear landing flag above zero throttle
if (motors.armed() && motors.get_interlock() && motors.rotor_runup_complete() && !ap.throttle_zero) {
set_land_complete(false);
}
// apply SIMPLE mode transform to pilot inputs
update_simple_mode();