Copter: eliminate mode_allows_arming

This commit is contained in:
Peter Barker 2016-03-24 16:01:40 +11:00 committed by Randy Mackay
parent 9c60c1de58
commit a4859e13c1
4 changed files with 6 additions and 49 deletions

View File

@ -586,7 +586,7 @@ bool AP_Arming_Copter::arm_checks(bool display_failure, bool arming_from_gcs)
control_mode_t control_mode = copter.control_mode;
// always check if the current mode allows arming
if (!copter.mode_allows_arming(arming_from_gcs)) {
if (!copter.flightmode->allows_arming(arming_from_gcs)) {
if (display_failure) {
gcs().send_text(MAV_SEVERITY_CRITICAL,"Arm: Mode not armable");
}

View File

@ -805,7 +805,6 @@ private:
void exit_mode(control_mode_t old_control_mode, control_mode_t new_control_mode);
bool mode_requires_GPS();
bool mode_has_manual_throttle(control_mode_t mode);
bool mode_allows_arming(bool arming_from_gcs);
void notify_flight_mode();
void heli_init();
void check_dynamic_flight(void);

View File

@ -236,17 +236,9 @@ void Copter::update_flight_mode()
// Update EKF speed limit - used to limit speed when we are using optical flow
ahrs.getEkfControlLimits(ekfGndSpdLimit, ekfNavVelGainScaler);
if (flightmode != nullptr) {
flightmode->run();
}
switch (control_mode) {
default:
break;
}
}
// exit_mode - high level call to organise cleanup as a flight mode is exited
void Copter::exit_mode(control_mode_t old_control_mode, control_mode_t new_control_mode)
{
@ -324,42 +316,8 @@ bool Copter::mode_has_manual_throttle(control_mode_t mode)
}
}
// mode_allows_arming - returns true if vehicle can be armed in the current mode
// arming_from_gcs should be set to true if the arming request comes from the ground station
bool Copter::mode_allows_arming(bool arming_from_gcs)
{
if (flightmode != nullptr) {
return flightmode->allows_arming(arming_from_gcs);
}
control_mode_t mode = control_mode;
if (mode_has_manual_throttle(mode) || mode == LOITER || mode == ALT_HOLD || mode == POSHOLD || mode == DRIFT || mode == SPORT || mode == THROW || (arming_from_gcs && (mode == GUIDED || mode == GUIDED_NOGPS))) {
return true;
}
return false;
}
// notify_flight_mode - sets notify object based on current flight mode. Only used for OreoLED notify device
void Copter::notify_flight_mode()
{
AP_Notify::flags.flight_mode = control_mode;
if (flightmode != nullptr) {
void Copter::notify_flight_mode() {
AP_Notify::flags.autopilot_mode = flightmode->is_autopilot();
notify.set_flight_mode_str(flightmode->name4());
return;
}
switch (control_mode) {
break;
default:
// all other are manual flight modes
AP_Notify::flags.autopilot_mode = false;
break;
}
// set flight mode string
switch (control_mode) {
default:
notify.set_flight_mode_str("----");
break;
}
}

View File

@ -111,7 +111,7 @@ void Copter::set_land_complete(bool b)
// trigger disarm-on-land if configured
bool disarm_on_land_configured = (g.throttle_behavior & THR_BEHAVE_DISARM_ON_LAND_DETECT) != 0;
bool mode_disarms_on_land = mode_allows_arming(false) && !mode_has_manual_throttle(control_mode);
bool mode_disarms_on_land = flightmode->allows_arming(false) && !mode_has_manual_throttle(control_mode);
if (ap.land_complete && motors->armed() && disarm_on_land_configured && mode_disarms_on_land) {
init_disarm_motors();