2014-02-03 04:57:31 -04:00
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
2015-05-29 23:12:49 -03:00
# include "Copter.h"
2014-02-03 04:57:31 -04:00
/*
* 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
2015-05-29 23:12:49 -03:00
bool Copter : : set_mode ( uint8_t mode )
2014-02-03 04:57:31 -04:00
{
// boolean to record if flight mode could be set
bool success = false ;
bool ignore_checks = ! motors . armed ( ) ; // allow switching to any mode if disarmed. We rely on the arming check to perform
// return immediately if we are already in the desired mode
if ( mode = = control_mode ) {
return true ;
}
switch ( mode ) {
case ACRO :
# if FRAME_CONFIG == HELI_FRAME
success = heli_acro_init ( ignore_checks ) ;
# else
success = acro_init ( ignore_checks ) ;
# endif
break ;
case STABILIZE :
# if FRAME_CONFIG == HELI_FRAME
success = heli_stabilize_init ( ignore_checks ) ;
# else
success = stabilize_init ( ignore_checks ) ;
# endif
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 LOITER :
success = loiter_init ( ignore_checks ) ;
break ;
case GUIDED :
success = guided_init ( ignore_checks ) ;
break ;
case LAND :
success = land_init ( ignore_checks ) ;
break ;
case RTL :
success = rtl_init ( ignore_checks ) ;
break ;
case DRIFT :
success = drift_init ( ignore_checks ) ;
break ;
case SPORT :
success = sport_init ( ignore_checks ) ;
break ;
case FLIP :
success = flip_init ( ignore_checks ) ;
break ;
# if AUTOTUNE_ENABLED == ENABLED
case AUTOTUNE :
success = autotune_init ( ignore_checks ) ;
break ;
# endif
2014-07-11 02:08:09 -03:00
# if POSHOLD_ENABLED == ENABLED
case POSHOLD :
success = poshold_init ( ignore_checks ) ;
2014-04-04 11:14:30 -03:00
break ;
2014-04-23 03:24:03 -03:00
# endif
2014-04-04 11:14:30 -03:00
2015-05-17 00:22:20 -03:00
case BRAKE :
success = brake_init ( ignore_checks ) ;
2015-04-22 18:10:30 -03:00
break ;
2014-02-03 04:57:31 -04:00
default :
success = false ;
break ;
}
// update flight mode
if ( success ) {
// perform any cleanup required by previous flight mode
2014-02-11 09:32:44 -04:00
exit_mode ( control_mode , mode ) ;
2014-02-03 04:57:31 -04:00
control_mode = mode ;
2014-12-22 16:11:31 -04:00
DataFlash . Log_Write_Mode ( control_mode ) ;
2014-04-26 23:09:15 -03: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
2014-02-03 04:57:31 -04:00
} else {
// Log error that we failed to enter desired flight mode
Log_Write_Error ( ERROR_SUBSYSTEM_FLIGHT_MODE , mode ) ;
}
2015-03-06 02:33:25 -04:00
// update notify object
if ( success ) {
notify_flight_mode ( control_mode ) ;
}
2014-02-03 04:57:31 -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
2015-05-29 23:12:49 -03:00
void Copter : : update_flight_mode ( )
2014-02-03 04:57:31 -04:00
{
2014-11-15 20:51:46 -04:00
// Update EKF speed limit - used to limit speed when we are using optical flow
2014-11-15 21:42:56 -04:00
ahrs . getEkfControlLimits ( ekfGndSpdLimit , ekfNavVelGainScaler ) ;
2015-06-10 00:14:13 -03:00
2014-02-03 04:57:31 -04:00
switch ( control_mode ) {
case ACRO :
# if FRAME_CONFIG == HELI_FRAME
heli_acro_run ( ) ;
# else
acro_run ( ) ;
# endif
break ;
case STABILIZE :
# if FRAME_CONFIG == HELI_FRAME
heli_stabilize_run ( ) ;
# else
stabilize_run ( ) ;
# endif
break ;
case ALT_HOLD :
althold_run ( ) ;
break ;
case AUTO :
auto_run ( ) ;
break ;
case CIRCLE :
circle_run ( ) ;
break ;
case LOITER :
loiter_run ( ) ;
break ;
case GUIDED :
guided_run ( ) ;
break ;
case LAND :
land_run ( ) ;
break ;
case RTL :
rtl_run ( ) ;
break ;
case DRIFT :
drift_run ( ) ;
break ;
case SPORT :
sport_run ( ) ;
break ;
case FLIP :
flip_run ( ) ;
break ;
# if AUTOTUNE_ENABLED == ENABLED
case AUTOTUNE :
autotune_run ( ) ;
break ;
# endif
2014-04-04 11:14:30 -03:00
2014-07-11 02:08:09 -03:00
# if POSHOLD_ENABLED == ENABLED
case POSHOLD :
poshold_run ( ) ;
2014-04-04 11:14:30 -03:00
break ;
2014-04-23 03:24:03 -03:00
# endif
2015-04-22 18:10:30 -03:00
2015-05-17 00:22:20 -03:00
case BRAKE :
brake_run ( ) ;
2015-04-22 18:10:30 -03:00
break ;
2014-02-03 04:57:31 -04:00
}
}
// exit_mode - high level call to organise cleanup as a flight mode is exited
2015-05-29 23:12:49 -03:00
void Copter : : exit_mode ( uint8_t old_control_mode , uint8_t new_control_mode )
2014-02-03 04:57:31 -04:00
{
# if AUTOTUNE_ENABLED == ENABLED
if ( old_control_mode = = AUTOTUNE ) {
autotune_stop ( ) ;
}
# endif
2014-02-11 09:32:44 -04:00
2014-05-03 15:26:58 -03:00
// stop mission when we leave auto mode
if ( old_control_mode = = AUTO ) {
2014-05-15 04:11:17 -03:00
if ( mission . state ( ) = = AP_Mission : : MISSION_RUNNING ) {
mission . stop ( ) ;
}
2014-06-09 16:02:28 -03:00
# if MOUNT == ENABLED
camera_mount . set_mode_to_default ( ) ;
# endif // MOUNT == ENABLED
2014-05-03 15:26:58 -03:00
}
2014-02-11 09:32:44 -04:00
// smooth throttle transition when switching from manual to automatic flight modes
2015-01-21 06:57:02 -04:00
if ( mode_has_manual_throttle ( old_control_mode ) & & ! mode_has_manual_throttle ( new_control_mode ) & & motors . armed ( ) & & ! ap . land_complete ) {
2014-02-11 09:32:44 -04:00
// this assumes all manual flight modes use get_pilot_desired_throttle to translate pilot input to output throttle
2015-05-11 23:24:13 -03:00
set_accel_throttle_I_from_pilot_throttle ( get_pilot_desired_throttle ( channel_throttle - > control_in ) ) ;
2014-02-11 09:32:44 -04:00
}
2015-04-30 03:52:32 -03:00
// cancel any takeoffs in progress
takeoff_stop ( ) ;
2014-07-03 18:07:04 -03:00
# if FRAME_CONFIG == HELI_FRAME
// firmly reset the flybar passthrough to false when exiting acro mode.
if ( old_control_mode = = ACRO ) {
attitude_control . use_flybar_passthrough ( false ) ;
}
2015-05-23 19:57:17 -03:00
// reset RC Passthrough to motors
motors . reset_radio_passthrough ( ) ;
2014-07-03 18:07:04 -03:00
# endif //HELI_FRAME
2014-02-03 04:57:31 -04:00
}
// returns true or false whether mode requires GPS
2015-05-29 23:12:49 -03:00
bool Copter : : mode_requires_GPS ( uint8_t mode ) {
2014-02-03 04:57:31 -04:00
switch ( mode ) {
case AUTO :
case GUIDED :
case LOITER :
case RTL :
case CIRCLE :
case DRIFT :
2014-07-11 02:08:09 -03:00
case POSHOLD :
2015-05-17 00:22:20 -03:00
case BRAKE :
2014-02-03 04:57:31 -04:00
return true ;
default :
return false ;
}
return false ;
}
2015-01-21 06:57:02 -04:00
// mode_has_manual_throttle - returns true if the flight mode has a manual throttle (i.e. pilot directly controls throttle)
2015-05-29 23:12:49 -03:00
bool Copter : : mode_has_manual_throttle ( uint8_t mode ) {
2014-02-03 04:57:31 -04:00
switch ( mode ) {
case ACRO :
case STABILIZE :
return true ;
default :
return false ;
}
return false ;
}
2014-10-11 04:05:32 -03:00
// 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
2015-05-29 23:12:49 -03:00
bool Copter : : mode_allows_arming ( uint8_t mode , bool arming_from_gcs ) {
2015-01-21 06:57:02 -04:00
if ( mode_has_manual_throttle ( mode ) | | mode = = LOITER | | mode = = ALT_HOLD | | mode = = POSHOLD | | ( arming_from_gcs & & mode = = GUIDED ) ) {
2014-10-10 06:26:43 -03:00
return true ;
}
return false ;
}
2015-03-06 02:33:25 -04:00
// notify_flight_mode - sets notify object based on flight mode. Only used for OreoLED notify device
2015-05-29 23:12:49 -03:00
void Copter : : notify_flight_mode ( uint8_t mode ) {
2015-03-06 02:33:25 -04:00
switch ( mode ) {
case AUTO :
case GUIDED :
case RTL :
case CIRCLE :
case LAND :
// autopilot modes
AP_Notify : : flags . autopilot_mode = true ;
break ;
default :
// all other are manual flight modes
AP_Notify : : flags . autopilot_mode = false ;
break ;
}
}
2014-02-03 04:57:31 -04:00
//
// print_flight_mode - prints flight mode to serial port.
//
2015-05-29 23:12:49 -03:00
void Copter : : print_flight_mode ( AP_HAL : : BetterStream * port , uint8_t mode )
2014-02-03 04:57:31 -04:00
{
switch ( mode ) {
case STABILIZE :
port - > print_P ( PSTR ( " STABILIZE " ) ) ;
break ;
case ACRO :
port - > print_P ( PSTR ( " ACRO " ) ) ;
break ;
case ALT_HOLD :
port - > print_P ( PSTR ( " ALT_HOLD " ) ) ;
break ;
case AUTO :
port - > print_P ( PSTR ( " AUTO " ) ) ;
break ;
case GUIDED :
port - > print_P ( PSTR ( " GUIDED " ) ) ;
break ;
case LOITER :
port - > print_P ( PSTR ( " LOITER " ) ) ;
break ;
case RTL :
port - > print_P ( PSTR ( " RTL " ) ) ;
break ;
case CIRCLE :
port - > print_P ( PSTR ( " CIRCLE " ) ) ;
break ;
case LAND :
port - > print_P ( PSTR ( " LAND " ) ) ;
break ;
case OF_LOITER :
port - > print_P ( PSTR ( " OF_LOITER " ) ) ;
break ;
case DRIFT :
port - > print_P ( PSTR ( " DRIFT " ) ) ;
break ;
case SPORT :
port - > print_P ( PSTR ( " SPORT " ) ) ;
break ;
case FLIP :
port - > print_P ( PSTR ( " FLIP " ) ) ;
break ;
case AUTOTUNE :
port - > print_P ( PSTR ( " AUTOTUNE " ) ) ;
break ;
2014-07-11 02:08:09 -03:00
case POSHOLD :
port - > print_P ( PSTR ( " POSHOLD " ) ) ;
2014-04-04 11:14:30 -03:00
break ;
2015-05-17 00:22:20 -03:00
case BRAKE :
port - > print_P ( PSTR ( " BRAKE " ) ) ;
break ;
2014-02-03 04:57:31 -04:00
default :
port - > printf_P ( PSTR ( " Mode(%u) " ) , ( unsigned ) mode ) ;
break ;
}
}
2014-02-03 09:03:43 -04:00