mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 21:48:28 -04:00
Copter: Tradheli Mavlink Takeoff to fail if rotor not spinning.
This commit is contained in:
parent
e1902e2289
commit
bc6deb5575
@ -28,6 +28,14 @@ bool Copter::current_mode_has_user_takeoff(bool must_navigate)
|
||||
bool Copter::do_user_takeoff(float takeoff_alt_cm, bool must_navigate)
|
||||
{
|
||||
if (motors.armed() && ap.land_complete && current_mode_has_user_takeoff(must_navigate) && takeoff_alt_cm > current_loc.alt) {
|
||||
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
// Helicopters should return false if MAVlink takeoff command is received while the rotor is not spinning
|
||||
if (!motors.rotor_runup_complete()){
|
||||
return false;
|
||||
}
|
||||
#endif
|
||||
|
||||
switch(control_mode) {
|
||||
case GUIDED:
|
||||
set_auto_armed(true);
|
||||
|
Loading…
Reference in New Issue
Block a user