mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-03 14:38:44 -04:00
Copter: fixed motor runup check for heli
for all auto-throttle modes we should not allow a mode change to the mode if the motor runup is not complete. This moves the code to the set_mode() so it applies to all modes fixes issue #6956
This commit is contained in:
parent
02f6f3b87b
commit
61da180881
@ -8,13 +8,6 @@
|
||||
// althold_init - initialise althold controller
|
||||
bool Copter::althold_init(bool ignore_checks)
|
||||
{
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
// do not allow helis to enter Alt Hold if the Rotor Runup is not complete
|
||||
if (!ignore_checks && !motors->rotor_runup_complete()){
|
||||
return false;
|
||||
}
|
||||
#endif
|
||||
|
||||
// initialize vertical speeds and leash lengths
|
||||
pos_control->set_speed_z(-g.pilot_velocity_z_max, g.pilot_velocity_z_max);
|
||||
pos_control->set_accel_z(g.pilot_accel_z);
|
||||
|
@ -7,13 +7,6 @@
|
||||
// loiter_init - initialise loiter controller
|
||||
bool Copter::loiter_init(bool ignore_checks)
|
||||
{
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
// do not allow helis to enter Loiter if the Rotor Runup is not complete
|
||||
if (!ignore_checks && !motors->rotor_runup_complete()){
|
||||
return false;
|
||||
}
|
||||
#endif
|
||||
|
||||
if (position_ok() || ignore_checks) {
|
||||
|
||||
// set target to current position
|
||||
|
@ -75,13 +75,6 @@ static struct {
|
||||
// poshold_init - initialise PosHold controller
|
||||
bool Copter::poshold_init(bool ignore_checks)
|
||||
{
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
// do not allow helis to enter Pos Hold if the Rotor Runup is not complete
|
||||
if (!ignore_checks && !motors->rotor_runup_complete()){
|
||||
return false;
|
||||
}
|
||||
#endif
|
||||
|
||||
// fail to initialise PosHold mode if no GPS lock
|
||||
if (!position_ok() && !ignore_checks) {
|
||||
return false;
|
||||
|
@ -24,6 +24,15 @@ bool Copter::set_mode(control_mode_t mode, mode_reason_t reason)
|
||||
return true;
|
||||
}
|
||||
|
||||
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
// do not allow helis to enter a non-manual throttle mode if the
|
||||
// rotor runup is not complete
|
||||
if (!ignore_checks && !mode_has_manual_throttle(mode) && !motors->rotor_runup_complete()){
|
||||
goto failed;
|
||||
}
|
||||
#endif
|
||||
|
||||
switch (mode) {
|
||||
case ACRO:
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
@ -114,6 +123,10 @@ bool Copter::set_mode(control_mode_t mode, mode_reason_t reason)
|
||||
break;
|
||||
}
|
||||
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
failed:
|
||||
#endif
|
||||
|
||||
// update flight mode
|
||||
if (success) {
|
||||
// perform any cleanup required by previous flight mode
|
||||
|
Loading…
Reference in New Issue
Block a user