2015-05-29 23:12:49 -03:00
# include "Copter.h"
2014-02-03 04:57:31 -04:00
/*
2016-07-25 15:45:29 -03:00
* High level calls to set and update flight modes logic for individual
* flight modes is in control_acro . cpp , control_stabilize . cpp , etc
2014-02-03 04:57:31 -04:00
*/
2018-02-07 22:21:09 -04:00
/*
constructor for Mode object
*/
Copter : : Mode : : Mode ( void ) :
g ( copter . g ) ,
g2 ( copter . g2 ) ,
wp_nav ( copter . wp_nav ) ,
pos_control ( copter . pos_control ) ,
inertial_nav ( copter . inertial_nav ) ,
ahrs ( copter . ahrs ) ,
attitude_control ( copter . attitude_control ) ,
motors ( copter . motors ) ,
channel_roll ( copter . channel_roll ) ,
channel_pitch ( copter . channel_pitch ) ,
channel_throttle ( copter . channel_throttle ) ,
channel_yaw ( copter . channel_yaw ) ,
G_Dt ( copter . G_Dt ) ,
ap ( copter . ap ) ,
takeoff_state ( copter . takeoff_state ) ,
ekfGndSpdLimit ( copter . ekfGndSpdLimit ) ,
ekfNavVelGainScaler ( copter . ekfNavVelGainScaler ) ,
# if FRAME_CONFIG == HELI_FRAME
heli_flags ( copter . heli_flags ) ,
# endif
auto_yaw_mode ( copter . auto_yaw_mode )
{ } ;
2016-03-23 00:27:05 -03:00
// return the static controller object corresponding to supplied mode
2017-12-11 01:43:27 -04:00
Copter : : Mode * Copter : : mode_from_mode_num ( const uint8_t mode )
2014-02-03 04:57:31 -04:00
{
2017-12-10 23:51:13 -04:00
Copter : : Mode * ret = nullptr ;
2016-03-21 01:33:42 -03:00
2016-10-10 00:11:14 -03:00
switch ( mode ) {
2014-02-03 04:57:31 -04:00
case ACRO :
2017-12-11 01:43:27 -04:00
ret = & mode_acro ;
2014-02-03 04:57:31 -04:00
break ;
case STABILIZE :
2017-12-11 01:43:27 -04:00
ret = & mode_stabilize ;
2014-02-03 04:57:31 -04:00
break ;
case ALT_HOLD :
2017-12-11 01:43:27 -04:00
ret = & mode_althold ;
2014-02-03 04:57:31 -04:00
break ;
case AUTO :
2017-12-11 01:43:27 -04:00
ret = & mode_auto ;
2014-02-03 04:57:31 -04:00
break ;
case CIRCLE :
2017-12-11 01:43:27 -04:00
ret = & mode_circle ;
2014-02-03 04:57:31 -04:00
break ;
case LOITER :
2017-12-11 01:43:27 -04:00
ret = & mode_loiter ;
2014-02-03 04:57:31 -04:00
break ;
case GUIDED :
2017-12-11 01:43:27 -04:00
ret = & mode_guided ;
2014-02-03 04:57:31 -04:00
break ;
case LAND :
2017-12-11 01:43:27 -04:00
ret = & mode_land ;
2014-02-03 04:57:31 -04:00
break ;
case RTL :
2017-12-11 01:43:27 -04:00
ret = & mode_rtl ;
2014-02-03 04:57:31 -04:00
break ;
case DRIFT :
2017-12-11 01:43:27 -04:00
ret = & mode_drift ;
2014-02-03 04:57:31 -04:00
break ;
case SPORT :
2017-12-11 01:43:27 -04:00
ret = & mode_sport ;
2014-02-03 04:57:31 -04:00
break ;
case FLIP :
2017-12-11 01:43:27 -04:00
ret = & mode_flip ;
2014-02-03 04:57:31 -04:00
break ;
# if AUTOTUNE_ENABLED == ENABLED
case AUTOTUNE :
2017-12-11 01:43:27 -04:00
ret = & mode_autotune ;
2014-02-03 04:57:31 -04:00
break ;
# endif
2014-07-11 02:08:09 -03:00
case POSHOLD :
2017-12-11 01:43:27 -04:00
ret = & mode_poshold ;
2014-04-04 11:14:30 -03:00
break ;
2015-05-17 00:22:20 -03:00
case BRAKE :
2017-12-11 01:43:27 -04:00
ret = & mode_brake ;
2015-04-22 18:10:30 -03:00
break ;
2015-12-18 05:46:56 -04:00
case THROW :
2017-12-11 01:43:27 -04:00
ret = & mode_throw ;
2015-12-18 05:46:56 -04:00
break ;
2016-07-21 09:44:09 -03:00
case AVOID_ADSB :
2017-12-11 01:43:27 -04:00
ret = & mode_avoid_adsb ;
2016-07-21 09:44:09 -03:00
break ;
2016-08-01 05:44:12 -03:00
case GUIDED_NOGPS :
2017-12-11 01:43:27 -04:00
ret = & mode_guided_nogps ;
2016-08-01 05:44:12 -03:00
break ;
2017-09-08 23:45:31 -03:00
case SMART_RTL :
2017-12-11 01:43:27 -04:00
ret = & mode_smartrtl ;
2017-07-26 14:14:40 -03:00
break ;
2018-01-18 02:12:29 -04:00
# if OPTFLOW == ENABLED
case FLOWHOLD :
2018-02-07 22:21:09 -04:00
ret = ( Copter : : Mode * ) g2 . mode_flowhold_ptr ;
2018-01-18 02:12:29 -04:00
break ;
# endif
2014-02-03 04:57:31 -04:00
default :
break ;
}
2016-03-23 00:27:05 -03:00
return ret ;
}
// 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 successfully 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 Copter : : set_mode ( control_mode_t mode , mode_reason_t reason )
{
// return immediately if we are already in the desired mode
if ( mode = = control_mode ) {
control_mode_reason = reason ;
return true ;
}
2017-12-11 01:43:27 -04:00
Copter : : Mode * new_flightmode = mode_from_mode_num ( mode ) ;
2016-03-23 00:27:05 -03:00
if ( new_flightmode = = nullptr ) {
gcs ( ) . send_text ( MAV_SEVERITY_WARNING , " No such mode " ) ;
Log_Write_Error ( ERROR_SUBSYSTEM_FLIGHT_MODE , mode ) ;
return false ;
}
bool ignore_checks = ! motors - > armed ( ) ; // allow switching to any mode if disarmed. We rely on the arming check to perform
2017-09-19 22:18:49 -03:00
# if FRAME_CONFIG == HELI_FRAME
2016-03-23 00:27:05 -03:00
// do not allow helis to enter a non-manual throttle mode if the
// rotor runup is not complete
2017-12-05 19:56:38 -04:00
if ( ! ignore_checks & & ! new_flightmode - > has_manual_throttle ( ) & & ! motors - > rotor_runup_complete ( ) ) {
2017-12-12 19:02:51 -04:00
gcs ( ) . send_text ( MAV_SEVERITY_WARNING , " Flight mode change failed " ) ;
Log_Write_Error ( ERROR_SUBSYSTEM_FLIGHT_MODE , mode ) ;
2016-03-23 00:27:05 -03:00
return false ;
}
2017-09-19 22:18:49 -03:00
# endif
2016-01-26 20:08:45 -04:00
2017-12-12 19:02:51 -04:00
if ( ! new_flightmode - > init ( ignore_checks ) ) {
gcs ( ) . send_text ( MAV_SEVERITY_WARNING , " Flight mode change failed " ) ;
Log_Write_Error ( ERROR_SUBSYSTEM_FLIGHT_MODE , mode ) ;
return false ;
}
2016-03-23 00:27:05 -03:00
// perform any cleanup required by previous flight mode
2017-12-05 19:52:54 -04:00
exit_mode ( flightmode , new_flightmode ) ;
2016-03-23 00:27:05 -03:00
// update flight mode
flightmode = new_flightmode ;
control_mode = mode ;
control_mode_reason = reason ;
DataFlash . Log_Write_Mode ( control_mode ) ;
2014-04-26 23:09:15 -03:00
2017-11-10 01:13:52 -04:00
adsb . set_is_auto_mode ( ( mode = = AUTO ) | | ( mode = = RTL ) | | ( mode = = GUIDED ) ) ;
2016-07-21 02:43:46 -03:00
2014-04-26 23:09:15 -03:00
# if AC_FENCE == ENABLED
2017-11-10 01:13:52 -04:00
// 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
2016-03-23 00:27:05 -03:00
fence . manual_recovery_start ( ) ;
2014-04-26 23:09:15 -03:00
# endif
2017-11-10 01:13:52 -04:00
2016-08-09 19:27:47 -03:00
# if FRSKY_TELEM_ENABLED == ENABLED
2017-11-10 01:13:52 -04:00
frsky_telemetry . update_control_mode ( control_mode ) ;
2016-08-09 19:27:47 -03:00
# endif
2017-10-24 07:44:57 -03:00
# if CAMERA == ENABLED
2017-11-10 01:13:52 -04:00
camera . set_is_auto_mode ( control_mode = = AUTO ) ;
2017-10-24 07:44:57 -03:00
# endif
2014-02-03 04:57:31 -04:00
2015-03-06 02:33:25 -04:00
// update notify object
2016-03-23 00:27:05 -03:00
notify_flight_mode ( ) ;
2015-03-06 02:33:25 -04:00
2016-03-23 00:27:05 -03:00
// return success
return true ;
2014-02-03 04:57:31 -04:00
}
// 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
2016-03-24 02:01:40 -03:00
flightmode - > run ( ) ;
2014-02-03 04:57:31 -04:00
}
// exit_mode - high level call to organise cleanup as a flight mode is exited
2017-12-10 23:51:13 -04:00
void Copter : : exit_mode ( Copter : : Mode * & old_flightmode ,
Copter : : Mode * & new_flightmode )
2014-02-03 04:57:31 -04:00
{
# if AUTOTUNE_ENABLED == ENABLED
2017-12-11 01:43:27 -04:00
if ( old_flightmode = = & mode_autotune ) {
mode_autotune . stop ( ) ;
2014-02-03 04:57:31 -04:00
}
# endif
2014-02-11 09:32:44 -04:00
2014-05-03 15:26:58 -03:00
// stop mission when we leave auto mode
2017-12-11 01:43:27 -04:00
if ( old_flightmode = = & 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
2017-12-05 19:52:54 -04:00
if ( old_flightmode - > has_manual_throttle ( ) & & ! new_flightmode - > has_manual_throttle ( ) & & 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
2016-10-14 03:34:24 -03:00
set_accel_throttle_I_from_pilot_throttle ( ) ;
2014-02-11 09:32:44 -04:00
}
2015-04-30 03:52:32 -03:00
// cancel any takeoffs in progress
takeoff_stop ( ) ;
2017-09-08 23:45:31 -03:00
// call smart_rtl cleanup
2017-12-11 01:43:27 -04:00
if ( old_flightmode = = & mode_smartrtl ) {
mode_smartrtl . exit ( ) ;
2017-07-26 14:14:40 -03:00
}
2014-07-03 18:07:04 -03:00
# if FRAME_CONFIG == HELI_FRAME
// firmly reset the flybar passthrough to false when exiting acro mode.
2017-12-11 01:43:27 -04:00
if ( old_flightmode = = & mode_acro ) {
2017-01-09 03:31:26 -04:00
attitude_control - > use_flybar_passthrough ( false , false ) ;
motors - > set_acro_tail ( false ) ;
2014-07-03 18:07:04 -03:00
}
2015-05-23 19:57:17 -03:00
2015-10-12 22:05:49 -03:00
// if we are changing from a mode that did not use manual throttle,
// stab col ramp value should be pre-loaded to the correct value to avoid a twitch
// heli_stab_col_ramp should really only be active switching between Stabilize and Acro modes
2017-12-05 19:52:54 -04:00
if ( ! old_flightmode - > has_manual_throttle ( ) ) {
2017-12-11 01:43:27 -04:00
if ( new_flightmode = = & mode_stabilize ) {
2015-10-12 22:05:49 -03:00
input_manager . set_stab_col_ramp ( 1.0 ) ;
2017-12-11 01:43:27 -04:00
} else if ( new_flightmode = = & mode_acro ) {
2015-10-12 22:05:49 -03:00
input_manager . set_stab_col_ramp ( 0.0 ) ;
}
}
2014-07-03 18:07:04 -03:00
# endif //HELI_FRAME
2014-02-03 04:57:31 -04:00
}
2016-03-20 22:19:11 -03:00
// notify_flight_mode - sets notify object based on current flight mode. Only used for OreoLED notify device
2016-03-24 02:01:40 -03:00
void Copter : : notify_flight_mode ( ) {
AP_Notify : : flags . autopilot_mode = flightmode - > is_autopilot ( ) ;
2018-01-06 01:53:48 -04:00
AP_Notify : : flags . flight_mode = control_mode ;
2016-03-24 02:01:40 -03:00
notify . set_flight_mode_str ( flightmode - > name4 ( ) ) ;
2015-03-06 02:33:25 -04:00
}
2017-12-05 21:28:32 -04:00
2017-12-10 23:51:13 -04:00
void Copter : : Mode : : update_navigation ( )
2017-12-05 21:28:32 -04:00
{
// run autopilot to make high level decisions about control modes
run_autopilot ( ) ;
}
2017-12-12 06:53:56 -04:00
bool Copter : : Mode : : takeoff_triggered ( const float target_climb_rate ) const
{
if ( ! ap . land_complete ) {
// can't take off if we're already flying
return false ;
}
if ( target_climb_rate < = 0.0f ) {
// can't takeoff unless we want to go up...
return false ;
}
# if FRAME_CONFIG == HELI_FRAME
if ( ! motors - > rotor_runup_complete ( ) ) {
// hold heli on the ground until rotor speed runup has finished
return false ;
}
# endif
return true ;
}
2016-11-17 01:46:52 -04:00
void Copter : : Mode : : zero_throttle_and_relax_ac ( )
{
2017-12-21 19:15:14 -04:00
# if FRAME_CONFIG == HELI_FRAME
// Helicopters always stabilize roll/pitch/yaw
attitude_control - > input_euler_angle_roll_pitch_euler_rate_yaw ( 0.0f , 0.0f , 0.0f , get_smoothing_gain ( ) ) ;
2018-02-07 22:21:09 -04:00
attitude_control - > set_throttle_out ( 0.0f , false , copter . g . throttle_filt ) ;
2016-11-17 01:46:52 -04:00
# else
2017-12-21 19:15:14 -04:00
motors - > set_desired_spool_state ( AP_Motors : : DESIRED_SPIN_WHEN_ARMED ) ;
// multicopters do not stabilize roll/pitch/yaw when disarmed
2018-02-07 22:21:09 -04:00
attitude_control - > set_throttle_out_unstabilized ( 0.0f , true , copter . g . throttle_filt ) ;
2016-11-17 01:46:52 -04:00
# endif
}
2018-02-07 22:21:09 -04:00
// pass-through functions to reduce code churn on conversion;
// these are candidates for moving into the Mode base
// class.
void Copter : : Mode : : get_pilot_desired_lean_angles ( float roll_in , float pitch_in , float & roll_out , float & pitch_out , float angle_max )
{
copter . get_pilot_desired_lean_angles ( roll_in , pitch_in , roll_out , pitch_out , angle_max ) ;
}
float Copter : : Mode : : get_surface_tracking_climb_rate ( int16_t target_rate , float current_alt_target , float dt )
{
return copter . get_surface_tracking_climb_rate ( target_rate , current_alt_target , dt ) ;
}
float Copter : : Mode : : get_pilot_desired_yaw_rate ( int16_t stick_angle )
{
return copter . get_pilot_desired_yaw_rate ( stick_angle ) ;
}
float Copter : : Mode : : get_pilot_desired_climb_rate ( float throttle_control )
{
return copter . get_pilot_desired_climb_rate ( throttle_control ) ;
}
float Copter : : Mode : : get_pilot_desired_throttle ( int16_t throttle_control , float thr_mid )
{
return copter . get_pilot_desired_throttle ( throttle_control , thr_mid ) ;
}
float Copter : : Mode : : get_non_takeoff_throttle ( )
{
return copter . get_non_takeoff_throttle ( ) ;
}
void Copter : : Mode : : update_simple_mode ( void ) {
copter . update_simple_mode ( ) ;
}
float Copter : : Mode : : get_smoothing_gain ( ) {
return copter . get_smoothing_gain ( ) ;
}
bool Copter : : Mode : : set_mode ( control_mode_t mode , mode_reason_t reason )
{
return copter . set_mode ( mode , reason ) ;
}
void Copter : : Mode : : set_land_complete ( bool b )
{
return copter . set_land_complete ( b ) ;
}
GCS_Copter & Copter : : Mode : : gcs ( )
{
return copter . gcs ( ) ;
}
void Copter : : Mode : : Log_Write_Event ( uint8_t id )
{
return copter . Log_Write_Event ( id ) ;
}
void Copter : : Mode : : set_throttle_takeoff ( )
{
return copter . set_throttle_takeoff ( ) ;
}
void Copter : : Mode : : set_auto_yaw_mode ( uint8_t yaw_mode )
{
return copter . set_auto_yaw_mode ( yaw_mode ) ;
}
void Copter : : Mode : : set_auto_yaw_rate ( float turn_rate_cds )
{
return copter . set_auto_yaw_rate ( turn_rate_cds ) ;
}
void Copter : : Mode : : set_auto_yaw_look_at_heading ( float angle_deg , float turn_rate_dps , int8_t direction , bool relative_angle )
{
return copter . set_auto_yaw_look_at_heading ( angle_deg , turn_rate_dps , direction , relative_angle ) ;
}
void Copter : : Mode : : takeoff_timer_start ( float alt_cm )
{
return copter . takeoff_timer_start ( alt_cm ) ;
}
void Copter : : Mode : : takeoff_stop ( )
{
return copter . takeoff_stop ( ) ;
}
void Copter : : Mode : : takeoff_get_climb_rates ( float & pilot_climb_rate , float & takeoff_climb_rate )
{
return copter . takeoff_get_climb_rates ( pilot_climb_rate , takeoff_climb_rate ) ;
}
float Copter : : Mode : : get_auto_heading ( )
{
return copter . get_auto_heading ( ) ;
}
float Copter : : Mode : : get_auto_yaw_rate_cds ( )
{
return copter . get_auto_yaw_rate_cds ( ) ;
}
float Copter : : Mode : : get_avoidance_adjusted_climbrate ( float target_rate )
{
return copter . get_avoidance_adjusted_climbrate ( target_rate ) ;
}
uint16_t Copter : : Mode : : get_pilot_speed_dn ( )
{
return copter . get_pilot_speed_dn ( ) ;
}