mirror of https://github.com/ArduPilot/ardupilot
266 lines
6.5 KiB
C++
266 lines
6.5 KiB
C++
#include "Sub.h"
|
|
|
|
/*
|
|
* flight.pde - high level calls to set and update flight modes
|
|
* logic for individual flight modes is in control_acro.pde, control_stabilize.pde, etc
|
|
*/
|
|
|
|
// set_mode - change flight mode and perform any necessary initialisation
|
|
// optional force parameter used to force the flight mode change (used only first time mode is set)
|
|
// returns true if mode was succesfully set
|
|
// ACRO, STABILIZE, ALTHOLD, LAND, DRIFT and SPORT can always be set successfully but the return state of other flight modes should be checked and the caller should deal with failures appropriately
|
|
bool Sub::set_mode(control_mode_t mode, mode_reason_t reason)
|
|
{
|
|
// boolean to record if flight mode could be set
|
|
bool success = false;
|
|
bool ignore_checks = false; // Always check for now
|
|
|
|
// return immediately if we are already in the desired mode
|
|
if (mode == control_mode) {
|
|
prev_control_mode = control_mode;
|
|
prev_control_mode_reason = control_mode_reason;
|
|
|
|
control_mode_reason = reason;
|
|
return true;
|
|
}
|
|
|
|
switch (mode) {
|
|
case ACRO:
|
|
success = acro_init(ignore_checks);
|
|
break;
|
|
|
|
case STABILIZE:
|
|
success = stabilize_init(ignore_checks);
|
|
break;
|
|
|
|
case ALT_HOLD:
|
|
success = althold_init(ignore_checks);
|
|
break;
|
|
|
|
case AUTO:
|
|
success = auto_init(ignore_checks);
|
|
break;
|
|
|
|
case CIRCLE:
|
|
success = circle_init(ignore_checks);
|
|
break;
|
|
|
|
case GUIDED:
|
|
success = guided_init(ignore_checks);
|
|
break;
|
|
|
|
case SURFACE:
|
|
success = surface_init(ignore_checks);
|
|
break;
|
|
|
|
#if POSHOLD_ENABLED == ENABLED
|
|
case POSHOLD:
|
|
success = poshold_init(ignore_checks);
|
|
break;
|
|
#endif
|
|
|
|
case MANUAL:
|
|
success = manual_init(ignore_checks);
|
|
break;
|
|
|
|
default:
|
|
success = false;
|
|
break;
|
|
}
|
|
|
|
// update flight mode
|
|
if (success) {
|
|
// perform any cleanup required by previous flight mode
|
|
exit_mode(control_mode, mode);
|
|
|
|
prev_control_mode = control_mode;
|
|
prev_control_mode_reason = control_mode_reason;
|
|
|
|
control_mode = mode;
|
|
control_mode_reason = reason;
|
|
DataFlash.Log_Write_Mode(control_mode, control_mode_reason);
|
|
|
|
#if AC_FENCE == ENABLED
|
|
// pilot requested flight mode change during a fence breach indicates pilot is attempting to manually recover
|
|
// this flight mode change could be automatic (i.e. fence, battery, GPS or GCS failsafe)
|
|
// but it should be harmless to disable the fence temporarily in these situations as well
|
|
fence.manual_recovery_start();
|
|
#endif
|
|
} else {
|
|
// Log error that we failed to enter desired flight mode
|
|
Log_Write_Error(ERROR_SUBSYSTEM_FLIGHT_MODE,mode);
|
|
}
|
|
|
|
// update notify object
|
|
if (success) {
|
|
notify_flight_mode(control_mode);
|
|
}
|
|
|
|
// return success or failure
|
|
return success;
|
|
}
|
|
|
|
// update_flight_mode - calls the appropriate attitude controllers based on flight mode
|
|
// called at 100hz or more
|
|
void Sub::update_flight_mode()
|
|
{
|
|
// Update EKF speed limit - used to limit speed when we are using optical flow
|
|
ahrs.getEkfControlLimits(ekfGndSpdLimit, ekfNavVelGainScaler);
|
|
|
|
switch (control_mode) {
|
|
case ACRO:
|
|
acro_run();
|
|
break;
|
|
|
|
case STABILIZE:
|
|
stabilize_run();
|
|
break;
|
|
|
|
case ALT_HOLD:
|
|
althold_run();
|
|
break;
|
|
|
|
case AUTO:
|
|
auto_run();
|
|
break;
|
|
|
|
case CIRCLE:
|
|
circle_run();
|
|
break;
|
|
|
|
case GUIDED:
|
|
guided_run();
|
|
break;
|
|
|
|
case SURFACE:
|
|
surface_run();
|
|
break;
|
|
|
|
#if POSHOLD_ENABLED == ENABLED
|
|
case POSHOLD:
|
|
poshold_run();
|
|
break;
|
|
#endif
|
|
|
|
case MANUAL:
|
|
manual_run();
|
|
break;
|
|
|
|
default:
|
|
break;
|
|
}
|
|
}
|
|
|
|
// exit_mode - high level call to organise cleanup as a flight mode is exited
|
|
void Sub::exit_mode(control_mode_t old_control_mode, control_mode_t new_control_mode)
|
|
{
|
|
// stop mission when we leave auto mode
|
|
if (old_control_mode == AUTO) {
|
|
if (mission.state() == AP_Mission::MISSION_RUNNING) {
|
|
mission.stop();
|
|
}
|
|
#if MOUNT == ENABLED
|
|
camera_mount.set_mode_to_default();
|
|
#endif // MOUNT == ENABLED
|
|
}
|
|
}
|
|
|
|
// returns true or false whether mode requires GPS
|
|
bool Sub::mode_requires_GPS(control_mode_t mode)
|
|
{
|
|
switch (mode) {
|
|
case AUTO:
|
|
case GUIDED:
|
|
case CIRCLE:
|
|
case POSHOLD:
|
|
return true;
|
|
default:
|
|
return false;
|
|
}
|
|
|
|
return false;
|
|
}
|
|
|
|
// mode_has_manual_throttle - returns true if the flight mode has a manual throttle (i.e. pilot directly controls throttle)
|
|
bool Sub::mode_has_manual_throttle(control_mode_t mode)
|
|
{
|
|
switch (mode) {
|
|
case ACRO:
|
|
case STABILIZE:
|
|
case MANUAL:
|
|
return true;
|
|
default:
|
|
return false;
|
|
}
|
|
|
|
return false;
|
|
}
|
|
|
|
// mode_allows_arming - returns true if vehicle can be armed in the specified mode
|
|
// arming_from_gcs should be set to true if the arming request comes from the ground station
|
|
bool Sub::mode_allows_arming(control_mode_t mode, bool arming_from_gcs)
|
|
{
|
|
if (mode_has_manual_throttle(mode) || mode == ALT_HOLD || mode == POSHOLD || (arming_from_gcs && mode == GUIDED)) {
|
|
return true;
|
|
}
|
|
return false;
|
|
}
|
|
|
|
// notify_flight_mode - sets notify object based on flight mode. Only used for OreoLED notify device
|
|
void Sub::notify_flight_mode(control_mode_t mode)
|
|
{
|
|
switch (mode) {
|
|
case AUTO:
|
|
case GUIDED:
|
|
case CIRCLE:
|
|
case SURFACE:
|
|
// autopilot modes
|
|
AP_Notify::flags.autopilot_mode = true;
|
|
break;
|
|
default:
|
|
// all other are manual flight modes
|
|
AP_Notify::flags.autopilot_mode = false;
|
|
break;
|
|
}
|
|
}
|
|
|
|
//
|
|
// print_flight_mode - prints flight mode to serial port.
|
|
//
|
|
void Sub::print_flight_mode(AP_HAL::BetterStream *port, uint8_t mode)
|
|
{
|
|
switch (mode) {
|
|
case STABILIZE:
|
|
port->print("STABILIZE");
|
|
break;
|
|
case ACRO:
|
|
port->print("ACRO");
|
|
break;
|
|
case ALT_HOLD:
|
|
port->print("ALT_HOLD");
|
|
break;
|
|
case AUTO:
|
|
port->print("AUTO");
|
|
break;
|
|
case GUIDED:
|
|
port->print("GUIDED");
|
|
break;
|
|
case CIRCLE:
|
|
port->print("CIRCLE");
|
|
break;
|
|
case SURFACE:
|
|
port->print("SURFACE");
|
|
break;
|
|
case POSHOLD:
|
|
port->print("POSHOLD");
|
|
break;
|
|
case MANUAL:
|
|
port->print("MANUAL");
|
|
break;
|
|
default:
|
|
port->printf("Mode(%u)", (unsigned)mode);
|
|
break;
|
|
}
|
|
}
|
|
|