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 ) ,
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 ) ,
G_Dt ( copter . G_Dt ) ,
# if FRAME_CONFIG == HELI_FRAME
heli_flags ( copter . heli_flags ) ,
# endif
2018-09-05 03:47:50 -03:00
ap ( copter . ap )
2018-02-07 22:21:09 -04:00
{ } ;
2018-06-26 00:24:54 -03:00
float Copter : : Mode : : auto_takeoff_no_nav_alt_cm = 0 ;
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 ) {
2018-03-14 17:14:49 -03:00
# if MODE_ACRO_ENABLED == ENABLED
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 ;
2018-03-14 17:14:49 -03:00
# endif
2014-02-03 04:57:31 -04:00
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 ;
2018-02-21 22:06:07 -04:00
# if MODE_AUTO_ENABLED == ENABLED
2014-02-03 04:57:31 -04:00
case 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
2014-02-03 04:57:31 -04:00
case 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
2014-02-03 04:57:31 -04:00
case 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
2014-02-03 04:57:31 -04:00
case 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
case 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
2014-02-03 04:57:31 -04:00
case 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
2014-02-03 04:57:31 -04:00
case 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
2014-02-03 04:57:31 -04:00
case 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
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
2018-02-21 23:45:02 -04:00
# if MODE_POSHOLD_ENABLED == ENABLED
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 ;
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
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 ;
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
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 ;
2018-03-14 17:16:16 -03:00
# endif
2015-12-18 05:46:56 -04:00
2018-02-16 10:21:55 -04:00
# if ADSB_ENABLED == ENABLED
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 ;
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
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 ;
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
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-02-21 23:58:28 -04:00
# endif
2017-07-26 14:14:40 -03:00
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
2018-02-06 02:16:09 -04:00
# if MODE_FOLLOW_ENABLED == ENABLED
2018-02-05 22:44:05 -04:00
case FOLLOW :
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
case ZIGZAG :
ret = & mode_zigzag ;
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 ;
2018-02-21 18:37:55 -04:00
DataFlash . Log_Write_Mode ( control_mode , reason ) ;
2014-04-26 23:09:15 -03:00
2018-02-16 10:21:55 -04:00
# if ADSB_ENABLED == ENABLED
2017-11-10 01:13:52 -04:00
adsb . set_is_auto_mode ( ( mode = = AUTO ) | | ( mode = = RTL ) | | ( mode = = GUIDED ) ) ;
2018-02-16 10:21:55 -04:00
# endif
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
2018-03-04 05:41:06 -04:00
# if DEVO_TELEM_ENABLED == ENABLED
devo_telemetry . update_control_mode ( control_mode ) ;
# 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
{
2018-06-05 05:21:09 -03:00
target_rangefinder_alt_used = false ;
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
2018-02-21 22:06:07 -04:00
# if MODE_AUTO_ENABLED == ENABLED
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
}
2018-02-21 22:06:07 -04:00
# endif
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
2017-12-12 06:34:49 -04:00
old_flightmode - > takeoff_stop ( ) ;
2015-04-30 03:52:32 -03:00
2018-02-21 23:58:28 -04:00
# if MODE_SMARTRTL_ENABLED == ENABLED
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
}
2018-02-21 23:58:28 -04:00
# endif
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
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
2018-03-18 08:06:54 -03:00
void Copter : : Mode : : get_pilot_desired_lean_angles ( float & roll_out , float & pitch_out , float angle_max , float angle_limit ) const
2018-03-13 21:23:30 -03:00
{
2018-03-18 08:06:54 -03:00
// fetch roll and pitch inputs
roll_out = channel_roll - > get_control_in ( ) ;
pitch_out = channel_pitch - > get_control_in ( ) ;
// limit max lean angle
2017-11-12 03:50:51 -04:00
angle_limit = constrain_float ( angle_limit , 1000.0f , angle_max ) ;
2018-03-13 21:23:30 -03:00
2018-03-18 08:06:54 -03:00
// scale roll and pitch inputs to ANGLE_MAX parameter range
2017-11-12 03:50:51 -04:00
float scaler = angle_max / ( float ) ROLL_PITCH_YAW_INPUT_MAX ;
2018-03-18 08:06:54 -03:00
roll_out * = scaler ;
pitch_out * = scaler ;
2018-03-13 21:23:30 -03:00
// do circular limit
2018-03-18 08:06:54 -03:00
float total_in = norm ( pitch_out , roll_out ) ;
2017-11-12 03:50:51 -04:00
if ( total_in > angle_limit ) {
float ratio = angle_limit / total_in ;
2018-03-18 08:06:54 -03:00
roll_out * = ratio ;
pitch_out * = ratio ;
2018-03-13 21:23:30 -03:00
}
// do lateral tilt to euler roll conversion
2018-03-18 08:06:54 -03:00
roll_out = ( 18000 / M_PI ) * atanf ( cosf ( pitch_out * ( M_PI / 18000 ) ) * tanf ( roll_out * ( M_PI / 18000 ) ) ) ;
2018-03-13 21:23:30 -03:00
2018-03-18 08:06:54 -03:00
// roll_out and pitch_out are returned
2018-03-13 21:23:30 -03:00
}
2018-03-16 03:22:14 -03:00
bool Copter : : 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 ;
}
# if FRAME_CONFIG == HELI_FRAME
2018-03-16 03:22:14 -03:00
if ( ! copter . motors - > rotor_runup_complete ( ) ) {
2017-12-12 06:53:56 -04:00
// 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
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 ) ;
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
2018-03-22 07:13:58 -03:00
/*
get a height above ground estimate for landing
*/
int32_t Copter : : Mode : : get_alt_above_ground ( void )
{
int32_t alt_above_ground ;
if ( copter . rangefinder_alt_ok ( ) ) {
alt_above_ground = copter . rangefinder_state . alt_cm_filt . get ( ) ;
} else {
bool navigating = pos_control - > is_active_xy ( ) ;
if ( ! navigating | | ! copter . current_loc . get_alt_cm ( Location_Class : : ALT_FRAME_ABOVE_TERRAIN , alt_above_ground ) ) {
alt_above_ground = copter . current_loc . alt ;
}
}
return alt_above_ground ;
}
void Copter : : Mode : : land_run_vertical_control ( bool pause_descent )
{
2018-04-06 10:21:42 -03:00
# if PRECISION_LANDING == ENABLED
2018-03-22 07:13:58 -03:00
const bool navigating = pos_control - > is_active_xy ( ) ;
2018-10-03 00:14:44 -03:00
bool doing_precision_landing = ! ap . land_repo_active & & copter . precland . target_acquired ( ) & & navigating ;
2018-03-22 07:13:58 -03:00
# else
bool doing_precision_landing = false ;
# endif
// compute desired velocity
const float precland_acceptable_error = 15.0f ;
const float precland_min_descent_speed = 10.0f ;
const int32_t alt_above_ground = get_alt_above_ground ( ) ;
float cmb_rate = 0 ;
if ( ! pause_descent ) {
float max_land_descent_velocity ;
if ( g . land_speed_high > 0 ) {
max_land_descent_velocity = - g . land_speed_high ;
} else {
2018-09-20 02:45:02 -03:00
max_land_descent_velocity = pos_control - > get_max_speed_down ( ) ;
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.
2018-09-20 02:45:02 -03:00
cmb_rate = AC_AttitudeControl : : sqrt_controller ( MAX ( g2 . land_alt_low , 100 ) - alt_above_ground , pos_control - > get_pos_z_p ( ) . kP ( ) , pos_control - > get_max_accel_z ( ) , 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 ) ) ;
if ( doing_precision_landing & & copter . rangefinder_alt_ok ( ) & & copter . rangefinder_state . alt_cm > 35.0f & & copter . rangefinder_state . alt_cm < 200.0f ) {
float max_descent_speed = abs ( g . land_speed ) / 2.0f ;
float land_slowdown = MAX ( 0.0f , pos_control - > get_horizontal_error ( ) * ( max_descent_speed / precland_acceptable_error ) ) ;
cmb_rate = MIN ( - precland_min_descent_speed , - max_descent_speed + land_slowdown ) ;
}
}
// update altitude target and call position controller
pos_control - > set_alt_target_from_climb_rate_ff ( cmb_rate , G_Dt , true ) ;
pos_control - > update_z_controller ( ) ;
}
void Copter : : Mode : : land_run_horizontal_control ( )
{
float target_roll = 0.0f ;
float target_pitch = 0.0f ;
float target_yaw_rate = 0 ;
// relax loiter target if we might be landed
if ( ap . land_complete_maybe ) {
2018-03-27 23:13:37 -03:00
loiter_nav - > soften_for_landing ( ) ;
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 ) {
2018-03-22 07:13:58 -03:00
copter . Log_Write_Event ( DATA_LAND_CANCELLED_BY_PILOT ) ;
// exit land if throttle is high
if ( ! set_mode ( LOITER , MODE_REASON_THROTTLE_LAND_ESCAPE ) ) {
set_mode ( ALT_HOLD , MODE_REASON_THROTTLE_LAND_ESCAPE ) ;
}
}
if ( g . land_repositioning ) {
// apply SIMPLE mode transform to pilot inputs
update_simple_mode ( ) ;
// convert pilot input to lean angles
2018-03-27 23:13:37 -03:00
get_pilot_desired_lean_angles ( target_roll , target_pitch , loiter_nav - > get_angle_max_cd ( ) , attitude_control - > get_althold_lean_angle_max ( ) ) ;
2018-03-22 07:13:58 -03:00
// record if pilot has overriden roll or pitch
if ( ! is_zero ( target_roll ) | | ! is_zero ( target_pitch ) ) {
ap . land_repo_active = true ;
}
}
// get pilot's desired yaw rate
target_yaw_rate = get_pilot_desired_yaw_rate ( channel_yaw - > get_control_in ( ) ) ;
}
# if PRECISION_LANDING == ENABLED
2018-10-03 00:14:44 -03:00
bool doing_precision_landing = ! ap . land_repo_active & & copter . precland . target_acquired ( ) ;
2018-03-22 07:13:58 -03:00
// run precision landing
if ( doing_precision_landing ) {
Vector2f target_pos , target_vel_rel ;
2018-10-03 00:14:44 -03:00
if ( ! copter . precland . get_target_position_cm ( target_pos ) ) {
2018-03-22 07:13:58 -03:00
target_pos . x = inertial_nav . get_position ( ) . x ;
target_pos . y = inertial_nav . get_position ( ) . y ;
}
2018-10-03 00:14:44 -03:00
if ( ! copter . precland . get_target_velocity_relative_cms ( target_vel_rel ) ) {
2018-03-22 07:13:58 -03:00
target_vel_rel . x = - inertial_nav . get_velocity ( ) . x ;
target_vel_rel . y = - inertial_nav . get_velocity ( ) . y ;
}
pos_control - > set_xy_target ( target_pos . x , target_pos . y ) ;
pos_control - > override_vehicle_velocity_xy ( - target_vel_rel ) ;
}
# endif
// process roll, pitch inputs
2018-03-27 23:13:37 -03:00
loiter_nav - > set_pilot_desired_acceleration ( target_roll , target_pitch , G_Dt ) ;
2018-03-22 07:13:58 -03:00
// run loiter controller
2018-09-05 03:47:50 -03:00
loiter_nav - > update ( ) ;
2018-03-22 07:13:58 -03:00
2018-03-27 23:13:37 -03:00
int32_t nav_roll = loiter_nav - > get_roll ( ) ;
int32_t nav_pitch = loiter_nav - > get_pitch ( ) ;
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
const int alt_above_ground = get_alt_above_ground ( ) ;
2018-10-03 00:14:44 -03:00
float attitude_limit_cd = linear_interpolate ( 700 , copter . aparm . angle_max , alt_above_ground ,
2018-03-22 07:13:58 -03:00
g2 . wp_navalt_min * 100U , ( g2 . wp_navalt_min + 1 ) * 100U ) ;
float total_angle_cd = norm ( nav_roll , nav_pitch ) ;
if ( total_angle_cd > attitude_limit_cd ) {
float ratio = attitude_limit_cd / total_angle_cd ;
nav_roll * = ratio ;
nav_pitch * = ratio ;
// tell position controller we are applying an external limit
pos_control - > set_limit_accel_xy ( ) ;
}
}
// call attitude controller
attitude_control - > input_euler_angle_roll_pitch_euler_rate_yaw ( nav_roll , nav_pitch , target_yaw_rate ) ;
}
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.
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 ( ) ;
}
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 ( ) ;
}
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 ( ) ;
}