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
*/
2019-05-09 23:18:49 -03:00
Mode : : Mode ( void ) :
2018-02-07 22:21:09 -04:00
g ( copter . g ) ,
g2 ( copter . g2 ) ,
wp_nav ( copter . wp_nav ) ,
2018-03-27 23:13:37 -03:00
loiter_nav ( copter . loiter_nav ) ,
2018-02-07 22:21:09 -04:00
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 ) ,
2019-05-09 23:18:49 -03:00
G_Dt ( copter . G_Dt )
2018-02-07 22:21:09 -04:00
{ } ;
2023-10-18 23:34:30 -03:00
# if AC_PAYLOAD_PLACE_ENABLED
2023-09-27 22:24:36 -03:00
PayloadPlace Mode : : payload_place ;
2023-10-18 23:34:30 -03:00
# endif
2023-09-27 22:24:36 -03:00
2016-03-23 00:27:05 -03:00
// return the static controller object corresponding to supplied mode
2019-09-07 20:33:56 -03:00
Mode * Copter : : mode_from_mode_num ( const Mode : : Number mode )
2014-02-03 04:57:31 -04:00
{
2019-05-09 23:18:49 -03:00
Mode * ret = nullptr ;
2016-03-21 01:33:42 -03:00
2016-10-10 00:11:14 -03:00
switch ( mode ) {
2018-03-14 17:14:49 -03:00
# if MODE_ACRO_ENABLED == ENABLED
2019-09-07 20:33:56 -03:00
case Mode : : Number : : ACRO :
2017-12-11 01:43:27 -04:00
ret = & mode_acro ;
2014-02-03 04:57:31 -04:00
break ;
2018-03-14 17:14:49 -03:00
# endif
2014-02-03 04:57:31 -04:00
2019-09-07 20:33:56 -03:00
case Mode : : Number : : STABILIZE :
2017-12-11 01:43:27 -04:00
ret = & mode_stabilize ;
2014-02-03 04:57:31 -04:00
break ;
2019-09-07 20:33:56 -03:00
case Mode : : Number : : ALT_HOLD :
2017-12-11 01:43:27 -04:00
ret = & mode_althold ;
2014-02-03 04:57:31 -04:00
break ;
2018-02-21 22:06:07 -04:00
# if MODE_AUTO_ENABLED == ENABLED
2019-09-07 20:33:56 -03:00
case Mode : : Number : : AUTO :
2017-12-11 01:43:27 -04:00
ret = & mode_auto ;
2014-02-03 04:57:31 -04:00
break ;
2018-02-21 22:06:07 -04:00
# endif
2014-02-03 04:57:31 -04:00
2018-02-23 05:51:17 -04:00
# if MODE_CIRCLE_ENABLED == ENABLED
2019-09-07 20:33:56 -03:00
case Mode : : Number : : CIRCLE :
2017-12-11 01:43:27 -04:00
ret = & mode_circle ;
2014-02-03 04:57:31 -04:00
break ;
2018-02-23 05:51:17 -04:00
# endif
2014-02-03 04:57:31 -04:00
2018-02-22 01:23:35 -04:00
# if MODE_LOITER_ENABLED == ENABLED
2019-09-07 20:33:56 -03:00
case Mode : : Number : : LOITER :
2017-12-11 01:43:27 -04:00
ret = & mode_loiter ;
2014-02-03 04:57:31 -04:00
break ;
2018-02-22 01:23:35 -04:00
# endif
2014-02-03 04:57:31 -04:00
2018-02-23 00:09:07 -04:00
# if MODE_GUIDED_ENABLED == ENABLED
2019-09-07 20:33:56 -03:00
case Mode : : Number : : GUIDED :
2017-12-11 01:43:27 -04:00
ret = & mode_guided ;
2014-02-03 04:57:31 -04:00
break ;
2018-02-23 00:09:07 -04:00
# endif
2014-02-03 04:57:31 -04:00
2019-09-07 20:33:56 -03:00
case Mode : : Number : : LAND :
2017-12-11 01:43:27 -04:00
ret = & mode_land ;
2014-02-03 04:57:31 -04:00
break ;
2018-02-23 01:33:49 -04:00
# if MODE_RTL_ENABLED == ENABLED
2019-09-07 20:33:56 -03:00
case Mode : : Number : : RTL :
2017-12-11 01:43:27 -04:00
ret = & mode_rtl ;
2014-02-03 04:57:31 -04:00
break ;
2018-02-23 01:33:49 -04:00
# endif
2014-02-03 04:57:31 -04:00
2018-02-22 23:55:51 -04:00
# if MODE_DRIFT_ENABLED == ENABLED
2019-09-07 20:33:56 -03:00
case Mode : : Number : : DRIFT :
2017-12-11 01:43:27 -04:00
ret = & mode_drift ;
2014-02-03 04:57:31 -04:00
break ;
2018-02-22 23:55:51 -04:00
# endif
2014-02-03 04:57:31 -04:00
2018-02-22 23:48:02 -04:00
# if MODE_SPORT_ENABLED == ENABLED
2019-09-07 20:33:56 -03:00
case Mode : : Number : : SPORT :
2017-12-11 01:43:27 -04:00
ret = & mode_sport ;
2014-02-03 04:57:31 -04:00
break ;
2018-02-22 23:48:02 -04:00
# endif
2014-02-03 04:57:31 -04:00
2018-11-25 19:47:55 -04:00
# if MODE_FLIP_ENABLED == ENABLED
2019-09-07 20:33:56 -03:00
case Mode : : Number : : FLIP :
2017-12-11 01:43:27 -04:00
ret = & mode_flip ;
2014-02-03 04:57:31 -04:00
break ;
2018-11-25 19:47:55 -04:00
# endif
2014-02-03 04:57:31 -04:00
# if AUTOTUNE_ENABLED == ENABLED
2019-09-07 20:33:56 -03:00
case Mode : : Number : : AUTOTUNE :
2017-12-11 01:43:27 -04:00
ret = & mode_autotune ;
2014-02-03 04:57:31 -04:00
break ;
# endif
2018-02-21 23:45:02 -04:00
# if MODE_POSHOLD_ENABLED == ENABLED
2019-09-07 20:33:56 -03:00
case Mode : : Number : : POSHOLD :
2017-12-11 01:43:27 -04:00
ret = & mode_poshold ;
2014-04-04 11:14:30 -03:00
break ;
2018-02-21 23:45:02 -04:00
# endif
2014-04-04 11:14:30 -03:00
2018-02-23 01:40:29 -04:00
# if MODE_BRAKE_ENABLED == ENABLED
2019-09-07 20:33:56 -03:00
case Mode : : Number : : BRAKE :
2017-12-11 01:43:27 -04:00
ret = & mode_brake ;
2015-04-22 18:10:30 -03:00
break ;
2018-02-23 01:40:29 -04:00
# endif
2015-04-22 18:10:30 -03:00
2018-03-14 17:16:16 -03:00
# if MODE_THROW_ENABLED == ENABLED
2019-09-07 20:33:56 -03:00
case Mode : : Number : : THROW :
2017-12-11 01:43:27 -04:00
ret = & mode_throw ;
2015-12-18 05:46:56 -04:00
break ;
2018-03-14 17:16:16 -03:00
# endif
2015-12-18 05:46:56 -04:00
2020-09-19 05:37:52 -03:00
# if HAL_ADSB_ENABLED
2019-09-07 20:33:56 -03:00
case Mode : : Number : : AVOID_ADSB :
2017-12-11 01:43:27 -04:00
ret = & mode_avoid_adsb ;
2016-07-21 09:44:09 -03:00
break ;
2018-02-16 10:21:55 -04:00
# endif
2016-07-21 09:44:09 -03:00
2018-02-23 03:54:34 -04:00
# if MODE_GUIDED_NOGPS_ENABLED == ENABLED
2019-09-07 20:33:56 -03:00
case Mode : : Number : : GUIDED_NOGPS :
2017-12-11 01:43:27 -04:00
ret = & mode_guided_nogps ;
2016-08-01 05:44:12 -03:00
break ;
2018-02-23 03:54:34 -04:00
# endif
2016-08-01 05:44:12 -03:00
2018-02-21 23:58:28 -04:00
# if MODE_SMARTRTL_ENABLED == ENABLED
2019-09-07 20:33:56 -03:00
case Mode : : Number : : SMART_RTL :
2017-12-11 01:43:27 -04:00
ret = & mode_smartrtl ;
2017-07-26 14:14:40 -03:00
break ;
2018-02-21 23:58:28 -04:00
# endif
2017-07-26 14:14:40 -03:00
2022-08-16 23:18:38 -03:00
# if MODE_FLOWHOLD_ENABLED == ENABLED
2019-09-07 20:33:56 -03:00
case Mode : : Number : : FLOWHOLD :
2019-05-09 23:18:49 -03:00
ret = ( Mode * ) g2 . mode_flowhold_ptr ;
2018-01-18 02:12:29 -04:00
break ;
# endif
2018-02-06 02:16:09 -04:00
# if MODE_FOLLOW_ENABLED == ENABLED
2019-09-07 20:33:56 -03:00
case Mode : : Number : : FOLLOW :
2018-02-05 22:44:05 -04:00
ret = & mode_follow ;
break ;
2018-02-06 02:16:09 -04:00
# endif
2018-02-05 22:44:05 -04:00
2018-09-07 01:23:33 -03:00
# if MODE_ZIGZAG_ENABLED == ENABLED
2019-09-07 20:33:56 -03:00
case Mode : : Number : : ZIGZAG :
2018-09-07 01:23:33 -03:00
ret = & mode_zigzag ;
break ;
# endif
2019-07-29 04:55:40 -03:00
# if MODE_SYSTEMID_ENABLED == ENABLED
case Mode : : Number : : SYSTEMID :
ret = ( Mode * ) g2 . mode_systemid_ptr ;
break ;
# endif
2019-11-28 16:21:07 -04:00
# if MODE_AUTOROTATE_ENABLED == ENABLED
case Mode : : Number : : AUTOROTATE :
ret = & mode_autorotate ;
break ;
# endif
2021-07-27 16:51:19 -03:00
# if MODE_TURTLE_ENABLED == ENABLED
case Mode : : Number : : TURTLE :
ret = & mode_turtle ;
break ;
# endif
2014-02-03 04:57:31 -04:00
default :
break ;
}
2016-03-23 00:27:05 -03:00
return ret ;
}
2020-07-06 01:32:32 -03:00
// called when an attempt to change into a mode is unsuccessful:
void Copter : : mode_change_failed ( const Mode * mode , const char * reason )
{
gcs ( ) . send_text ( MAV_SEVERITY_WARNING , " Mode change to %s failed: %s " , mode - > name ( ) , reason ) ;
2023-07-13 21:58:09 -03:00
LOGGER_WRITE_ERROR ( LogErrorSubsystem : : FLIGHT_MODE , LogErrorCode ( mode - > mode_number ( ) ) ) ;
2021-08-03 21:30:10 -03:00
// make sad noise
if ( copter . ap . initialised ) {
AP_Notify : : events . user_mode_change_failed = 1 ;
}
2020-07-06 01:32:32 -03:00
}
2023-06-18 12:31:03 -03:00
// Check if this mode can be entered from the GCS
bool Copter : : gcs_mode_enabled ( const Mode : : Number mode_num )
{
// List of modes that can be blocked, index is bit number in parameter bitmask
static const uint8_t mode_list [ ] {
( uint8_t ) Mode : : Number : : STABILIZE ,
( uint8_t ) Mode : : Number : : ACRO ,
( uint8_t ) Mode : : Number : : ALT_HOLD ,
( uint8_t ) Mode : : Number : : AUTO ,
( uint8_t ) Mode : : Number : : GUIDED ,
( uint8_t ) Mode : : Number : : LOITER ,
( uint8_t ) Mode : : Number : : CIRCLE ,
( uint8_t ) Mode : : Number : : DRIFT ,
( uint8_t ) Mode : : Number : : SPORT ,
( uint8_t ) Mode : : Number : : FLIP ,
( uint8_t ) Mode : : Number : : AUTOTUNE ,
( uint8_t ) Mode : : Number : : POSHOLD ,
( uint8_t ) Mode : : Number : : BRAKE ,
( uint8_t ) Mode : : Number : : THROW ,
( uint8_t ) Mode : : Number : : AVOID_ADSB ,
( uint8_t ) Mode : : Number : : GUIDED_NOGPS ,
( uint8_t ) Mode : : Number : : SMART_RTL ,
( uint8_t ) Mode : : Number : : FLOWHOLD ,
( uint8_t ) Mode : : Number : : FOLLOW ,
( uint8_t ) Mode : : Number : : ZIGZAG ,
( uint8_t ) Mode : : Number : : SYSTEMID ,
( uint8_t ) Mode : : Number : : AUTOROTATE ,
( uint8_t ) Mode : : Number : : AUTO_RTL ,
( uint8_t ) Mode : : Number : : TURTLE
} ;
if ( ! block_GCS_mode_change ( ( uint8_t ) mode_num , mode_list , ARRAY_SIZE ( mode_list ) ) ) {
return true ;
}
// Mode disabled, try and grab a mode name to give a better warning.
Mode * new_flightmode = mode_from_mode_num ( mode_num ) ;
if ( new_flightmode ! = nullptr ) {
mode_change_failed ( new_flightmode , " GCS entry disabled (FLTMODE_GCSBLOCK) " ) ;
} else {
notify_no_such_mode ( ( uint8_t ) mode_num ) ;
}
return false ;
}
2016-03-23 00:27:05 -03:00
// 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
2019-10-17 00:49:22 -03:00
bool Copter : : set_mode ( Mode : : Number mode , ModeReason reason )
2016-03-23 00:27:05 -03:00
{
2021-08-03 21:30:10 -03:00
// update last reason
const ModeReason last_reason = _last_reason ;
_last_reason = reason ;
2016-03-23 00:27:05 -03:00
// return immediately if we are already in the desired mode
2020-01-30 03:29:36 -04:00
if ( mode = = flightmode - > mode_number ( ) ) {
2016-03-23 00:27:05 -03:00
control_mode_reason = reason ;
2022-06-15 00:08:53 -03:00
// set yaw rate time constant during autopilot startup
if ( reason = = ModeReason : : INITIALISED & & mode = = Mode : : Number : : STABILIZE ) {
attitude_control - > set_yaw_rate_tc ( g2 . command_model_pilot . get_rate_tc ( ) ) ;
}
2021-08-03 21:30:10 -03:00
// make happy noise
if ( copter . ap . initialised & & ( reason ! = last_reason ) ) {
AP_Notify : : events . user_mode_change = 1 ;
}
2016-03-23 00:27:05 -03:00
return true ;
}
2023-06-18 12:31:03 -03:00
// Check if GCS mode change is disabled via parameter
if ( ( reason = = ModeReason : : GCS_COMMAND ) & & ! gcs_mode_enabled ( mode ) ) {
return false ;
}
2021-07-24 20:25:18 -03:00
# if MODE_AUTO_ENABLED == ENABLED
if ( mode = = Mode : : Number : : AUTO_RTL ) {
// Special case for AUTO RTL, not a true mode, just AUTO in disguise
return mode_auto . jump_to_landing_sequence_auto_RTL ( reason ) ;
}
# endif
2021-08-24 23:04:50 -03:00
Mode * new_flightmode = mode_from_mode_num ( mode ) ;
2016-03-23 00:27:05 -03:00
if ( new_flightmode = = nullptr ) {
2021-08-24 23:04:50 -03:00
notify_no_such_mode ( ( uint8_t ) mode ) ;
2016-03-23 00:27:05 -03:00
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
2019-11-28 21:42:36 -04:00
if ( ! ignore_checks & & ! new_flightmode - > has_manual_throttle ( ) & &
( motors - > get_spool_state ( ) = = AP_Motors : : SpoolState : : SPOOLING_UP | | motors - > get_spool_state ( ) = = AP_Motors : : SpoolState : : SPOOLING_DOWN ) ) {
2019-11-28 16:21:07 -04:00
# if MODE_AUTOROTATE_ENABLED == ENABLED
//if the mode being exited is the autorotation mode allow mode change despite rotor not being at
//full speed. This will reduce altitude loss on bail-outs back to non-manual throttle modes
bool in_autorotation_check = ( flightmode ! = & mode_autorotate | | new_flightmode ! = & mode_autorotate ) ;
# else
bool in_autorotation_check = false ;
# endif
if ( ! in_autorotation_check ) {
2020-07-06 01:32:32 -03:00
mode_change_failed ( new_flightmode , " runup not complete " ) ;
2019-11-28 16:21:07 -04:00
return false ;
}
2016-03-23 00:27:05 -03:00
}
2017-09-19 22:18:49 -03:00
# endif
2016-01-26 20:08:45 -04:00
2019-03-06 01:31:05 -04:00
# if FRAME_CONFIG != HELI_FRAME
// ensure vehicle doesn't leap off the ground if a user switches
// into a manual throttle mode from a non-manual-throttle mode
// (e.g. user arms in guided, raises throttle to 1300 (not enough to
// trigger auto takeoff), then switches into manual):
2019-08-21 00:24:21 -03:00
bool user_throttle = new_flightmode - > has_manual_throttle ( ) ;
# if MODE_DRIFT_ENABLED == ENABLED
if ( new_flightmode = = & mode_drift ) {
user_throttle = true ;
}
# endif
2019-03-06 01:31:05 -04:00
if ( ! ignore_checks & &
ap . land_complete & &
2019-08-21 00:24:21 -03:00
user_throttle & &
2019-03-06 01:31:05 -04:00
! copter . flightmode - > has_manual_throttle ( ) & &
new_flightmode - > get_pilot_desired_throttle ( ) > copter . get_non_takeoff_throttle ( ) ) {
2020-07-06 01:32:32 -03:00
mode_change_failed ( new_flightmode , " throttle too high " ) ;
2019-03-06 01:31:05 -04:00
return false ;
}
# endif
2019-02-27 23:56:36 -04:00
if ( ! ignore_checks & &
new_flightmode - > requires_GPS ( ) & &
! copter . position_ok ( ) ) {
2020-07-06 01:32:32 -03:00
mode_change_failed ( new_flightmode , " requires position " ) ;
2019-02-27 23:56:36 -04:00
return false ;
}
2020-08-18 03:07:21 -03:00
// check for valid altitude if old mode did not require it but new one does
// we only want to stop changing modes if it could make things worse
if ( ! ignore_checks & &
! copter . ekf_alt_ok ( ) & &
flightmode - > has_manual_throttle ( ) & &
! new_flightmode - > has_manual_throttle ( ) ) {
2020-07-06 01:32:32 -03:00
mode_change_failed ( new_flightmode , " need alt estimate " ) ;
2020-08-18 03:07:21 -03:00
return false ;
}
2017-12-12 19:02:51 -04:00
if ( ! new_flightmode - > init ( ignore_checks ) ) {
2022-10-01 23:26:11 -03:00
mode_change_failed ( new_flightmode , " init failed " ) ;
2017-12-12 19:02:51 -04:00
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
2019-11-28 21:42:36 -04:00
// store previous flight mode (only used by tradeheli's autorotation)
2020-01-30 03:29:36 -04:00
prev_control_mode = flightmode - > mode_number ( ) ;
2019-11-28 21:42:36 -04:00
2016-03-23 00:27:05 -03:00
// update flight mode
flightmode = new_flightmode ;
control_mode_reason = reason ;
2023-07-13 21:58:09 -03:00
# if HAL_LOGGING_ENABLED
2020-01-30 03:29:36 -04:00
logger . Write_Mode ( ( uint8_t ) flightmode - > mode_number ( ) , reason ) ;
2023-07-13 21:58:09 -03:00
# endif
2019-06-26 15:21:38 -03:00
gcs ( ) . send_message ( MSG_HEARTBEAT ) ;
2014-04-26 23:09:15 -03:00
2020-09-19 05:37:52 -03:00
# if HAL_ADSB_ENABLED
2019-09-07 20:33:56 -03:00
adsb . set_is_auto_mode ( ( mode = = Mode : : Number : : AUTO ) | | ( mode = = Mode : : Number : : RTL ) | | ( mode = = Mode : : Number : : GUIDED ) ) ;
2018-02-16 10:21:55 -04:00
# endif
2016-07-21 02:43:46 -03:00
2022-07-19 08:33:13 -03:00
# if AP_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
2022-06-02 05:28:26 -03:00
# if AP_CAMERA_ENABLED
2020-01-30 03:29:36 -04:00
camera . set_is_auto_mode ( flightmode - > mode_number ( ) = = Mode : : Number : : AUTO ) ;
2017-10-24 07:44:57 -03:00
# endif
2014-02-03 04:57:31 -04:00
2022-06-15 00:08:53 -03:00
// set rate shaping time constants
# if MODE_ACRO_ENABLED == ENABLED || MODE_SPORT_ENABLED == ENABLED
attitude_control - > set_roll_pitch_rate_tc ( g2 . command_model_acro_rp . get_rate_tc ( ) ) ;
# endif
attitude_control - > set_yaw_rate_tc ( g2 . command_model_pilot . get_rate_tc ( ) ) ;
# if MODE_ACRO_ENABLED == ENABLED || MODE_DRIFT_ENABLED == ENABLED
if ( mode = = Mode : : Number : : ACRO | | mode = = Mode : : Number : : DRIFT ) {
attitude_control - > set_yaw_rate_tc ( g2 . command_model_acro_y . get_rate_tc ( ) ) ;
}
# endif
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
2021-08-03 21:30:10 -03:00
// make happy noise
if ( copter . ap . initialised ) {
AP_Notify : : events . user_mode_change = 1 ;
}
2016-03-23 00:27:05 -03:00
// return success
return true ;
2014-02-03 04:57:31 -04:00
}
2019-10-17 00:49:22 -03:00
bool Copter : : set_mode ( const uint8_t new_mode , const ModeReason reason )
{
static_assert ( sizeof ( Mode : : Number ) = = sizeof ( new_mode ) , " The new mode can't be mapped to the vehicles mode number " ) ;
# ifdef DISALLOW_GCS_MODE_CHANGE_DURING_RC_FAILSAFE
if ( reason = = ModeReason : : GCS_COMMAND & & copter . failsafe . radio ) {
// don't allow mode changes while in radio failsafe
return false ;
}
# endif
2020-07-25 22:39:38 -03:00
return copter . set_mode ( static_cast < Mode : : Number > ( new_mode ) , reason ) ;
2019-10-17 00:49:22 -03:00
}
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
{
2019-06-11 00:13:24 -03:00
surface_tracking . invalidate_for_logging ( ) ; // invalidate surface tracking alt, flight mode will set to true if used
2018-06-05 05:21:09 -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
2019-05-09 23:18:49 -03:00
void Copter : : exit_mode ( Mode * & old_flightmode ,
Mode * & new_flightmode )
2014-02-03 04:57:31 -04: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
2017-12-12 06:34:49 -04:00
old_flightmode - > takeoff_stop ( ) ;
2015-04-30 03:52:32 -03:00
2021-04-20 09:36:36 -03:00
// perform cleanup required for each flight mode
old_flightmode - > exit ( ) ;
2020-06-16 17:01:19 -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 ( ) ;
2020-01-30 03:29:36 -04:00
AP_Notify : : flags . flight_mode = ( uint8_t ) flightmode - > mode_number ( ) ;
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
2018-03-13 21:23:30 -03:00
// get_pilot_desired_angle - transform pilot's roll or pitch input into a desired lean angle
// returns desired angle in centi-degrees
2022-03-23 18:55:13 -03:00
void Mode : : get_pilot_desired_lean_angles ( float & roll_out_cd , float & pitch_out_cd , float angle_max_cd , float angle_limit_cd ) const
2018-03-13 21:23:30 -03:00
{
2019-09-13 21:56:36 -03:00
// throttle failsafe check
if ( copter . failsafe . radio | | ! copter . ap . rc_receiver_present ) {
2022-03-23 18:55:13 -03:00
roll_out_cd = 0.0 ;
pitch_out_cd = 0.0 ;
2019-09-13 21:56:36 -03:00
return ;
}
2018-03-18 08:06:54 -03:00
2022-04-22 23:29:38 -03:00
//transform pilot's normalised roll or pitch stick input into a roll and pitch euler angle command
float roll_out_deg ;
float pitch_out_deg ;
rc_input_to_roll_pitch ( channel_roll - > get_control_in ( ) * ( 1.0 / ROLL_PITCH_YAW_INPUT_MAX ) , channel_pitch - > get_control_in ( ) * ( 1.0 / ROLL_PITCH_YAW_INPUT_MAX ) , angle_max_cd * 0.01 , angle_limit_cd * 0.01 , roll_out_deg , pitch_out_deg ) ;
2022-04-02 04:43:06 -03:00
// Convert to centi-degrees
2022-04-22 23:29:38 -03:00
roll_out_cd = roll_out_deg * 100.0 ;
pitch_out_cd = pitch_out_deg * 100.0 ;
2018-03-13 21:23:30 -03:00
}
2022-02-01 23:40:27 -04:00
// transform pilot's roll or pitch input into a desired velocity
Vector2f Mode : : get_pilot_desired_velocity ( float vel_max ) const
{
Vector2f vel ;
// throttle failsafe check
if ( copter . failsafe . radio | | ! copter . ap . rc_receiver_present ) {
return vel ;
}
// fetch roll and pitch inputs
float roll_out = channel_roll - > get_control_in ( ) ;
float pitch_out = channel_pitch - > get_control_in ( ) ;
// convert roll and pitch inputs to -1 to +1 range
float scaler = 1.0 / ( float ) ROLL_PITCH_YAW_INPUT_MAX ;
roll_out * = scaler ;
pitch_out * = scaler ;
// convert roll and pitch inputs into velocity in NE frame
vel = Vector2f ( - pitch_out , roll_out ) ;
if ( vel . is_zero ( ) ) {
return vel ;
}
copter . rotate_body_frame_to_NE ( vel . x , vel . y ) ;
// Transform square input range to circular output
// vel_scaler is the vector to the edge of the +- 1.0 square in the direction of the current input
Vector2f vel_scaler = vel / MAX ( fabsf ( vel . x ) , fabsf ( vel . y ) ) ;
// We scale the output by the ratio of the distance to the square to the unit circle and multiply by vel_max
vel * = vel_max / vel_scaler . length ( ) ;
return vel ;
}
2019-05-09 23:18:49 -03:00
bool Mode : : _TakeOff : : triggered ( const float target_climb_rate ) const
2017-12-12 06:53:56 -04:00
{
2018-03-16 03:22:14 -03:00
if ( ! copter . ap . land_complete ) {
2017-12-12 06:53:56 -04:00
// 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 ;
}
2018-12-31 00:18:14 -04:00
2019-04-09 09:16:58 -03:00
if ( copter . motors - > get_spool_state ( ) ! = AP_Motors : : SpoolState : : THROTTLE_UNLIMITED ) {
2019-02-28 05:03:00 -04:00
// hold aircraft on the ground until rotor speed runup has finished
2017-12-12 06:53:56 -04:00
return false ;
}
2019-02-28 05:03:00 -04:00
2017-12-12 06:53:56 -04:00
return true ;
}
2016-11-17 01:46:52 -04:00
2019-05-09 23:18:49 -03:00
bool Mode : : is_disarmed_or_landed ( ) const
2019-04-08 05:15:57 -03:00
{
2019-05-09 23:18:49 -03:00
if ( ! motors - > armed ( ) | | ! copter . ap . auto_armed | | copter . ap . land_complete ) {
2019-04-08 05:15:57 -03:00
return true ;
}
return false ;
}
2019-05-09 23:18:49 -03:00
void Mode : : zero_throttle_and_relax_ac ( bool spool_up )
2016-11-17 01:46:52 -04:00
{
2019-01-08 06:43:51 -04:00
if ( spool_up ) {
2019-04-09 09:16:58 -03:00
motors - > set_desired_spool_state ( AP_Motors : : DesiredSpoolState : : THROTTLE_UNLIMITED ) ;
2019-01-08 06:43:51 -04:00
} else {
2019-04-09 09:16:58 -03:00
motors - > set_desired_spool_state ( AP_Motors : : DesiredSpoolState : : GROUND_IDLE ) ;
2019-01-08 06:43:51 -04:00
}
2017-06-26 05:48:04 -03:00
attitude_control - > input_euler_angle_roll_pitch_euler_rate_yaw ( 0.0f , 0.0f , 0.0f ) ;
2018-02-07 22:21:09 -04:00
attitude_control - > set_throttle_out ( 0.0f , false , copter . g . throttle_filt ) ;
2019-02-28 05:03:23 -04:00
}
2019-05-09 23:18:49 -03:00
void Mode : : zero_throttle_and_hold_attitude ( )
2019-02-28 05:03:23 -04:00
{
// run attitude controller
attitude_control - > input_rate_bf_roll_pitch_yaw ( 0.0f , 0.0f , 0.0f ) ;
attitude_control - > set_throttle_out ( 0.0f , false , copter . g . throttle_filt ) ;
}
2020-10-13 20:19:42 -03:00
// handle situations where the vehicle is on the ground waiting for takeoff
// force_throttle_unlimited should be true in cases where we want to keep the motors spooled up
// (instead of spooling down to ground idle). This is required for tradheli's in Guided and Auto
// where we always want the motor spooled up in Guided or Auto mode. Tradheli's main rotor stops
// when spooled down to ground idle.
// ultimately it forces the motor interlock to be obeyed in auto and guided modes when on the ground.
void Mode : : make_safe_ground_handling ( bool force_throttle_unlimited )
2019-02-28 05:03:23 -04:00
{
2020-10-13 20:19:42 -03:00
if ( force_throttle_unlimited ) {
// keep rotors turning
motors - > set_desired_spool_state ( AP_Motors : : DesiredSpoolState : : THROTTLE_UNLIMITED ) ;
} else {
// spool down to ground idle
motors - > set_desired_spool_state ( AP_Motors : : DesiredSpoolState : : GROUND_IDLE ) ;
}
2022-02-03 12:32:50 -04:00
// aircraft is landed, integrator terms must be reset regardless of spool state
attitude_control - > reset_rate_controller_I_terms_smoothly ( ) ;
2019-04-09 09:16:58 -03:00
switch ( motors - > get_spool_state ( ) ) {
case AP_Motors : : SpoolState : : SHUT_DOWN :
case AP_Motors : : SpoolState : : GROUND_IDLE :
2022-02-03 12:32:50 -04:00
// reset yaw targets and rates during idle states
2021-05-24 10:42:19 -03:00
attitude_control - > reset_yaw_target_and_rate ( ) ;
2019-02-28 05:03:23 -04:00
break ;
2019-04-09 09:16:58 -03:00
case AP_Motors : : SpoolState : : SPOOLING_UP :
case AP_Motors : : SpoolState : : THROTTLE_UNLIMITED :
case AP_Motors : : SpoolState : : SPOOLING_DOWN :
2019-02-28 05:03:23 -04:00
// while transitioning though active states continue to operate normally
break ;
}
2022-05-13 21:38:49 -03:00
pos_control - > relax_velocity_controller_xy ( ) ;
pos_control - > update_xy_controller ( ) ;
2021-05-19 11:07:38 -03:00
pos_control - > relax_z_controller ( 0.0f ) ; // forces throttle output to decay to zero
2019-02-28 05:03:23 -04:00
pos_control - > update_z_controller ( ) ;
// we may need to move this out
attitude_control - > input_euler_angle_roll_pitch_euler_rate_yaw ( 0.0f , 0.0f , 0.0f ) ;
2016-11-17 01:46:52 -04:00
}
2018-02-07 22:21:09 -04:00
2018-03-22 07:13:58 -03:00
/*
get a height above ground estimate for landing
*/
2019-05-09 23:18:49 -03:00
int32_t Mode : : get_alt_above_ground_cm ( void )
2018-03-22 07:13:58 -03:00
{
2020-02-25 23:23:23 -04:00
int32_t alt_above_ground_cm ;
if ( copter . get_rangefinder_height_interpolated_cm ( alt_above_ground_cm ) ) {
return alt_above_ground_cm ;
}
if ( ! pos_control - > is_active_xy ( ) ) {
return copter . current_loc . alt ;
2018-03-22 07:13:58 -03:00
}
2020-02-25 23:23:23 -04:00
if ( copter . current_loc . get_alt_cm ( Location : : AltFrame : : ABOVE_TERRAIN , alt_above_ground_cm ) ) {
return alt_above_ground_cm ;
}
// Assume the Earth is flat:
return copter . current_loc . alt ;
2018-03-22 07:13:58 -03:00
}
2019-05-09 23:18:49 -03:00
void Mode : : land_run_vertical_control ( bool pause_descent )
2018-03-22 07:13:58 -03:00
{
float cmb_rate = 0 ;
2021-06-21 04:51:39 -03:00
bool ignore_descent_limit = false ;
2018-03-22 07:13:58 -03:00
if ( ! pause_descent ) {
2021-06-21 04:51:39 -03:00
// do not ignore limits until we have slowed down for landing
ignore_descent_limit = ( MAX ( g2 . land_alt_low , 100 ) > get_alt_above_ground_cm ( ) ) | | copter . ap . land_complete_maybe ;
2018-03-22 07:13:58 -03:00
float max_land_descent_velocity ;
if ( g . land_speed_high > 0 ) {
max_land_descent_velocity = - g . land_speed_high ;
} else {
2021-05-11 01:42:02 -03:00
max_land_descent_velocity = pos_control - > get_max_speed_down_cms ( ) ;
2018-03-22 07:13:58 -03:00
}
// Don't speed up for landing.
max_land_descent_velocity = MIN ( max_land_descent_velocity , - abs ( g . land_speed ) ) ;
// Compute a vertical velocity demand such that the vehicle approaches g2.land_alt_low. Without the below constraint, this would cause the vehicle to hover at g2.land_alt_low.
2021-05-11 01:42:02 -03:00
cmb_rate = sqrt_controller ( MAX ( g2 . land_alt_low , 100 ) - get_alt_above_ground_cm ( ) , pos_control - > get_pos_z_p ( ) . kP ( ) , pos_control - > get_max_accel_z_cmss ( ) , G_Dt ) ;
2018-03-22 07:13:58 -03:00
// Constrain the demanded vertical velocity so that it is between the configured maximum descent speed and the configured minimum descent speed.
cmb_rate = constrain_float ( cmb_rate , max_land_descent_velocity , - abs ( g . land_speed ) ) ;
2023-03-22 05:45:41 -03:00
# if AC_PRECLAND_ENABLED
2019-12-09 23:12:07 -04:00
const bool navigating = pos_control - > is_active_xy ( ) ;
bool doing_precision_landing = ! copter . ap . land_repo_active & & copter . precland . target_acquired ( ) & & navigating ;
2021-08-05 16:05:00 -03:00
if ( doing_precision_landing ) {
// prec landing is active
Vector2f target_pos ;
float target_error_cm = 0.0f ;
if ( copter . precland . get_target_position_cm ( target_pos ) ) {
2021-10-20 05:29:57 -03:00
const Vector2f current_pos = inertial_nav . get_position_xy_cm ( ) ;
2021-08-05 16:05:00 -03:00
// target is this many cm away from the vehicle
target_error_cm = ( target_pos - current_pos ) . length ( ) ;
}
// check if we should descend or not
const float max_horiz_pos_error_cm = copter . precland . get_max_xy_error_before_descending_cm ( ) ;
2022-09-13 10:10:46 -03:00
Vector3f target_pos_meas ;
copter . precland . get_target_position_measurement_cm ( target_pos_meas ) ;
2021-08-05 16:05:00 -03:00
if ( target_error_cm > max_horiz_pos_error_cm & & ! is_zero ( max_horiz_pos_error_cm ) ) {
// doing precland but too far away from the obstacle
// do not descend
cmb_rate = 0.0f ;
2023-09-04 00:11:52 -03:00
} else if ( target_pos_meas . z > 35.0f & & target_pos_meas . z < 200.0f & & ! copter . precland . do_fast_descend ( ) ) {
2021-08-05 16:05:00 -03:00
// very close to the ground and doing prec land, lets slow down to make sure we land on target
// compute desired descent velocity
const float precland_acceptable_error_cm = 15.0f ;
const float precland_min_descent_speed_cms = 10.0f ;
const float max_descent_speed_cms = abs ( g . land_speed ) * 0.5f ;
const float land_slowdown = MAX ( 0.0f , target_error_cm * ( max_descent_speed_cms / precland_acceptable_error_cm ) ) ;
cmb_rate = MIN ( - precland_min_descent_speed_cms , - max_descent_speed_cms + land_slowdown ) ;
}
2018-03-22 07:13:58 -03:00
}
2019-12-09 23:12:07 -04:00
# endif
2018-03-22 07:13:58 -03:00
}
// update altitude target and call position controller
2021-08-31 01:17:59 -03:00
pos_control - > land_at_climb_rate_cm ( cmb_rate , ignore_descent_limit ) ;
2018-03-22 07:13:58 -03:00
pos_control - > update_z_controller ( ) ;
}
2019-05-09 23:18:49 -03:00
void Mode : : land_run_horizontal_control ( )
2018-03-22 07:13:58 -03:00
{
2022-02-01 23:40:27 -04:00
Vector2f vel_correction ;
2018-03-22 07:13:58 -03:00
// relax loiter target if we might be landed
2019-05-09 23:18:49 -03:00
if ( copter . ap . land_complete_maybe ) {
2022-02-01 23:40:27 -04:00
pos_control - > soften_for_landing_xy ( ) ;
2018-03-22 07:13:58 -03:00
}
// process pilot inputs
if ( ! copter . failsafe . radio ) {
2018-10-03 00:14:44 -03:00
if ( ( g . throttle_behavior & THR_BEHAVE_HIGH_THROTTLE_CANCELS_LAND ) ! = 0 & & copter . rc_throttle_control_in_filter . get ( ) > LAND_CANCEL_TRIGGER_THR ) {
2023-07-13 21:58:09 -03:00
LOGGER_WRITE_EVENT ( LogEvent : : LAND_CANCELLED_BY_PILOT ) ;
2018-03-22 07:13:58 -03:00
// exit land if throttle is high
2019-10-17 00:49:22 -03:00
if ( ! set_mode ( Mode : : Number : : LOITER , ModeReason : : THROTTLE_LAND_ESCAPE ) ) {
set_mode ( Mode : : Number : : ALT_HOLD , ModeReason : : THROTTLE_LAND_ESCAPE ) ;
2018-03-22 07:13:58 -03:00
}
}
if ( g . land_repositioning ) {
// apply SIMPLE mode transform to pilot inputs
update_simple_mode ( ) ;
2022-02-01 23:40:27 -04:00
// convert pilot input to reposition velocity
// use half maximum acceleration as the maximum velocity to ensure aircraft will
// stop from full reposition speed in less than 1 second.
const float max_pilot_vel = wp_nav - > get_wp_acceleration ( ) * 0.5 ;
vel_correction = get_pilot_desired_velocity ( max_pilot_vel ) ;
2018-03-22 07:13:58 -03:00
2019-03-25 20:57:55 -03:00
// record if pilot has overridden roll or pitch
2022-02-01 23:40:27 -04:00
if ( ! vel_correction . is_zero ( ) ) {
2019-05-09 23:18:49 -03:00
if ( ! copter . ap . land_repo_active ) {
2023-07-13 21:58:09 -03:00
LOGGER_WRITE_EVENT ( LogEvent : : LAND_REPO_ACTIVE ) ;
2018-11-12 06:31:22 -04:00
}
2019-05-09 23:18:49 -03:00
copter . ap . land_repo_active = true ;
2023-03-22 05:45:41 -03:00
# if AC_PRECLAND_ENABLED
2023-01-29 06:09:28 -04:00
} else {
// no override right now, check if we should allow precland
if ( copter . precland . allow_precland_after_reposition ( ) ) {
copter . ap . land_repo_active = false ;
}
# endif
2018-03-22 07:13:58 -03:00
}
}
}
2021-09-05 17:07:57 -03:00
// this variable will be updated if prec land target is in sight and pilot isn't trying to reposition the vehicle
2022-02-01 23:40:27 -04:00
copter . ap . prec_land_active = false ;
2023-03-22 05:45:41 -03:00
# if AC_PRECLAND_ENABLED
2022-02-01 23:40:27 -04:00
copter . ap . prec_land_active = ! copter . ap . land_repo_active & & copter . precland . target_acquired ( ) ;
2018-03-22 07:13:58 -03:00
// run precision landing
2022-02-01 23:40:27 -04:00
if ( copter . ap . prec_land_active ) {
2021-09-05 17:07:57 -03:00
Vector2f target_pos , target_vel ;
2018-10-03 00:14:44 -03:00
if ( ! copter . precland . get_target_position_cm ( target_pos ) ) {
2021-10-20 05:29:57 -03:00
target_pos = inertial_nav . get_position_xy_cm ( ) ;
2018-03-22 07:13:58 -03:00
}
2021-09-05 17:07:57 -03:00
// get the velocity of the target
copter . precland . get_target_velocity_cms ( inertial_nav . get_velocity_xy_cms ( ) , target_vel ) ;
Vector2f zero ;
Vector2p landing_pos = target_pos . topostype ( ) ;
// target vel will remain zero if landing target is stationary
pos_control - > input_pos_vel_accel_xy ( landing_pos , target_vel , zero ) ;
}
# endif
2022-02-01 23:40:27 -04:00
if ( ! copter . ap . prec_land_active ) {
Vector2f accel ;
pos_control - > input_vel_accel_xy ( vel_correction , accel ) ;
2021-09-05 17:07:57 -03:00
}
2018-03-22 07:13:58 -03:00
2022-02-01 23:40:27 -04:00
// run pos controller
pos_control - > update_xy_controller ( ) ;
2021-09-05 17:07:57 -03:00
Vector3f thrust_vector = pos_control - > get_thrust_vector ( ) ;
2018-03-22 07:13:58 -03:00
if ( g2 . wp_navalt_min > 0 ) {
// user has requested an altitude below which navigation
// attitude is limited. This is used to prevent commanded roll
// over on landing, which particularly affects helicopters if
// there is any position estimate drift after touchdown. We
// limit attitude to 7 degrees below this limit and linearly
// interpolate for 1m above that
2021-09-11 07:25:53 -03:00
const float attitude_limit_cd = linear_interpolate ( 700 , copter . aparm . angle_max , get_alt_above_ground_cm ( ) ,
2018-03-22 07:13:58 -03:00
g2 . wp_navalt_min * 100U , ( g2 . wp_navalt_min + 1 ) * 100U ) ;
2022-03-11 13:29:59 -04:00
const float thrust_vector_max = sinf ( radians ( attitude_limit_cd * 0.01f ) ) * GRAVITY_MSS * 100.0f ;
2021-09-11 07:25:53 -03:00
const float thrust_vector_mag = thrust_vector . xy ( ) . length ( ) ;
2021-04-13 02:39:53 -03:00
if ( thrust_vector_mag > thrust_vector_max ) {
float ratio = thrust_vector_max / thrust_vector_mag ;
thrust_vector . x * = ratio ;
thrust_vector . y * = ratio ;
2018-03-22 07:13:58 -03:00
// tell position controller we are applying an external limit
2021-05-19 11:07:38 -03:00
pos_control - > set_externally_limited_xy ( ) ;
2018-03-22 07:13:58 -03:00
}
}
// call attitude controller
2022-09-24 11:12:33 -03:00
attitude_control - > input_thrust_vector_heading ( thrust_vector , auto_yaw . get_heading ( ) ) ;
2018-03-22 07:13:58 -03:00
}
2021-08-25 02:53:56 -03:00
// run normal or precision landing (if enabled)
// pause_descent is true if vehicle should not descend
void Mode : : land_run_normal_or_precland ( bool pause_descent )
2021-08-23 06:00:09 -03:00
{
2023-03-22 05:45:41 -03:00
# if AC_PRECLAND_ENABLED
2021-08-23 06:00:09 -03:00
if ( pause_descent | | ! copter . precland . enabled ( ) ) {
// we don't want to start descending immediately or prec land is disabled
// in both cases just run simple land controllers
2021-08-25 02:53:56 -03:00
land_run_horiz_and_vert_control ( pause_descent ) ;
2021-08-23 06:00:09 -03:00
} else {
// prec land is enabled and we have not paused descent
// the state machine takes care of the entire prec landing procedure
2021-08-25 02:53:56 -03:00
precland_run ( ) ;
2021-08-23 06:00:09 -03:00
}
# else
2021-08-25 02:53:56 -03:00
land_run_horiz_and_vert_control ( pause_descent ) ;
2021-08-23 06:00:09 -03:00
# endif
}
2023-03-22 05:45:41 -03:00
# if AC_PRECLAND_ENABLED
2021-07-21 16:33:37 -03:00
// Go towards a position commanded by prec land state machine in order to retry landing
// The passed in location is expected to be NED and in m
2021-08-25 02:53:56 -03:00
void Mode : : precland_retry_position ( const Vector3f & retry_pos )
2021-07-21 16:33:37 -03:00
{
if ( ! copter . failsafe . radio ) {
if ( ( g . throttle_behavior & THR_BEHAVE_HIGH_THROTTLE_CANCELS_LAND ) ! = 0 & & copter . rc_throttle_control_in_filter . get ( ) > LAND_CANCEL_TRIGGER_THR ) {
2023-07-13 21:58:09 -03:00
LOGGER_WRITE_EVENT ( LogEvent : : LAND_CANCELLED_BY_PILOT ) ;
2021-07-21 16:33:37 -03:00
// exit land if throttle is high
if ( ! set_mode ( Mode : : Number : : LOITER , ModeReason : : THROTTLE_LAND_ESCAPE ) ) {
set_mode ( Mode : : Number : : ALT_HOLD , ModeReason : : THROTTLE_LAND_ESCAPE ) ;
}
}
// allow user to take control during repositioning. Note: copied from land_run_horizontal_control()
2022-07-10 08:11:07 -03:00
// To-Do: this code exists at several different places in slightly different forms and that should be fixed
2021-07-21 16:33:37 -03:00
if ( g . land_repositioning ) {
float target_roll = 0.0f ;
float target_pitch = 0.0f ;
// convert pilot input to lean angles
2021-09-06 06:44:18 -03:00
get_pilot_desired_lean_angles ( target_roll , target_pitch , loiter_nav - > get_angle_max_cd ( ) , attitude_control - > get_althold_lean_angle_max_cd ( ) ) ;
2021-07-21 16:33:37 -03:00
// record if pilot has overridden roll or pitch
if ( ! is_zero ( target_roll ) | | ! is_zero ( target_pitch ) ) {
if ( ! copter . ap . land_repo_active ) {
2023-07-13 21:58:09 -03:00
LOGGER_WRITE_EVENT ( LogEvent : : LAND_REPO_ACTIVE ) ;
2021-07-21 16:33:37 -03:00
}
// this flag will be checked by prec land state machine later and any further landing retires will be cancelled
copter . ap . land_repo_active = true ;
}
}
}
2021-08-25 02:53:56 -03:00
Vector3p retry_pos_NEU { retry_pos . x , retry_pos . y , retry_pos . z * - 1.0f } ;
2022-07-10 08:11:07 -03:00
// pos controller expects input in NEU cm's
2021-08-25 02:53:56 -03:00
retry_pos_NEU = retry_pos_NEU * 100.0f ;
pos_control - > input_pos_xyz ( retry_pos_NEU , 0.0f , 1000.0f ) ;
2021-07-21 16:33:37 -03:00
// run position controllers
pos_control - > update_xy_controller ( ) ;
pos_control - > update_z_controller ( ) ;
2022-05-19 02:28:48 -03:00
// call attitude controller
2022-09-24 11:12:33 -03:00
attitude_control - > input_thrust_vector_heading ( pos_control - > get_thrust_vector ( ) , auto_yaw . get_heading ( ) ) ;
2021-07-21 16:33:37 -03:00
}
// Run precland statemachine. This function should be called from any mode that wants to do precision landing.
// This handles everything from prec landing, to prec landing failures, to retries and failsafe measures
2021-08-25 02:53:56 -03:00
void Mode : : precland_run ( )
2021-07-21 16:33:37 -03:00
{
// if user is taking control, we will not run the statemachine, and simply land (may or may not be on target)
if ( ! copter . ap . land_repo_active ) {
// This will get updated later to a retry pos if needed
Vector3f retry_pos ;
switch ( copter . precland_statemachine . update ( retry_pos ) ) {
case AC_PrecLand_StateMachine : : Status : : RETRYING :
// we want to retry landing by going to another position
2021-08-25 02:53:56 -03:00
precland_retry_position ( retry_pos ) ;
2021-07-21 16:33:37 -03:00
break ;
case AC_PrecLand_StateMachine : : Status : : FAILSAFE : {
// we have hit a failsafe. Failsafe can only mean two things, we either want to stop permanently till user takes over or land
switch ( copter . precland_statemachine . get_failsafe_actions ( ) ) {
case AC_PrecLand_StateMachine : : FailSafeAction : : DESCEND :
// descend normally, prec land target is definitely not in sight
2021-08-25 02:53:56 -03:00
land_run_horiz_and_vert_control ( ) ;
2021-07-21 16:33:37 -03:00
break ;
case AC_PrecLand_StateMachine : : FailSafeAction : : HOLD_POS :
// sending "true" in this argument will stop the descend
2021-08-25 02:53:56 -03:00
land_run_horiz_and_vert_control ( true ) ;
2021-07-21 16:33:37 -03:00
break ;
}
break ;
}
case AC_PrecLand_StateMachine : : Status : : ERROR :
// should never happen, is certainly a bug. Report then descend
INTERNAL_ERROR ( AP_InternalError : : error_t : : flow_of_control ) ;
FALLTHROUGH ;
case AC_PrecLand_StateMachine : : Status : : DESCEND :
// run land controller. This will descend towards the target if prec land target is in sight
// else it will just descend vertically
2021-08-25 02:53:56 -03:00
land_run_horiz_and_vert_control ( ) ;
2021-07-21 16:33:37 -03:00
break ;
}
} else {
// just land, since user has taken over controls, it does not make sense to run any retries or failsafe measures
2021-08-25 02:53:56 -03:00
land_run_horiz_and_vert_control ( ) ;
2021-07-21 16:33:37 -03:00
}
}
# endif
2019-05-09 23:18:49 -03:00
float Mode : : throttle_hover ( ) const
2019-03-26 07:09:12 -03:00
{
return motors - > get_throttle_hover ( ) ;
}
// transform pilot's manual throttle input to make hover throttle mid stick
// used only for manual throttle modes
// thr_mid should be in the range 0 to 1
// returns throttle output 0 to 1
2019-05-09 23:18:49 -03:00
float Mode : : get_pilot_desired_throttle ( ) const
2019-03-26 07:09:12 -03:00
{
const float thr_mid = throttle_hover ( ) ;
int16_t throttle_control = channel_throttle - > get_control_in ( ) ;
int16_t mid_stick = copter . get_throttle_mid ( ) ;
// protect against unlikely divide by zero
if ( mid_stick < = 0 ) {
mid_stick = 500 ;
}
// ensure reasonable throttle values
throttle_control = constrain_int16 ( throttle_control , 0 , 1000 ) ;
// calculate normalised throttle input
float throttle_in ;
if ( throttle_control < mid_stick ) {
throttle_in = ( ( float ) throttle_control ) * 0.5f / ( float ) mid_stick ;
} else {
2019-03-26 21:55:18 -03:00
throttle_in = 0.5f + ( ( float ) ( throttle_control - mid_stick ) ) * 0.5f / ( float ) ( 1000 - mid_stick ) ;
2019-03-26 07:09:12 -03:00
}
2019-04-04 02:41:10 -03:00
const float expo = constrain_float ( - ( thr_mid - 0.5f ) / 0.375f , - 0.5f , 1.0f ) ;
2019-03-26 07:09:12 -03:00
// calculate the output throttle using the given expo function
float throttle_out = throttle_in * ( 1.0f - expo ) + expo * throttle_in * throttle_in * throttle_in ;
return throttle_out ;
}
2020-06-16 03:50:37 -03:00
float Mode : : get_avoidance_adjusted_climbrate ( float target_rate )
{
# if AC_AVOID_ENABLED == ENABLED
2021-05-11 01:42:02 -03:00
AP : : ac_avoid ( ) - > adjust_velocity_z ( pos_control - > get_pos_z_p ( ) . kP ( ) , pos_control - > get_max_accel_z_cmss ( ) , target_rate , G_Dt ) ;
2020-06-16 03:50:37 -03:00
return target_rate ;
# else
return target_rate ;
# endif
}
2021-08-14 06:12:18 -03:00
// send output to the motors, can be overridden by subclasses
void Mode : : output_to_motors ( )
{
motors - > output ( ) ;
}
2019-05-09 23:18:49 -03:00
Mode : : AltHoldModeState Mode : : get_alt_hold_state ( float target_climb_rate_cms )
2019-02-28 05:03:23 -04:00
{
// Alt Hold State Machine Determination
if ( ! motors - > armed ( ) ) {
// the aircraft should moved to a shut down state
2019-04-09 09:16:58 -03:00
motors - > set_desired_spool_state ( AP_Motors : : DesiredSpoolState : : SHUT_DOWN ) ;
2019-02-28 05:03:23 -04:00
// transition through states as aircraft spools down
2019-04-09 09:16:58 -03:00
switch ( motors - > get_spool_state ( ) ) {
2019-02-28 05:03:23 -04:00
2019-04-09 09:16:58 -03:00
case AP_Motors : : SpoolState : : SHUT_DOWN :
2019-02-28 05:03:23 -04:00
return AltHold_MotorStopped ;
2019-04-09 09:16:58 -03:00
case AP_Motors : : SpoolState : : GROUND_IDLE :
2019-02-28 05:03:23 -04:00
return AltHold_Landed_Ground_Idle ;
default :
return AltHold_Landed_Pre_Takeoff ;
}
} else if ( takeoff . running ( ) | | takeoff . triggered ( target_climb_rate_cms ) ) {
// the aircraft is currently landed or taking off, asking for a positive climb rate and in THROTTLE_UNLIMITED
// the aircraft should progress through the take off procedure
return AltHold_Takeoff ;
2019-05-09 23:18:49 -03:00
} else if ( ! copter . ap . auto_armed | | copter . ap . land_complete ) {
2019-02-28 05:03:23 -04:00
// the aircraft is armed and landed
2019-05-09 23:18:49 -03:00
if ( target_climb_rate_cms < 0.0f & & ! copter . ap . using_interlock ) {
2019-02-28 05:03:23 -04:00
// the aircraft should move to a ground idle state
2019-04-09 09:16:58 -03:00
motors - > set_desired_spool_state ( AP_Motors : : DesiredSpoolState : : GROUND_IDLE ) ;
2019-02-28 05:03:23 -04:00
} else {
// the aircraft should prepare for imminent take off
2019-04-09 09:16:58 -03:00
motors - > set_desired_spool_state ( AP_Motors : : DesiredSpoolState : : THROTTLE_UNLIMITED ) ;
2019-02-28 05:03:23 -04:00
}
2019-04-09 09:16:58 -03:00
if ( motors - > get_spool_state ( ) = = AP_Motors : : SpoolState : : GROUND_IDLE ) {
2019-02-28 05:03:23 -04:00
// the aircraft is waiting in ground idle
return AltHold_Landed_Ground_Idle ;
} else {
// the aircraft can leave the ground at any time
return AltHold_Landed_Pre_Takeoff ;
}
} else {
// the aircraft is in a flying state
2019-04-09 09:16:58 -03:00
motors - > set_desired_spool_state ( AP_Motors : : DesiredSpoolState : : THROTTLE_UNLIMITED ) ;
2019-02-28 05:03:23 -04:00
return AltHold_Flying ;
}
}
2021-01-26 19:06:20 -04:00
// transform pilot's yaw input into a desired yaw rate
// returns desired yaw rate in centi-degrees per second
2021-09-17 02:54:19 -03:00
float Mode : : get_pilot_desired_yaw_rate ( float yaw_in )
2018-02-07 22:21:09 -04:00
{
2021-01-26 19:06:20 -04:00
// throttle failsafe check
if ( copter . failsafe . radio | | ! copter . ap . rc_receiver_present ) {
return 0.0f ;
}
// convert pilot input to the desired yaw rate
2022-06-15 00:08:53 -03:00
return g2 . command_model_pilot . get_rate ( ) * 100.0 * input_expo ( yaw_in , g2 . command_model_pilot . get_expo ( ) ) ;
2018-02-07 22:21:09 -04:00
}
2021-01-26 19:06:20 -04:00
// pass-through functions to reduce code churn on conversion;
// these are candidates for moving into the Mode base
// class.
2019-05-09 23:18:49 -03:00
float Mode : : get_pilot_desired_climb_rate ( float throttle_control )
2018-02-07 22:21:09 -04:00
{
return copter . get_pilot_desired_climb_rate ( throttle_control ) ;
}
2019-05-09 23:18:49 -03:00
float Mode : : get_non_takeoff_throttle ( )
2018-02-07 22:21:09 -04:00
{
return copter . get_non_takeoff_throttle ( ) ;
}
2019-05-09 23:18:49 -03:00
void Mode : : update_simple_mode ( void ) {
2018-02-07 22:21:09 -04:00
copter . update_simple_mode ( ) ;
}
2019-10-17 00:49:22 -03:00
bool Mode : : set_mode ( Mode : : Number mode , ModeReason reason )
2018-02-07 22:21:09 -04:00
{
return copter . set_mode ( mode , reason ) ;
}
2019-05-09 23:18:49 -03:00
void Mode : : set_land_complete ( bool b )
2018-02-07 22:21:09 -04:00
{
return copter . set_land_complete ( b ) ;
}
2019-05-09 23:18:49 -03:00
GCS_Copter & Mode : : gcs ( )
2018-02-07 22:21:09 -04:00
{
return copter . gcs ( ) ;
}
2019-05-09 23:18:49 -03:00
uint16_t Mode : : get_pilot_speed_dn ( )
2018-02-07 22:21:09 -04:00
{
return copter . get_pilot_speed_dn ( ) ;
}