mirror of https://github.com/ArduPilot/ardupilot
Copter: simplify throttle-is-unlimited check
Now not the same pattern as the other checks - but it is much shorter
This commit is contained in:
parent
ce408ca58b
commit
9aa033d84a
|
@ -1468,7 +1468,6 @@ private:
|
||||||
bool throw_position_good() const;
|
bool throw_position_good() const;
|
||||||
bool throw_height_good() const;
|
bool throw_height_good() const;
|
||||||
bool throw_attitude_good() const;
|
bool throw_attitude_good() const;
|
||||||
bool throttle_is_unlimited() const;
|
|
||||||
|
|
||||||
// Throw stages
|
// Throw stages
|
||||||
enum ThrowModeStage {
|
enum ThrowModeStage {
|
||||||
|
|
|
@ -57,7 +57,8 @@ void ModeThrow::run()
|
||||||
// Cancel the waiting for throw tone sequence
|
// Cancel the waiting for throw tone sequence
|
||||||
AP_Notify::flags.waiting_for_throw = false;
|
AP_Notify::flags.waiting_for_throw = false;
|
||||||
|
|
||||||
} else if (stage == Throw_Wait_Throttle_Unlimited && throttle_is_unlimited()) {
|
} else if (stage == Throw_Wait_Throttle_Unlimited &&
|
||||||
|
motors->get_spool_state() == AP_Motors::SpoolState::THROTTLE_UNLIMITED) {
|
||||||
gcs().send_text(MAV_SEVERITY_INFO,"throttle is unlimited - uprighting");
|
gcs().send_text(MAV_SEVERITY_INFO,"throttle is unlimited - uprighting");
|
||||||
stage = Throw_Uprighting;
|
stage = Throw_Uprighting;
|
||||||
} else if (stage == Throw_Uprighting && throw_attitude_good()) {
|
} else if (stage == Throw_Uprighting && throw_attitude_good()) {
|
||||||
|
@ -305,19 +306,4 @@ bool ModeThrow::throw_position_good() const
|
||||||
return (pos_control->get_pos_error_xy_cm() < 50.0f);
|
return (pos_control->get_pos_error_xy_cm() < 50.0f);
|
||||||
}
|
}
|
||||||
|
|
||||||
bool ModeThrow::throttle_is_unlimited() const
|
|
||||||
{
|
|
||||||
switch (motors->get_spool_state()) {
|
|
||||||
case AP_Motors::SpoolState::SHUT_DOWN:
|
|
||||||
case AP_Motors::SpoolState::GROUND_IDLE:
|
|
||||||
case AP_Motors::SpoolState::SPOOLING_UP:
|
|
||||||
return false;
|
|
||||||
case AP_Motors::SpoolState::THROTTLE_UNLIMITED:
|
|
||||||
return true;
|
|
||||||
case AP_Motors::SpoolState::SPOOLING_DOWN:
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
// compiler ensures we never get here
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
#endif
|
#endif
|
||||||
|
|
Loading…
Reference in New Issue