2015-05-29 23:12:49 -03:00
# include "Copter.h"
2019-02-25 10:32:52 -04:00
# if MODE_RTL_ENABLED == ENABLED
2014-01-24 02:47:42 -04:00
/*
2016-07-25 15:45:29 -03:00
* Init and run calls for RTL flight mode
2014-01-25 04:24:43 -04:00
*
* There are two parts to RTL , the high level decision making which controls which state we are in
* and the lower implementation of the waypoint or landing controllers within those states
2014-01-24 02:47:42 -04:00
*/
// rtl_init - initialise rtl controller
2019-05-09 23:18:49 -03:00
bool ModeRTL : : init ( bool ignore_checks )
2014-01-24 02:47:42 -04:00
{
2018-09-03 08:29:46 -03:00
if ( ! ignore_checks ) {
if ( ! AP : : ahrs ( ) . home_is_set ( ) ) {
return false ;
}
}
2019-02-28 20:52:28 -04:00
// initialise waypoint and spline controller
wp_nav - > wp_and_spline_init ( ) ;
2018-10-25 23:10:32 -03:00
_state = RTL_Starting ;
_state_complete = true ; // see run() method below
terrain_following_allowed = ! copter . failsafe . terrain ;
2019-02-28 20:52:28 -04:00
return true ;
2014-01-24 02:47:42 -04:00
}
2016-04-22 08:44:57 -03:00
// re-start RTL with terrain following disabled
2019-05-09 23:18:49 -03:00
void ModeRTL : : restart_without_terrain ( )
2016-04-22 08:44:57 -03:00
{
2019-03-24 22:31:46 -03:00
AP : : logger ( ) . Write_Error ( LogErrorSubsystem : : NAVIGATION , LogErrorCode : : RESTARTED_RTL ) ;
2019-12-11 23:36:49 -04:00
terrain_following_allowed = false ;
_state = RTL_Starting ;
_state_complete = true ;
gcs ( ) . send_text ( MAV_SEVERITY_CRITICAL , " Restarting RTL - Terrain data missing " ) ;
}
ModeRTL : : RTLAltType ModeRTL : : get_alt_type ( ) const
{
// sanity check parameter
if ( g . rtl_alt_type < 0 | | g . rtl_alt_type > ( int ) RTLAltType : : RTL_ALTTYPE_TERRAIN ) {
return RTLAltType : : RTL_ALTTYPE_RELATIVE ;
2016-04-22 08:44:57 -03:00
}
2019-12-11 23:36:49 -04:00
return ( RTLAltType ) g . rtl_alt_type . get ( ) ;
2016-04-22 08:44:57 -03:00
}
2014-01-24 02:47:42 -04:00
// rtl_run - runs the return-to-launch controller
// should be called at 100hz or more
2019-05-09 23:18:49 -03:00
void ModeRTL : : run ( bool disarm_on_land )
2014-01-24 02:47:42 -04:00
{
2018-10-25 23:10:32 -03:00
if ( ! motors - > armed ( ) ) {
return ;
2018-10-25 22:28:03 -03:00
}
2014-01-25 04:24:43 -04:00
// check if we need to move to next state
2016-03-22 03:42:17 -03:00
if ( _state_complete ) {
switch ( _state ) {
2018-10-25 23:10:32 -03:00
case RTL_Starting :
build_path ( ) ;
climb_start ( ) ;
break ;
2015-05-17 22:37:32 -03:00
case RTL_InitialClimb :
2016-03-22 03:42:17 -03:00
return_start ( ) ;
2014-01-25 04:24:43 -04:00
break ;
2015-05-17 22:37:32 -03:00
case RTL_ReturnHome :
2016-03-22 03:42:17 -03:00
loiterathome_start ( ) ;
2014-01-25 04:24:43 -04:00
break ;
2015-05-17 22:37:32 -03:00
case RTL_LoiterAtHome :
2018-02-07 22:21:09 -04:00
if ( rtl_path . land | | copter . failsafe . radio ) {
2016-03-22 03:42:17 -03:00
land_start ( ) ;
2016-01-06 02:52:20 -04:00
} else {
2016-03-22 03:42:17 -03:00
descent_start ( ) ;
2014-01-25 04:24:43 -04:00
}
break ;
2015-05-17 22:37:32 -03:00
case RTL_FinalDescent :
2014-01-25 04:24:43 -04:00
// do nothing
break ;
2015-05-17 22:37:32 -03:00
case RTL_Land :
2014-04-24 05:26:41 -03:00
// do nothing - rtl_land_run will take care of disarming motors
2014-01-25 04:24:43 -04:00
break ;
}
}
// call the correct run function
2016-03-22 03:42:17 -03:00
switch ( _state ) {
2014-01-25 04:24:43 -04:00
2018-10-25 23:10:32 -03:00
case RTL_Starting :
// should not be reached:
_state = RTL_InitialClimb ;
FALLTHROUGH ;
2015-05-17 22:37:32 -03:00
case RTL_InitialClimb :
2016-03-22 03:42:17 -03:00
climb_return_run ( ) ;
2014-01-25 04:24:43 -04:00
break ;
2015-05-17 22:37:32 -03:00
case RTL_ReturnHome :
2016-03-22 03:42:17 -03:00
climb_return_run ( ) ;
2014-01-25 04:24:43 -04:00
break ;
2015-05-17 22:37:32 -03:00
case RTL_LoiterAtHome :
2016-03-22 03:42:17 -03:00
loiterathome_run ( ) ;
2014-01-25 04:24:43 -04:00
break ;
2015-05-17 22:37:32 -03:00
case RTL_FinalDescent :
2016-03-22 03:42:17 -03:00
descent_run ( ) ;
2014-01-25 04:24:43 -04:00
break ;
2015-05-17 22:37:32 -03:00
case RTL_Land :
2016-03-22 03:42:17 -03:00
land_run ( disarm_on_land ) ;
2014-01-25 04:24:43 -04:00
break ;
}
}
// rtl_climb_start - initialise climb to RTL altitude
2019-05-09 23:18:49 -03:00
void ModeRTL : : climb_start ( )
2014-01-25 04:24:43 -04:00
{
2016-03-22 03:42:17 -03:00
_state = RTL_InitialClimb ;
_state_complete = false ;
2014-01-25 04:24:43 -04:00
2015-10-19 21:19:37 -03:00
// RTL_SPEED == 0 means use WPNAV_SPEED
2016-05-16 15:14:56 -03:00
if ( g . rtl_speed_cms ! = 0 ) {
2017-01-09 03:31:26 -04:00
wp_nav - > set_speed_xy ( g . rtl_speed_cms ) ;
2015-10-19 21:19:37 -03:00
}
2014-05-07 03:03:00 -03:00
// set the destination
2017-01-09 03:31:26 -04:00
if ( ! wp_nav - > set_wp_destination ( rtl_path . climb_target ) ) {
2016-04-22 08:44:57 -03:00
// this should not happen because rtl_build_path will have checked terrain data was available
2019-12-11 23:36:49 -04:00
gcs ( ) . send_text ( MAV_SEVERITY_CRITICAL , " RTL: unexpected error setting climb target " ) ;
2019-03-24 22:31:46 -03:00
AP : : logger ( ) . Write_Error ( LogErrorSubsystem : : NAVIGATION , LogErrorCode : : FAILED_TO_SET_DESTINATION ) ;
2019-10-17 00:49:22 -03:00
copter . set_mode ( Mode : : Number : : LAND , ModeReason : : TERRAIN_FAILSAFE ) ;
2016-04-22 08:44:57 -03:00
return ;
2016-03-18 07:44:09 -03:00
}
2017-01-09 03:31:26 -04:00
wp_nav - > set_fast_waypoint ( true ) ;
2014-01-25 04:24:43 -04:00
// hold current yaw during initial climb
2017-12-25 23:55:42 -04:00
auto_yaw . set_mode ( AUTO_YAW_HOLD ) ;
2014-01-25 04:24:43 -04:00
}
// rtl_return_start - initialise return to home
2019-05-09 23:18:49 -03:00
void ModeRTL : : return_start ( )
2014-01-25 04:24:43 -04:00
{
2016-03-22 03:42:17 -03:00
_state = RTL_ReturnHome ;
_state_complete = false ;
2014-01-25 04:24:43 -04:00
2017-01-09 03:31:26 -04:00
if ( ! wp_nav - > set_wp_destination ( rtl_path . return_target ) ) {
2016-04-22 08:44:57 -03:00
// failure must be caused by missing terrain data, restart RTL
2016-03-22 03:42:17 -03:00
restart_without_terrain ( ) ;
2016-03-18 07:44:09 -03:00
}
2014-01-25 04:24:43 -04:00
// initialise yaw to point home (maybe)
2017-12-25 23:55:42 -04:00
auto_yaw . set_mode_to_default ( true ) ;
2014-01-25 04:24:43 -04:00
}
2014-04-25 02:15:57 -03:00
// rtl_climb_return_run - implements the initial climb, return home and descent portions of RTL which all rely on the wp controller
2014-01-25 04:24:43 -04:00
// called by rtl_run at 100hz or more
2019-05-09 23:18:49 -03:00
void ModeRTL : : climb_return_run ( )
2014-01-25 04:24:43 -04:00
{
2019-02-28 05:03:23 -04:00
// if not armed set throttle to zero and exit immediately
2019-04-08 05:15:57 -03:00
if ( is_disarmed_or_landed ( ) ) {
2019-03-14 20:45:00 -03:00
make_safe_spool_down ( ) ;
2014-01-25 04:24:43 -04:00
return ;
}
// process pilot's yaw input
float target_yaw_rate = 0 ;
2020-11-12 20:15:53 -04:00
if ( ! copter . failsafe . radio & & use_pilot_yaw ( ) ) {
2014-01-25 04:24:43 -04:00
// get pilot's desired yaw rate
ArduCopter: Fix up after refactoring RC_Channel class
Further to refactor of RC_Channel class which included
adding get_xx set_xx methods, change reads and writes to the public members
to calls to get and set functionsss
old public member(int16_t) get function -> int16_t set function (int16_t)
(expression where c is an object of type RC_Channel)
c.radio_in c.get_radio_in() c.set_radio_in(v)
c.control_in c.get_control_in() c.set_control_in(v)
c.servo_out c.get_servo_out() c.set_servo_out(v)
c.pwm_out c.get_pwm_out() // use existing
c.radio_out c.get_radio_out() c.set_radio_out(v)
c.radio_max c.get_radio_max() c.set_radio_max(v)
c.radio_min c.get_radio_min() c.set_radio_min(v)
c.radio_trim c.get_radio_trim() c.set_radio_trim(v);
c.min_max_configured() // return true if min and max are configured
Because data members of RC_Channels are now private and so cannot be written directly
some overloads are provided in the Plane classes to provide the old functionality
new overload Plane::stick_mix_channel(RC_Channel *channel)
which forwards to the previously existing
void stick_mix_channel(RC_Channel *channel, int16_t &servo_out);
new overload Plane::channel_output_mixer(Rc_Channel* , RC_Channel*)const
which forwards to
(uint8_t mixing_type, int16_t & chan1, int16_t & chan2)const;
Rename functions
RC_Channel_aux::set_radio_trim(Aux_servo_function_t function)
to RC_Channel_aux::set_trim_to_radio_in_for(Aux_servo_function_t function)
RC_Channel_aux::set_servo_out(Aux_servo_function_t function, int16_t value)
to RC_Channel_aux::set_servo_out_for(Aux_servo_function_t function, int16_t value)
Rationale:
RC_Channel is a complicated class, which combines
several functionalities dealing with stick inputs
in pwm and logical units, logical and actual actuator
outputs, unit conversion etc, etc
The intent of this PR is to clarify existing use of
the class. At the basic level it should now be possible
to grep all places where private variable is set by
searching for the set_xx function.
(The wider purpose is to provide a more generic and
logically simpler method of output mixing. This is a small step)
2016-05-08 05:46:59 -03:00
target_yaw_rate = get_pilot_desired_yaw_rate ( channel_yaw - > get_control_in ( ) ) ;
2015-05-04 23:34:21 -03:00
if ( ! is_zero ( target_yaw_rate ) ) {
2017-12-25 23:55:42 -04:00
auto_yaw . set_mode ( AUTO_YAW_HOLD ) ;
2014-01-25 04:24:43 -04:00
}
}
2016-01-13 03:11:50 -04:00
// set motors to full range
2019-04-09 09:16:58 -03:00
motors - > set_desired_spool_state ( AP_Motors : : DesiredSpoolState : : THROTTLE_UNLIMITED ) ;
2016-01-13 03:11:50 -04:00
2014-01-25 04:24:43 -04:00
// run waypoint controller
2018-02-07 22:21:09 -04:00
copter . failsafe_terrain_set_status ( wp_nav - > update_wpnav ( ) ) ;
2014-01-25 04:24:43 -04:00
// call z-axis position controller (wpnav should have already updated it's alt target)
2017-01-09 03:31:26 -04:00
pos_control - > update_z_controller ( ) ;
2014-01-25 04:24:43 -04:00
// call attitude controller
2017-12-25 23:55:42 -04:00
if ( auto_yaw . mode ( ) = = AUTO_YAW_HOLD ) {
2014-01-25 04:24:43 -04:00
// roll & pitch from waypoint controller, yaw rate from pilot
2017-06-26 05:48:04 -03:00
attitude_control - > input_euler_angle_roll_pitch_euler_rate_yaw ( wp_nav - > get_roll ( ) , wp_nav - > get_pitch ( ) , target_yaw_rate ) ;
2014-01-25 04:24:43 -04:00
} else {
// roll, pitch from waypoint controller, yaw heading from auto_heading()
2017-12-25 23:55:42 -04:00
attitude_control - > input_euler_angle_roll_pitch_yaw ( wp_nav - > get_roll ( ) , wp_nav - > get_pitch ( ) , auto_yaw . yaw ( ) , true ) ;
2014-01-25 04:24:43 -04:00
}
// check if we've completed this stage of RTL
2016-03-22 03:42:17 -03:00
_state_complete = wp_nav - > reached_wp_destination ( ) ;
2014-01-25 04:24:43 -04:00
}
2016-04-22 08:44:57 -03:00
// rtl_loiterathome_start - initialise return to home
2019-05-09 23:18:49 -03:00
void ModeRTL : : loiterathome_start ( )
2014-01-25 04:24:43 -04:00
{
2016-03-22 03:42:17 -03:00
_state = RTL_LoiterAtHome ;
_state_complete = false ;
_loiter_start_time = millis ( ) ;
2014-01-25 04:24:43 -04:00
// yaw back to initial take-off heading yaw unless pilot has already overridden yaw
2017-12-25 23:55:42 -04:00
if ( auto_yaw . default_mode ( true ) ! = AUTO_YAW_HOLD ) {
auto_yaw . set_mode ( AUTO_YAW_RESETTOARMEDYAW ) ;
2014-01-25 04:24:43 -04:00
} else {
2017-12-25 23:55:42 -04:00
auto_yaw . set_mode ( AUTO_YAW_HOLD ) ;
2014-01-25 04:24:43 -04:00
}
}
// rtl_climb_return_descent_run - implements the initial climb, return home and descent portions of RTL which all rely on the wp controller
// called by rtl_run at 100hz or more
2019-05-09 23:18:49 -03:00
void ModeRTL : : loiterathome_run ( )
2014-01-25 04:24:43 -04:00
{
2019-02-28 05:03:23 -04:00
// if not armed set throttle to zero and exit immediately
2019-04-08 05:15:57 -03:00
if ( is_disarmed_or_landed ( ) ) {
2019-03-14 20:45:00 -03:00
make_safe_spool_down ( ) ;
2014-01-25 04:24:43 -04:00
return ;
}
// process pilot's yaw input
float target_yaw_rate = 0 ;
2020-11-12 20:15:53 -04:00
if ( ! copter . failsafe . radio & & use_pilot_yaw ( ) ) {
2014-01-25 04:24:43 -04:00
// get pilot's desired yaw rate
ArduCopter: Fix up after refactoring RC_Channel class
Further to refactor of RC_Channel class which included
adding get_xx set_xx methods, change reads and writes to the public members
to calls to get and set functionsss
old public member(int16_t) get function -> int16_t set function (int16_t)
(expression where c is an object of type RC_Channel)
c.radio_in c.get_radio_in() c.set_radio_in(v)
c.control_in c.get_control_in() c.set_control_in(v)
c.servo_out c.get_servo_out() c.set_servo_out(v)
c.pwm_out c.get_pwm_out() // use existing
c.radio_out c.get_radio_out() c.set_radio_out(v)
c.radio_max c.get_radio_max() c.set_radio_max(v)
c.radio_min c.get_radio_min() c.set_radio_min(v)
c.radio_trim c.get_radio_trim() c.set_radio_trim(v);
c.min_max_configured() // return true if min and max are configured
Because data members of RC_Channels are now private and so cannot be written directly
some overloads are provided in the Plane classes to provide the old functionality
new overload Plane::stick_mix_channel(RC_Channel *channel)
which forwards to the previously existing
void stick_mix_channel(RC_Channel *channel, int16_t &servo_out);
new overload Plane::channel_output_mixer(Rc_Channel* , RC_Channel*)const
which forwards to
(uint8_t mixing_type, int16_t & chan1, int16_t & chan2)const;
Rename functions
RC_Channel_aux::set_radio_trim(Aux_servo_function_t function)
to RC_Channel_aux::set_trim_to_radio_in_for(Aux_servo_function_t function)
RC_Channel_aux::set_servo_out(Aux_servo_function_t function, int16_t value)
to RC_Channel_aux::set_servo_out_for(Aux_servo_function_t function, int16_t value)
Rationale:
RC_Channel is a complicated class, which combines
several functionalities dealing with stick inputs
in pwm and logical units, logical and actual actuator
outputs, unit conversion etc, etc
The intent of this PR is to clarify existing use of
the class. At the basic level it should now be possible
to grep all places where private variable is set by
searching for the set_xx function.
(The wider purpose is to provide a more generic and
logically simpler method of output mixing. This is a small step)
2016-05-08 05:46:59 -03:00
target_yaw_rate = get_pilot_desired_yaw_rate ( channel_yaw - > get_control_in ( ) ) ;
2015-05-04 23:34:21 -03:00
if ( ! is_zero ( target_yaw_rate ) ) {
2017-12-25 23:55:42 -04:00
auto_yaw . set_mode ( AUTO_YAW_HOLD ) ;
2014-01-25 04:24:43 -04:00
}
}
2016-01-13 03:11:50 -04:00
// set motors to full range
2019-04-09 09:16:58 -03:00
motors - > set_desired_spool_state ( AP_Motors : : DesiredSpoolState : : THROTTLE_UNLIMITED ) ;
2016-01-13 03:11:50 -04:00
2014-01-25 04:24:43 -04:00
// run waypoint controller
2018-02-07 22:21:09 -04:00
copter . failsafe_terrain_set_status ( wp_nav - > update_wpnav ( ) ) ;
2014-01-25 04:24:43 -04:00
// call z-axis position controller (wpnav should have already updated it's alt target)
2017-01-09 03:31:26 -04:00
pos_control - > update_z_controller ( ) ;
2014-01-25 04:24:43 -04:00
// call attitude controller
2017-12-25 23:55:42 -04:00
if ( auto_yaw . mode ( ) = = AUTO_YAW_HOLD ) {
2014-01-25 04:24:43 -04:00
// roll & pitch from waypoint controller, yaw rate from pilot
2017-06-26 05:48:04 -03:00
attitude_control - > input_euler_angle_roll_pitch_euler_rate_yaw ( wp_nav - > get_roll ( ) , wp_nav - > get_pitch ( ) , target_yaw_rate ) ;
2014-01-25 04:24:43 -04:00
} else {
// roll, pitch from waypoint controller, yaw heading from auto_heading()
2017-12-25 23:55:42 -04:00
attitude_control - > input_euler_angle_roll_pitch_yaw ( wp_nav - > get_roll ( ) , wp_nav - > get_pitch ( ) , auto_yaw . yaw ( ) , true ) ;
2014-01-25 04:24:43 -04:00
}
// check if we've completed this stage of RTL
2016-03-22 03:42:17 -03:00
if ( ( millis ( ) - _loiter_start_time ) > = ( uint32_t ) g . rtl_loiter_time . get ( ) ) {
2017-12-25 23:55:42 -04:00
if ( auto_yaw . mode ( ) = = AUTO_YAW_RESETTOARMEDYAW ) {
2014-04-24 06:52:21 -03:00
// check if heading is within 2 degrees of heading when vehicle was armed
2019-09-09 02:34:39 -03:00
if ( abs ( wrap_180_cd ( ahrs . yaw_sensor - copter . initial_armed_bearing ) ) < = 200 ) {
2016-03-22 03:42:17 -03:00
_state_complete = true ;
2014-04-24 06:52:21 -03:00
}
} else {
// we have loitered long enough
2016-03-22 03:42:17 -03:00
_state_complete = true ;
2014-04-24 06:52:21 -03:00
}
}
2014-01-25 04:24:43 -04:00
}
2014-04-25 02:15:57 -03:00
// rtl_descent_start - initialise descent to final alt
2019-05-09 23:18:49 -03:00
void ModeRTL : : descent_start ( )
2014-04-25 02:15:57 -03:00
{
2016-03-22 03:42:17 -03:00
_state = RTL_FinalDescent ;
_state_complete = false ;
2014-04-25 02:15:57 -03:00
// Set wp navigation target to above home
2018-03-27 23:13:37 -03:00
loiter_nav - > init_target ( wp_nav - > get_wp_destination ( ) ) ;
2014-04-25 02:15:57 -03:00
// initialise altitude target to stopping point
2017-01-09 03:31:26 -04:00
pos_control - > set_target_to_stopping_point_z ( ) ;
2014-04-25 02:15:57 -03:00
// initialise yaw
2017-12-25 23:55:42 -04:00
auto_yaw . set_mode ( AUTO_YAW_HOLD ) ;
2020-02-20 23:08:26 -04:00
2021-02-06 23:29:33 -04:00
# if LANDING_GEAR_ENABLED == ENABLED
2020-02-20 23:08:26 -04:00
// optionally deploy landing gear
copter . landinggear . deploy_for_landing ( ) ;
2021-02-06 23:29:33 -04:00
# endif
2021-02-19 08:47:28 -04:00
# if AC_FENCE == ENABLED
// disable the fence on landing
copter . fence . auto_disable_fence_for_landing ( ) ;
# endif
2014-04-25 02:15:57 -03:00
}
// rtl_descent_run - implements the final descent to the RTL_ALT
// called by rtl_run at 100hz or more
2019-05-09 23:18:49 -03:00
void ModeRTL : : descent_run ( )
2014-04-25 02:15:57 -03:00
{
2018-02-02 22:56:44 -04:00
float target_roll = 0.0f ;
float target_pitch = 0.0f ;
float target_yaw_rate = 0.0f ;
2014-07-06 06:05:43 -03:00
2019-02-28 05:03:23 -04:00
// if not armed set throttle to zero and exit immediately
2019-04-08 05:15:57 -03:00
if ( is_disarmed_or_landed ( ) ) {
2019-03-14 20:45:00 -03:00
make_safe_spool_down ( ) ;
2014-04-25 02:15:57 -03:00
return ;
}
// process pilot's input
2018-02-07 22:21:09 -04: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 ) {
2019-10-25 03:06:05 -03:00
AP : : logger ( ) . Write_Event ( LogEvent : : LAND_CANCELLED_BY_PILOT ) ;
2016-01-06 17:39:36 -04:00
// exit land if throttle is high
2019-10-17 00:49:22 -03:00
if ( ! copter . set_mode ( Mode : : Number : : LOITER , ModeReason : : THROTTLE_LAND_ESCAPE ) ) {
copter . set_mode ( Mode : : Number : : ALT_HOLD , ModeReason : : THROTTLE_LAND_ESCAPE ) ;
2016-01-06 17:39:36 -04:00
}
}
2014-07-06 06:05:43 -03:00
if ( g . land_repositioning ) {
// apply SIMPLE mode transform to pilot inputs
update_simple_mode ( ) ;
2014-04-25 02:15:57 -03:00
2018-02-02 22:56:44 -04:00
// 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-02-02 22:56:44 -04:00
2019-03-25 20:57:55 -03:00
// record if pilot has overridden roll or pitch
2018-02-02 22:56:44 -04:00
if ( ! is_zero ( target_roll ) | | ! is_zero ( target_pitch ) ) {
2019-05-09 23:18:49 -03:00
if ( ! copter . ap . land_repo_active ) {
2019-10-25 03:06:05 -03:00
AP : : 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 ;
2018-02-02 22:56:44 -04:00
}
2014-07-06 06:05:43 -03:00
}
2014-04-25 02:15:57 -03:00
2020-11-12 20:15:53 -04:00
if ( g . land_repositioning | | use_pilot_yaw ( ) ) {
// get pilot's desired yaw rate
target_yaw_rate = get_pilot_desired_yaw_rate ( channel_yaw - > get_control_in ( ) ) ;
}
2014-04-25 02:15:57 -03:00
}
2016-01-13 03:11:50 -04:00
// set motors to full range
2019-04-09 09:16:58 -03:00
motors - > set_desired_spool_state ( AP_Motors : : DesiredSpoolState : : THROTTLE_UNLIMITED ) ;
2016-01-13 03:11:50 -04:00
2014-07-06 06:05:43 -03:00
// process roll, pitch inputs
2018-03-27 23:13:37 -03:00
loiter_nav - > set_pilot_desired_acceleration ( target_roll , target_pitch , G_Dt ) ;
2014-07-06 06:05:43 -03:00
2014-04-25 02:15:57 -03:00
// run loiter controller
2018-09-05 03:47:50 -03:00
loiter_nav - > update ( ) ;
2014-04-25 02:15:57 -03:00
// call z-axis position controller
2017-01-09 03:31:26 -04:00
pos_control - > set_alt_target_with_slew ( rtl_path . descent_target . alt , G_Dt ) ;
pos_control - > update_z_controller ( ) ;
2014-04-25 02:15:57 -03:00
// roll & pitch from waypoint controller, yaw rate from pilot
2018-03-27 23:13:37 -03:00
attitude_control - > input_euler_angle_roll_pitch_euler_rate_yaw ( loiter_nav - > get_roll ( ) , loiter_nav - > get_pitch ( ) , target_yaw_rate ) ;
2014-04-25 02:15:57 -03:00
// check if we've reached within 20cm of final altitude
2018-02-07 22:21:09 -04:00
_state_complete = labs ( rtl_path . descent_target . alt - copter . current_loc . alt ) < 20 ;
2014-04-25 02:15:57 -03:00
}
2014-01-25 04:24:43 -04:00
// rtl_loiterathome_start - initialise controllers to loiter over home
2019-05-09 23:18:49 -03:00
void ModeRTL : : land_start ( )
2014-01-25 04:24:43 -04:00
{
2016-03-22 03:42:17 -03:00
_state = RTL_Land ;
_state_complete = false ;
2014-01-25 04:24:43 -04:00
// Set wp navigation target to above home
2018-03-27 23:13:37 -03:00
loiter_nav - > init_target ( wp_nav - > get_wp_destination ( ) ) ;
2014-01-25 04:24:43 -04:00
2016-07-07 21:41:38 -03:00
// initialise position and desired velocity
2017-01-09 03:31:26 -04:00
if ( ! pos_control - > is_active_z ( ) ) {
pos_control - > set_alt_target_to_current_alt ( ) ;
pos_control - > set_desired_velocity_z ( inertial_nav . get_velocity_z ( ) ) ;
2016-10-14 09:28:32 -03:00
}
2014-01-25 04:24:43 -04:00
// initialise yaw
2017-12-25 23:55:42 -04:00
auto_yaw . set_mode ( AUTO_YAW_HOLD ) ;
2020-02-20 23:08:26 -04:00
2021-02-06 23:29:33 -04:00
# if LANDING_GEAR_ENABLED == ENABLED
2020-02-20 23:08:26 -04:00
// optionally deploy landing gear
copter . landinggear . deploy_for_landing ( ) ;
2021-02-06 23:29:33 -04:00
# endif
2021-02-19 08:47:28 -04:00
# if AC_FENCE == ENABLED
// disable the fence on landing
copter . fence . auto_disable_fence_for_landing ( ) ;
# endif
2014-01-25 04:24:43 -04:00
}
2019-05-09 23:18:49 -03:00
bool ModeRTL : : is_landing ( ) const
2018-04-30 06:50:04 -03:00
{
return _state = = RTL_Land ;
}
2014-01-25 04:24:43 -04:00
// rtl_returnhome_run - return home
// called by rtl_run at 100hz or more
2019-05-09 23:18:49 -03:00
void ModeRTL : : land_run ( bool disarm_on_land )
2014-01-25 04:24:43 -04:00
{
2019-02-28 05:03:23 -04:00
// check if we've completed this stage of RTL
2019-05-09 23:18:49 -03:00
_state_complete = copter . ap . land_complete ;
2019-02-28 05:03:23 -04:00
// disarm when the landing detector says we've landed
2019-05-09 23:18:49 -03:00
if ( disarm_on_land & & copter . ap . land_complete & & motors - > get_spool_state ( ) = = AP_Motors : : SpoolState : : GROUND_IDLE ) {
2020-02-21 09:09:57 -04:00
copter . arming . disarm ( AP_Arming : : Method : : LANDED ) ;
2019-02-28 05:03:23 -04:00
}
2014-09-12 02:15:38 -03:00
2019-02-28 05:03:23 -04:00
// if not armed set throttle to zero and exit immediately
2019-04-08 05:15:57 -03:00
if ( is_disarmed_or_landed ( ) ) {
2019-03-14 20:45:00 -03:00
make_safe_spool_down ( ) ;
2019-07-18 08:06:09 -03:00
loiter_nav - > clear_pilot_desired_acceleration ( ) ;
2019-02-28 02:16:19 -04:00
loiter_nav - > init_target ( ) ;
2014-01-25 04:24:43 -04:00
return ;
}
2016-01-13 03:11:50 -04:00
// set motors to full range
2019-04-09 09:16:58 -03:00
motors - > set_desired_spool_state ( AP_Motors : : DesiredSpoolState : : THROTTLE_UNLIMITED ) ;
2016-01-13 03:11:50 -04:00
2018-03-19 14:26:35 -03:00
land_run_horizontal_control ( ) ;
land_run_vertical_control ( ) ;
2014-01-24 02:47:42 -04:00
}
2019-05-09 23:18:49 -03:00
void ModeRTL : : build_path ( )
2016-01-06 02:52:20 -04:00
{
// origin point is our stopping point
2016-03-18 07:44:09 -03:00
Vector3f stopping_point ;
2017-01-09 03:31:26 -04:00
pos_control - > get_stopping_point_xy ( stopping_point ) ;
pos_control - > get_stopping_point_z ( stopping_point ) ;
2019-01-01 22:54:31 -04:00
rtl_path . origin_point = Location ( stopping_point ) ;
2019-03-14 22:44:27 -03:00
rtl_path . origin_point . change_alt_frame ( Location : : AltFrame : : ABOVE_HOME ) ;
2016-01-06 02:52:20 -04:00
2016-06-16 12:13:57 -03:00
// compute return target
2018-10-25 23:10:32 -03:00
compute_return_target ( ) ;
2016-01-06 02:52:20 -04:00
// climb target is above our origin point at the return altitude
2019-01-01 22:54:31 -04:00
rtl_path . climb_target = Location ( rtl_path . origin_point . lat , rtl_path . origin_point . lng , rtl_path . return_target . alt , rtl_path . return_target . get_alt_frame ( ) ) ;
2016-01-06 02:52:20 -04:00
// descent target is below return target at rtl_alt_final
2019-03-14 22:44:27 -03:00
rtl_path . descent_target = Location ( rtl_path . return_target . lat , rtl_path . return_target . lng , g . rtl_alt_final , Location : : AltFrame : : ABOVE_HOME ) ;
2016-01-06 02:52:20 -04:00
// set land flag
rtl_path . land = g . rtl_alt_final < = 0 ;
}
2016-06-16 12:13:57 -03:00
// compute the return target - home or rally point
2016-06-16 11:39:07 -03:00
// return target's altitude is updated to a higher altitude that the vehicle can safely return at (frame may also be set)
2019-05-09 23:18:49 -03:00
void ModeRTL : : compute_return_target ( )
2014-02-17 06:49:30 -04:00
{
2016-07-04 03:54:51 -03:00
// set return target to nearest rally point or home position (Note: alt is absolute)
2016-06-16 12:13:57 -03:00
# if AC_RALLY == ENABLED
2018-02-07 22:21:09 -04:00
rtl_path . return_target = copter . rally . calc_best_rally_or_home_location ( copter . current_loc , ahrs . get_home ( ) . alt ) ;
2016-06-16 12:13:57 -03:00
# else
rtl_path . return_target = ahrs . get_home ( ) ;
# endif
2016-03-18 07:44:09 -03:00
// curr_alt is current altitude above home or above terrain depending upon use_terrain
2018-02-07 22:21:09 -04:00
int32_t curr_alt = copter . current_loc . alt ;
2016-03-18 07:44:09 -03:00
2019-12-11 23:36:49 -04:00
// determine altitude type of return journey (alt-above-home, alt-above-terrain using range finder or alt-above-terrain using terrain database)
2020-09-02 20:39:23 -03:00
ReturnTargetAltType alt_type = ReturnTargetAltType : : RELATIVE ;
2019-12-11 23:36:49 -04:00
if ( terrain_following_allowed & & ( get_alt_type ( ) = = RTLAltType : : RTL_ALTTYPE_TERRAIN ) ) {
// convert RTL_ALT_TYPE and WPNAV_RFNG_USE parameters to ReturnTargetAltType
switch ( wp_nav - > get_terrain_source ( ) ) {
case AC_WPNav : : TerrainSource : : TERRAIN_UNAVAILABLE :
2020-09-02 20:39:23 -03:00
alt_type = ReturnTargetAltType : : RELATIVE ;
2019-12-11 23:36:49 -04:00
AP : : logger ( ) . Write_Error ( LogErrorSubsystem : : NAVIGATION , LogErrorCode : : RTL_MISSING_RNGFND ) ;
gcs ( ) . send_text ( MAV_SEVERITY_CRITICAL , " RTL: no terrain data, using alt-above-home " ) ;
break ;
case AC_WPNav : : TerrainSource : : TERRAIN_FROM_RANGEFINDER :
2020-09-02 20:39:23 -03:00
alt_type = ReturnTargetAltType : : RANGEFINDER ;
2019-12-11 23:36:49 -04:00
break ;
case AC_WPNav : : TerrainSource : : TERRAIN_FROM_TERRAINDATABASE :
2020-09-02 20:39:23 -03:00
alt_type = ReturnTargetAltType : : TERRAINDATABASE ;
2019-12-11 23:36:49 -04:00
break ;
}
}
// set curr_alt and return_target.alt from range finder
2020-09-02 20:39:23 -03:00
if ( alt_type = = ReturnTargetAltType : : RANGEFINDER ) {
2020-02-18 18:22:31 -04:00
if ( copter . get_rangefinder_height_interpolated_cm ( curr_alt ) ) {
2019-12-11 23:36:49 -04:00
// set return_target.alt
rtl_path . return_target . set_alt_cm ( MAX ( curr_alt + MAX ( 0 , g . rtl_climb_min ) , MAX ( g . rtl_altitude , RTL_ALT_MIN ) ) , Location : : AltFrame : : ABOVE_TERRAIN ) ;
} else {
// fallback to relative alt and warn user
2020-09-02 20:39:23 -03:00
alt_type = ReturnTargetAltType : : RELATIVE ;
2019-12-11 23:36:49 -04:00
gcs ( ) . send_text ( MAV_SEVERITY_CRITICAL , " RTL: rangefinder unhealthy, using alt-above-home " ) ;
AP : : logger ( ) . Write_Error ( LogErrorSubsystem : : NAVIGATION , LogErrorCode : : RTL_MISSING_RNGFND ) ;
}
}
// set curr_alt and return_target.alt from terrain database
2020-09-02 20:39:23 -03:00
if ( alt_type = = ReturnTargetAltType : : TERRAINDATABASE ) {
2019-12-11 23:36:49 -04:00
// set curr_alt to current altitude above terrain
// convert return_target.alt from an abs (above MSL) to altitude above terrain
// Note: the return_target may be a rally point with the alt set above the terrain alt (like the top of a building)
int32_t curr_terr_alt ;
if ( copter . current_loc . get_alt_cm ( Location : : AltFrame : : ABOVE_TERRAIN , curr_terr_alt ) & &
rtl_path . return_target . change_alt_frame ( Location : : AltFrame : : ABOVE_TERRAIN ) ) {
curr_alt = curr_terr_alt ;
} else {
// fallback to relative alt and warn user
2020-09-02 20:39:23 -03:00
alt_type = ReturnTargetAltType : : RELATIVE ;
2019-03-24 22:31:46 -03:00
AP : : logger ( ) . Write_Error ( LogErrorSubsystem : : TERRAIN , LogErrorCode : : MISSING_TERRAIN_DATA ) ;
2019-12-11 23:36:49 -04:00
gcs ( ) . send_text ( MAV_SEVERITY_CRITICAL , " RTL: no terrain data, using alt-above-home " ) ;
2016-03-18 07:44:09 -03:00
}
}
2019-12-11 23:36:49 -04:00
// for the default case we must convert return-target alt (which is an absolute alt) to alt-above-home
2020-09-02 20:39:23 -03:00
if ( alt_type = = ReturnTargetAltType : : RELATIVE ) {
2019-03-14 22:44:27 -03:00
if ( ! rtl_path . return_target . change_alt_frame ( Location : : AltFrame : : ABOVE_HOME ) ) {
2016-07-02 02:39:11 -03:00
// this should never happen but just in case
2019-03-14 22:44:27 -03:00
rtl_path . return_target . set_alt_cm ( 0 , Location : : AltFrame : : ABOVE_HOME ) ;
2019-12-11 23:36:49 -04:00
gcs ( ) . send_text ( MAV_SEVERITY_WARNING , " RTL: unexpected error calculating target alt " ) ;
2016-07-02 02:39:11 -03:00
}
}
// set new target altitude to return target altitude
2019-12-11 23:36:49 -04:00
// Note: this is alt-above-home or terrain-alt depending upon rtl_alt_type
2016-07-02 02:39:11 -03:00
// Note: ignore negative altitudes which could happen if user enters negative altitude for rally point or terrain is higher at rally point compared to home
int32_t target_alt = MAX ( rtl_path . return_target . alt , 0 ) ;
// increase target to maximum of current altitude + climb_min and rtl altitude
target_alt = MAX ( target_alt , curr_alt + MAX ( 0 , g . rtl_climb_min ) ) ;
target_alt = MAX ( target_alt , MAX ( g . rtl_altitude , RTL_ALT_MIN ) ) ;
2014-04-27 03:35:32 -03:00
2016-07-02 02:39:11 -03:00
// reduce climb if close to return target
float rtl_return_dist_cm = rtl_path . return_target . get_distance ( rtl_path . origin_point ) * 100.0f ;
2016-03-18 07:44:09 -03:00
// don't allow really shallow slopes
if ( g . rtl_cone_slope > = RTL_MIN_CONE_SLOPE ) {
2016-07-02 02:39:11 -03:00
target_alt = MAX ( curr_alt , MIN ( target_alt , MAX ( rtl_return_dist_cm * g . rtl_cone_slope , curr_alt + RTL_ABS_MIN_CLIMB ) ) ) ;
2016-01-06 03:00:29 -04:00
}
2019-12-11 23:36:49 -04:00
// set returned target alt to new target_alt (don't change altitude type)
2020-09-02 20:39:23 -03:00
rtl_path . return_target . set_alt_cm ( target_alt , ( alt_type = = ReturnTargetAltType : : RELATIVE ) ? Location : : AltFrame : : ABOVE_HOME : Location : : AltFrame : : ABOVE_TERRAIN ) ;
2016-06-16 12:13:57 -03:00
2014-04-27 03:35:32 -03:00
# if AC_FENCE == ENABLED
// ensure not above fence altitude if alt fence is enabled
2016-07-04 03:54:51 -03:00
// Note: because the rtl_path.climb_target's altitude is simply copied from the return_target's altitude,
// if terrain altitudes are being used, the code below which reduces the return_target's altitude can lead to
// the vehicle not climbing at all as RTL begins. This can be overly conservative and it might be better
// to apply the fence alt limit independently on the origin_point and return_target
2018-02-07 22:21:09 -04:00
if ( ( copter . fence . get_enabled_fences ( ) & AC_FENCE_TYPE_ALT_MAX ) ! = 0 ) {
2016-07-02 02:39:11 -03:00
// get return target as alt-above-home so it can be compared to fence's alt
2019-03-14 22:44:27 -03:00
if ( rtl_path . return_target . get_alt_cm ( Location : : AltFrame : : ABOVE_HOME , target_alt ) ) {
2018-02-07 22:21:09 -04:00
float fence_alt = copter . fence . get_safe_alt_max ( ) * 100.0f ;
2016-07-02 02:39:11 -03:00
if ( target_alt > fence_alt ) {
// reduce target alt to the fence alt
rtl_path . return_target . alt - = ( target_alt - fence_alt ) ;
}
}
2014-04-27 03:35:32 -03:00
}
# endif
2016-03-18 07:44:09 -03:00
// ensure we do not descend
2016-07-02 02:39:11 -03:00
rtl_path . return_target . alt = MAX ( rtl_path . return_target . alt , curr_alt ) ;
2016-01-06 02:52:20 -04:00
}
2018-02-07 22:21:09 -04:00
2019-06-05 07:47:32 -03:00
bool ModeRTL : : get_wp ( Location & destination )
{
// provide target in states which use wp_nav
switch ( _state ) {
case RTL_Starting :
case RTL_InitialClimb :
case RTL_ReturnHome :
case RTL_LoiterAtHome :
case RTL_FinalDescent :
return wp_nav - > get_oa_wp_destination ( destination ) ;
case RTL_Land :
return false ;
}
// we should never get here but just in case
return false ;
}
2019-05-09 23:18:49 -03:00
uint32_t ModeRTL : : wp_distance ( ) const
2018-02-07 22:21:09 -04:00
{
return wp_nav - > get_wp_distance_to_destination ( ) ;
}
2019-05-09 23:18:49 -03:00
int32_t ModeRTL : : wp_bearing ( ) const
2018-02-07 22:21:09 -04:00
{
return wp_nav - > get_wp_bearing_to_destination ( ) ;
}
2019-02-25 10:32:52 -04:00
2020-11-12 20:15:53 -04:00
// returns true if pilot's yaw input should be used to adjust vehicle's heading
bool ModeRTL : : use_pilot_yaw ( void ) const
{
return ( copter . g2 . rtl_options . get ( ) & uint32_t ( Options : : IgnorePilotYaw ) ) = = 0 ;
}
2019-02-25 10:32:52 -04:00
# endif