2016-01-14 15:30:56 -04:00
|
|
|
#include "Sub.h"
|
2015-12-30 18:57:56 -04:00
|
|
|
|
2017-04-14 15:50:38 -03:00
|
|
|
// change flight mode and perform any necessary initialisation
|
2017-10-18 21:36:37 -03:00
|
|
|
// returns true if mode was successfully set
|
2016-04-18 01:38:21 -03:00
|
|
|
bool Sub::set_mode(control_mode_t mode, mode_reason_t reason)
|
2015-12-30 18:57:56 -04:00
|
|
|
{
|
|
|
|
// boolean to record if flight mode could be set
|
|
|
|
bool success = false;
|
|
|
|
|
|
|
|
// return immediately if we are already in the desired mode
|
|
|
|
if (mode == control_mode) {
|
2017-02-03 17:33:27 -04:00
|
|
|
prev_control_mode = control_mode;
|
|
|
|
prev_control_mode_reason = control_mode_reason;
|
2016-04-18 01:38:21 -03:00
|
|
|
|
2017-02-03 17:33:27 -04:00
|
|
|
control_mode_reason = reason;
|
2015-12-30 18:57:56 -04:00
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
2017-02-03 17:33:27 -04:00
|
|
|
switch (mode) {
|
|
|
|
case ACRO:
|
2017-04-14 16:10:29 -03:00
|
|
|
success = acro_init();
|
2017-02-03 17:33:27 -04:00
|
|
|
break;
|
2015-12-30 18:57:56 -04:00
|
|
|
|
2017-02-03 17:33:27 -04:00
|
|
|
case STABILIZE:
|
2017-04-14 16:10:29 -03:00
|
|
|
success = stabilize_init();
|
2017-02-03 17:33:27 -04:00
|
|
|
break;
|
2015-12-30 18:57:56 -04:00
|
|
|
|
2017-02-03 17:33:27 -04:00
|
|
|
case ALT_HOLD:
|
2017-04-14 16:10:29 -03:00
|
|
|
success = althold_init();
|
2017-02-03 17:33:27 -04:00
|
|
|
break;
|
2015-12-30 18:57:56 -04:00
|
|
|
|
2017-02-03 17:33:27 -04:00
|
|
|
case AUTO:
|
2017-04-14 16:10:29 -03:00
|
|
|
success = auto_init();
|
2017-02-03 17:33:27 -04:00
|
|
|
break;
|
2015-12-30 18:57:56 -04:00
|
|
|
|
2017-02-03 17:33:27 -04:00
|
|
|
case CIRCLE:
|
2017-04-14 16:10:29 -03:00
|
|
|
success = circle_init();
|
2017-02-03 17:33:27 -04:00
|
|
|
break;
|
2015-12-30 18:57:56 -04:00
|
|
|
|
2017-02-03 17:33:27 -04:00
|
|
|
case GUIDED:
|
2017-04-14 16:10:29 -03:00
|
|
|
success = guided_init();
|
2017-02-03 17:33:27 -04:00
|
|
|
break;
|
2015-12-30 18:57:56 -04:00
|
|
|
|
2017-02-03 17:33:27 -04:00
|
|
|
case SURFACE:
|
2017-04-14 16:10:29 -03:00
|
|
|
success = surface_init();
|
2017-02-03 17:33:27 -04:00
|
|
|
break;
|
2015-12-30 18:57:56 -04:00
|
|
|
|
|
|
|
#if POSHOLD_ENABLED == ENABLED
|
2017-02-03 17:33:27 -04:00
|
|
|
case POSHOLD:
|
2017-04-14 16:10:29 -03:00
|
|
|
success = poshold_init();
|
2017-02-03 17:33:27 -04:00
|
|
|
break;
|
2015-12-30 18:57:56 -04:00
|
|
|
#endif
|
|
|
|
|
2017-02-03 17:33:27 -04:00
|
|
|
case MANUAL:
|
2017-04-14 16:10:29 -03:00
|
|
|
success = manual_init();
|
2017-02-03 17:33:27 -04:00
|
|
|
break;
|
2016-06-26 01:07:27 -03:00
|
|
|
|
2017-02-03 17:33:27 -04:00
|
|
|
default:
|
|
|
|
success = false;
|
|
|
|
break;
|
2015-12-30 18:57:56 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
// update flight mode
|
|
|
|
if (success) {
|
|
|
|
// perform any cleanup required by previous flight mode
|
|
|
|
exit_mode(control_mode, mode);
|
2016-04-18 01:38:21 -03:00
|
|
|
|
|
|
|
prev_control_mode = control_mode;
|
|
|
|
prev_control_mode_reason = control_mode_reason;
|
|
|
|
|
2015-12-30 18:57:56 -04:00
|
|
|
control_mode = mode;
|
2016-04-18 01:38:21 -03:00
|
|
|
control_mode_reason = reason;
|
2019-01-18 00:24:08 -04:00
|
|
|
logger.Write_Mode(control_mode, control_mode_reason);
|
2019-06-26 15:21:56 -03:00
|
|
|
gcs().send_message(MSG_HEARTBEAT);
|
2015-12-30 18:57:56 -04:00
|
|
|
|
2017-04-14 14:13:18 -03:00
|
|
|
// update notify object
|
|
|
|
notify_flight_mode(control_mode);
|
|
|
|
|
2017-10-25 09:36:02 -03:00
|
|
|
#if CAMERA == ENABLED
|
|
|
|
camera.set_is_auto_mode(control_mode == AUTO);
|
|
|
|
#endif
|
|
|
|
|
2015-12-30 18:57:56 -04:00
|
|
|
#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
|
2017-02-03 17:33:27 -04:00
|
|
|
} else {
|
2015-12-30 18:57:56 -04:00
|
|
|
// Log error that we failed to enter desired flight mode
|
2019-03-24 22:53:26 -03:00
|
|
|
AP::logger().Write_Error(LogErrorSubsystem::FLIGHT_MODE, LogErrorCode(mode));
|
2015-12-30 18:57:56 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
// return success or failure
|
|
|
|
return success;
|
|
|
|
}
|
|
|
|
|
|
|
|
// update_flight_mode - calls the appropriate attitude controllers based on flight mode
|
|
|
|
// called at 100hz or more
|
2016-01-14 15:30:56 -04:00
|
|
|
void Sub::update_flight_mode()
|
2015-12-30 18:57:56 -04:00
|
|
|
{
|
|
|
|
switch (control_mode) {
|
2017-02-03 17:33:27 -04:00
|
|
|
case ACRO:
|
|
|
|
acro_run();
|
|
|
|
break;
|
2015-12-30 18:57:56 -04:00
|
|
|
|
2017-02-03 17:33:27 -04:00
|
|
|
case STABILIZE:
|
|
|
|
stabilize_run();
|
|
|
|
break;
|
2015-12-30 18:57:56 -04:00
|
|
|
|
2017-02-03 17:33:27 -04:00
|
|
|
case ALT_HOLD:
|
|
|
|
althold_run();
|
|
|
|
break;
|
2015-12-30 18:57:56 -04:00
|
|
|
|
2017-02-03 17:33:27 -04:00
|
|
|
case AUTO:
|
|
|
|
auto_run();
|
|
|
|
break;
|
2015-12-30 18:57:56 -04:00
|
|
|
|
2017-02-03 17:33:27 -04:00
|
|
|
case CIRCLE:
|
|
|
|
circle_run();
|
|
|
|
break;
|
2015-12-30 18:57:56 -04:00
|
|
|
|
2017-02-03 17:33:27 -04:00
|
|
|
case GUIDED:
|
|
|
|
guided_run();
|
|
|
|
break;
|
2015-12-30 18:57:56 -04:00
|
|
|
|
2017-02-03 17:33:27 -04:00
|
|
|
case SURFACE:
|
|
|
|
surface_run();
|
|
|
|
break;
|
2015-12-30 18:57:56 -04:00
|
|
|
|
|
|
|
#if POSHOLD_ENABLED == ENABLED
|
2017-02-03 17:33:27 -04:00
|
|
|
case POSHOLD:
|
|
|
|
poshold_run();
|
|
|
|
break;
|
2015-12-30 18:57:56 -04:00
|
|
|
#endif
|
|
|
|
|
2017-02-03 17:33:27 -04:00
|
|
|
case MANUAL:
|
|
|
|
manual_run();
|
|
|
|
break;
|
2016-06-26 01:07:27 -03:00
|
|
|
|
2017-02-03 17:33:27 -04:00
|
|
|
default:
|
|
|
|
break;
|
2015-12-30 18:57:56 -04:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
// exit_mode - high level call to organise cleanup as a flight mode is exited
|
2016-04-18 01:38:21 -03:00
|
|
|
void Sub::exit_mode(control_mode_t old_control_mode, control_mode_t new_control_mode)
|
2015-12-30 18:57:56 -04:00
|
|
|
{
|
|
|
|
// 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
|
2017-02-03 17:33:27 -04:00
|
|
|
bool Sub::mode_requires_GPS(control_mode_t mode)
|
|
|
|
{
|
|
|
|
switch (mode) {
|
|
|
|
case AUTO:
|
|
|
|
case GUIDED:
|
|
|
|
case CIRCLE:
|
|
|
|
case POSHOLD:
|
|
|
|
return true;
|
|
|
|
default:
|
|
|
|
return false;
|
2015-12-30 18:57:56 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
// mode_has_manual_throttle - returns true if the flight mode has a manual throttle (i.e. pilot directly controls throttle)
|
2017-02-03 17:33:27 -04:00
|
|
|
bool Sub::mode_has_manual_throttle(control_mode_t mode)
|
|
|
|
{
|
|
|
|
switch (mode) {
|
|
|
|
case ACRO:
|
|
|
|
case STABILIZE:
|
|
|
|
case MANUAL:
|
|
|
|
return true;
|
|
|
|
default:
|
|
|
|
return false;
|
2015-12-30 18:57:56 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
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
|
2017-02-03 17:33:27 -04:00
|
|
|
bool Sub::mode_allows_arming(control_mode_t mode, bool arming_from_gcs)
|
|
|
|
{
|
2018-06-28 12:18:49 -03:00
|
|
|
return (mode_has_manual_throttle(mode)
|
|
|
|
|| mode == ALT_HOLD
|
|
|
|
|| mode == POSHOLD
|
|
|
|
|| (arming_from_gcs&& mode == GUIDED)
|
|
|
|
);
|
2015-12-30 18:57:56 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
// notify_flight_mode - sets notify object based on flight mode. Only used for OreoLED notify device
|
2017-02-03 17:33:27 -04:00
|
|
|
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;
|
2015-12-30 18:57:56 -04:00
|
|
|
}
|
|
|
|
}
|