2014-01-24 02:47:42 -04:00
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
2015-05-29 23:12:49 -03:00
# include "Copter.h"
2014-01-24 02:47:42 -04:00
/*
* control_rtl . pde - 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
2015-05-29 23:12:49 -03:00
bool Copter : : rtl_init ( bool ignore_checks )
2014-01-24 02:47:42 -04:00
{
2015-01-02 07:43:50 -04:00
if ( position_ok ( ) | | ignore_checks ) {
2016-04-22 08:44:57 -03:00
rtl_build_path ( true ) ;
2014-01-25 04:24:43 -04:00
rtl_climb_start ( ) ;
2014-01-24 02:47:42 -04:00
return true ;
} else {
return false ;
}
}
2016-04-22 08:44:57 -03:00
// re-start RTL with terrain following disabled
void Copter : : rtl_restart_without_terrain ( )
{
// log an error
Log_Write_Error ( ERROR_SUBSYSTEM_NAVIGATION , ERROR_CODE_RESTARTED_RTL ) ;
if ( rtl_path . terrain_used ) {
rtl_build_path ( false ) ;
rtl_climb_start ( ) ;
gcs_send_text ( MAV_SEVERITY_CRITICAL , " Restarting RTL - Terrain data missing " ) ;
}
}
2014-01-24 02:47:42 -04:00
// rtl_run - runs the return-to-launch controller
// should be called at 100hz or more
2015-05-29 23:12:49 -03:00
void Copter : : rtl_run ( )
2014-01-24 02:47:42 -04:00
{
2014-01-25 04:24:43 -04:00
// check if we need to move to next state
if ( rtl_state_complete ) {
switch ( rtl_state ) {
2015-05-17 22:37:32 -03:00
case RTL_InitialClimb :
2014-01-25 04:24:43 -04:00
rtl_return_start ( ) ;
break ;
2015-05-17 22:37:32 -03:00
case RTL_ReturnHome :
2014-01-25 04:24:43 -04:00
rtl_loiterathome_start ( ) ;
break ;
2015-05-17 22:37:32 -03:00
case RTL_LoiterAtHome :
2016-01-06 02:52:20 -04:00
if ( rtl_path . land | | failsafe . radio ) {
2014-01-25 04:24:43 -04:00
rtl_land_start ( ) ;
2016-01-06 02:52:20 -04:00
} else {
rtl_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
switch ( rtl_state ) {
2015-05-17 22:37:32 -03:00
case RTL_InitialClimb :
2014-04-25 02:15:57 -03:00
rtl_climb_return_run ( ) ;
2014-01-25 04:24:43 -04:00
break ;
2015-05-17 22:37:32 -03:00
case RTL_ReturnHome :
2014-04-25 02:15:57 -03:00
rtl_climb_return_run ( ) ;
2014-01-25 04:24:43 -04:00
break ;
2015-05-17 22:37:32 -03:00
case RTL_LoiterAtHome :
2014-01-25 04:24:43 -04:00
rtl_loiterathome_run ( ) ;
break ;
2015-05-17 22:37:32 -03:00
case RTL_FinalDescent :
2014-04-25 02:15:57 -03:00
rtl_descent_run ( ) ;
2014-01-25 04:24:43 -04:00
break ;
2015-05-17 22:37:32 -03:00
case RTL_Land :
2014-01-25 04:24:43 -04:00
rtl_land_run ( ) ;
break ;
}
}
// rtl_climb_start - initialise climb to RTL altitude
2015-05-29 23:12:49 -03:00
void Copter : : rtl_climb_start ( )
2014-01-25 04:24:43 -04:00
{
2015-05-17 22:37:32 -03:00
rtl_state = RTL_InitialClimb ;
2014-01-25 04:24:43 -04:00
rtl_state_complete = false ;
2014-05-07 03:03:00 -03:00
// initialise waypoint and spline controller
wp_nav . wp_and_spline_init ( ) ;
2015-10-19 21:19:37 -03:00
// RTL_SPEED == 0 means use WPNAV_SPEED
if ( ! is_zero ( g . rtl_speed_cms ) ) {
wp_nav . set_speed_xy ( g . rtl_speed_cms ) ;
}
2014-05-07 03:03:00 -03:00
// set the destination
2016-03-18 07:44:09 -03: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
2016-03-18 07:44:09 -03:00
Log_Write_Error ( ERROR_SUBSYSTEM_NAVIGATION , ERROR_CODE_FAILED_TO_SET_DESTINATION ) ;
2016-04-22 08:44:57 -03:00
set_mode ( LAND , MODE_REASON_TERRAIN_FAILSAFE ) ;
return ;
2016-03-18 07:44:09 -03:00
}
2014-05-07 03:03:00 -03:00
wp_nav . set_fast_waypoint ( true ) ;
2014-01-25 04:24:43 -04:00
// hold current yaw during initial climb
set_auto_yaw_mode ( AUTO_YAW_HOLD ) ;
}
// rtl_return_start - initialise return to home
2015-05-29 23:12:49 -03:00
void Copter : : rtl_return_start ( )
2014-01-25 04:24:43 -04:00
{
2015-05-17 22:37:32 -03:00
rtl_state = RTL_ReturnHome ;
2014-01-25 04:24:43 -04:00
rtl_state_complete = false ;
2016-03-18 07:44:09 -03: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
rtl_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)
set_auto_yaw_mode ( get_default_auto_yaw_mode ( true ) ) ;
}
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
2015-05-29 23:12:49 -03:00
void Copter : : rtl_climb_return_run ( )
2014-01-25 04:24:43 -04:00
{
2015-04-17 14:49:08 -03:00
// if not auto armed or motor interlock not enabled set throttle to zero and exit immediately
2016-01-13 03:11:50 -04:00
if ( ! motors . armed ( ) | | ! ap . auto_armed | | ! motors . get_interlock ( ) ) {
2015-07-01 15:38:32 -03:00
# if FRAME_CONFIG == HELI_FRAME // Helicopters always stabilize roll/pitch/yaw
// call attitude controller
2015-11-28 13:57:14 -04:00
attitude_control . input_euler_angle_roll_pitch_euler_rate_yaw_smooth ( 0 , 0 , 0 , get_smoothing_gain ( ) ) ;
2015-07-01 15:38:32 -03:00
attitude_control . set_throttle_out ( 0 , false , g . throttle_filt ) ;
2016-01-13 03:11:50 -04:00
# else
2016-02-02 08:16:42 -04:00
motors . set_desired_spool_state ( AP_Motors : : DESIRED_SPIN_WHEN_ARMED ) ;
2016-01-13 03:11:50 -04:00
// multicopters do not stabilize roll/pitch/yaw when disarmed
2014-01-25 04:24:43 -04:00
// reset attitude control targets
2015-04-16 01:54:29 -03:00
attitude_control . set_throttle_out_unstabilized ( 0 , true , g . throttle_filt ) ;
2015-07-01 15:38:32 -03:00
# endif
2014-01-25 04:24:43 -04:00
// To-Do: re-initialise wpnav targets
return ;
}
// process pilot's yaw input
float target_yaw_rate = 0 ;
if ( ! failsafe . radio ) {
// get pilot's desired yaw rate
2015-05-19 10:38:57 -03:00
target_yaw_rate = get_pilot_desired_yaw_rate ( channel_yaw - > control_in ) ;
2015-05-04 23:34:21 -03:00
if ( ! is_zero ( target_yaw_rate ) ) {
2014-01-25 04:24:43 -04:00
set_auto_yaw_mode ( AUTO_YAW_HOLD ) ;
}
}
2016-01-13 03:11:50 -04:00
// set motors to full range
2016-02-02 08:16:42 -04:00
motors . set_desired_spool_state ( AP_Motors : : DESIRED_THROTTLE_UNLIMITED ) ;
2016-01-13 03:11:50 -04:00
2014-01-25 04:24:43 -04:00
// run waypoint controller
2016-04-22 08:44:57 -03:00
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)
pos_control . update_z_controller ( ) ;
// call attitude controller
if ( auto_yaw_mode = = AUTO_YAW_HOLD ) {
// roll & pitch from waypoint controller, yaw rate from pilot
2015-11-28 13:57:14 -04: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()
2015-11-28 13:57:14 -04:00
attitude_control . input_euler_angle_roll_pitch_yaw ( wp_nav . get_roll ( ) , wp_nav . get_pitch ( ) , get_auto_heading ( ) , true ) ;
2014-01-25 04:24:43 -04:00
}
// check if we've completed this stage of RTL
rtl_state_complete = wp_nav . reached_wp_destination ( ) ;
}
2016-04-22 08:44:57 -03:00
// rtl_loiterathome_start - initialise return to home
2015-05-29 23:12:49 -03:00
void Copter : : rtl_loiterathome_start ( )
2014-01-25 04:24:43 -04:00
{
2015-05-17 22:37:32 -03:00
rtl_state = RTL_LoiterAtHome ;
2014-01-25 04:24:43 -04:00
rtl_state_complete = false ;
rtl_loiter_start_time = millis ( ) ;
// yaw back to initial take-off heading yaw unless pilot has already overridden yaw
if ( get_default_auto_yaw_mode ( true ) ! = AUTO_YAW_HOLD ) {
set_auto_yaw_mode ( AUTO_YAW_RESETTOARMEDYAW ) ;
} else {
set_auto_yaw_mode ( AUTO_YAW_HOLD ) ;
}
}
// 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
2015-05-29 23:12:49 -03:00
void Copter : : rtl_loiterathome_run ( )
2014-01-25 04:24:43 -04:00
{
2015-04-17 14:49:08 -03:00
// if not auto armed or motor interlock not enabled set throttle to zero and exit immediately
2016-01-13 03:11:50 -04:00
if ( ! motors . armed ( ) | | ! ap . auto_armed | | ! motors . get_interlock ( ) ) {
2015-07-01 15:38:32 -03:00
# if FRAME_CONFIG == HELI_FRAME // Helicopters always stabilize roll/pitch/yaw
// call attitude controller
2015-11-28 13:57:14 -04:00
attitude_control . input_euler_angle_roll_pitch_euler_rate_yaw_smooth ( 0 , 0 , 0 , get_smoothing_gain ( ) ) ;
2015-07-01 15:38:32 -03:00
attitude_control . set_throttle_out ( 0 , false , g . throttle_filt ) ;
2016-01-13 03:11:50 -04:00
# else
2016-02-02 08:16:42 -04:00
motors . set_desired_spool_state ( AP_Motors : : DESIRED_SPIN_WHEN_ARMED ) ;
2016-01-13 03:11:50 -04:00
// multicopters do not stabilize roll/pitch/yaw when disarmed
2014-01-25 04:24:43 -04:00
// reset attitude control targets
2015-04-16 01:54:29 -03:00
attitude_control . set_throttle_out_unstabilized ( 0 , true , g . throttle_filt ) ;
2015-07-01 15:38:32 -03:00
# endif
2014-01-25 04:24:43 -04:00
// To-Do: re-initialise wpnav targets
return ;
}
// process pilot's yaw input
float target_yaw_rate = 0 ;
if ( ! failsafe . radio ) {
// get pilot's desired yaw rate
2015-05-19 10:38:57 -03:00
target_yaw_rate = get_pilot_desired_yaw_rate ( channel_yaw - > control_in ) ;
2015-05-04 23:34:21 -03:00
if ( ! is_zero ( target_yaw_rate ) ) {
2014-01-25 04:24:43 -04:00
set_auto_yaw_mode ( AUTO_YAW_HOLD ) ;
}
}
2016-01-13 03:11:50 -04:00
// set motors to full range
2016-02-02 08:16:42 -04:00
motors . set_desired_spool_state ( AP_Motors : : DESIRED_THROTTLE_UNLIMITED ) ;
2016-01-13 03:11:50 -04:00
2014-01-25 04:24:43 -04:00
// run waypoint controller
2016-04-22 08:44:57 -03:00
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)
pos_control . update_z_controller ( ) ;
// call attitude controller
if ( auto_yaw_mode = = AUTO_YAW_HOLD ) {
// roll & pitch from waypoint controller, yaw rate from pilot
2015-11-28 13:57:14 -04: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()
2015-11-28 13:57:14 -04:00
attitude_control . input_euler_angle_roll_pitch_yaw ( wp_nav . get_roll ( ) , wp_nav . get_pitch ( ) , get_auto_heading ( ) , true ) ;
2014-01-25 04:24:43 -04:00
}
// check if we've completed this stage of RTL
2014-04-24 06:52:21 -03:00
if ( ( millis ( ) - rtl_loiter_start_time ) > = ( uint32_t ) g . rtl_loiter_time . get ( ) ) {
if ( auto_yaw_mode = = AUTO_YAW_RESETTOARMEDYAW ) {
// check if heading is within 2 degrees of heading when vehicle was armed
if ( labs ( wrap_180_cd ( ahrs . yaw_sensor - initial_armed_bearing ) ) < = 200 ) {
rtl_state_complete = true ;
}
} else {
// we have loitered long enough
rtl_state_complete = true ;
}
}
2014-01-25 04:24:43 -04:00
}
2014-04-25 02:15:57 -03:00
// rtl_descent_start - initialise descent to final alt
2015-05-29 23:12:49 -03:00
void Copter : : rtl_descent_start ( )
2014-04-25 02:15:57 -03:00
{
2015-05-17 22:37:32 -03:00
rtl_state = RTL_FinalDescent ;
2014-04-25 02:15:57 -03:00
rtl_state_complete = false ;
// Set wp navigation target to above home
2014-05-15 10:19:18 -03:00
wp_nav . init_loiter_target ( wp_nav . get_wp_destination ( ) ) ;
2014-04-25 02:15:57 -03:00
// initialise altitude target to stopping point
pos_control . set_target_to_stopping_point_z ( ) ;
// initialise yaw
set_auto_yaw_mode ( AUTO_YAW_HOLD ) ;
}
// rtl_descent_run - implements the final descent to the RTL_ALT
// called by rtl_run at 100hz or more
2015-05-29 23:12:49 -03:00
void Copter : : rtl_descent_run ( )
2014-04-25 02:15:57 -03:00
{
2014-07-06 06:05:43 -03:00
int16_t roll_control = 0 , pitch_control = 0 ;
float target_yaw_rate = 0 ;
2015-04-17 14:49:08 -03:00
// if not auto armed or motor interlock not enabled set throttle to zero and exit immediately
2016-01-13 03:11:50 -04:00
if ( ! motors . armed ( ) | | ! ap . auto_armed | | ! motors . get_interlock ( ) ) {
2015-07-01 15:38:32 -03:00
# if FRAME_CONFIG == HELI_FRAME // Helicopters always stabilize roll/pitch/yaw
// call attitude controller
2015-11-28 13:57:14 -04:00
attitude_control . input_euler_angle_roll_pitch_euler_rate_yaw_smooth ( 0 , 0 , 0 , get_smoothing_gain ( ) ) ;
2015-07-01 15:38:32 -03:00
attitude_control . set_throttle_out ( 0 , false , g . throttle_filt ) ;
2016-01-13 03:11:50 -04:00
# else
2016-02-02 08:16:42 -04:00
motors . set_desired_spool_state ( AP_Motors : : DESIRED_SPIN_WHEN_ARMED ) ;
2016-01-13 03:11:50 -04:00
// multicopters do not stabilize roll/pitch/yaw when disarmed
2015-04-16 01:54:29 -03:00
attitude_control . set_throttle_out_unstabilized ( 0 , true , g . throttle_filt ) ;
2015-07-01 15:38:32 -03:00
# endif
2014-04-25 02:15:57 -03:00
// set target to current position
wp_nav . init_loiter_target ( ) ;
return ;
}
// process pilot's input
if ( ! failsafe . radio ) {
2016-01-14 01:47:26 -04:00
if ( ( g . throttle_behavior & THR_BEHAVE_HIGH_THROTTLE_CANCELS_LAND ) ! = 0 & & rc_throttle_control_in_filter . get ( ) > LAND_CANCEL_TRIGGER_THR ) {
Log_Write_Event ( DATA_LAND_CANCELLED_BY_PILOT ) ;
2016-01-06 17:39:36 -04:00
// exit land if throttle is high
2016-01-25 19:40:41 -04:00
if ( ! set_mode ( LOITER , MODE_REASON_THROTTLE_LAND_ESCAPE ) ) {
set_mode ( ALT_HOLD , MODE_REASON_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
2014-07-06 06:05:43 -03:00
// process pilot's roll and pitch input
2015-05-11 23:24:13 -03:00
roll_control = channel_roll - > control_in ;
pitch_control = channel_pitch - > control_in ;
2014-07-06 06:05:43 -03:00
}
2014-04-25 02:15:57 -03:00
// get pilot's desired yaw rate
2015-05-11 23:24:13 -03:00
target_yaw_rate = get_pilot_desired_yaw_rate ( channel_yaw - > control_in ) ;
2014-04-25 02:15:57 -03:00
}
2016-01-13 03:11:50 -04:00
// set motors to full range
2016-02-02 08:16:42 -04:00
motors . set_desired_spool_state ( AP_Motors : : DESIRED_THROTTLE_UNLIMITED ) ;
2016-01-13 03:11:50 -04:00
2014-07-06 06:05:43 -03:00
// process roll, pitch inputs
wp_nav . set_pilot_desired_acceleration ( roll_control , pitch_control ) ;
2014-04-25 02:15:57 -03:00
// run loiter controller
2014-11-15 23:06:05 -04:00
wp_nav . update_loiter ( ekfGndSpdLimit , ekfNavVelGainScaler ) ;
2014-04-25 02:15:57 -03:00
// call z-axis position controller
2016-03-18 07:44:09 -03:00
pos_control . set_alt_target_with_slew ( rtl_path . descent_target . alt , G_Dt ) ;
2014-04-25 02:15:57 -03:00
pos_control . update_z_controller ( ) ;
// roll & pitch from waypoint controller, yaw rate from pilot
2015-11-28 13:57:14 -04:00
attitude_control . input_euler_angle_roll_pitch_euler_rate_yaw ( wp_nav . get_roll ( ) , wp_nav . get_pitch ( ) , target_yaw_rate ) ;
2014-04-25 02:15:57 -03:00
// check if we've reached within 20cm of final altitude
2016-03-18 07:44:09 -03:00
rtl_state_complete = fabsf ( rtl_path . descent_target . alt - current_loc . alt ) < 20.0f ;
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
2015-05-29 23:12:49 -03:00
void Copter : : rtl_land_start ( )
2014-01-25 04:24:43 -04:00
{
2015-05-17 22:37:32 -03:00
rtl_state = RTL_Land ;
2014-01-25 04:24:43 -04:00
rtl_state_complete = false ;
// Set wp navigation target to above home
2014-05-15 10:19:18 -03:00
wp_nav . init_loiter_target ( wp_nav . get_wp_destination ( ) ) ;
2014-01-25 04:24:43 -04:00
// initialise altitude target to stopping point
pos_control . set_target_to_stopping_point_z ( ) ;
// initialise yaw
set_auto_yaw_mode ( AUTO_YAW_HOLD ) ;
}
// rtl_returnhome_run - return home
// called by rtl_run at 100hz or more
2015-05-29 23:12:49 -03:00
void Copter : : rtl_land_run ( )
2014-01-25 04:24:43 -04:00
{
2014-07-06 06:05:43 -03:00
int16_t roll_control = 0 , pitch_control = 0 ;
float target_yaw_rate = 0 ;
2015-04-17 14:49:08 -03:00
// if not auto armed or landing completed or motor interlock not enabled set throttle to zero and exit immediately
2016-01-13 03:11:50 -04:00
if ( ! motors . armed ( ) | | ! ap . auto_armed | | ap . land_complete | | ! motors . get_interlock ( ) ) {
2015-07-01 15:38:32 -03:00
# if FRAME_CONFIG == HELI_FRAME // Helicopters always stabilize roll/pitch/yaw
// call attitude controller
2015-11-28 13:57:14 -04:00
attitude_control . input_euler_angle_roll_pitch_euler_rate_yaw_smooth ( 0 , 0 , 0 , get_smoothing_gain ( ) ) ;
2015-07-01 15:38:32 -03:00
attitude_control . set_throttle_out ( 0 , false , g . throttle_filt ) ;
2016-01-13 03:11:50 -04:00
# else
2016-02-02 08:16:42 -04:00
motors . set_desired_spool_state ( AP_Motors : : DESIRED_SPIN_WHEN_ARMED ) ;
2016-01-13 03:11:50 -04:00
// multicopters do not stabilize roll/pitch/yaw when disarmed
2015-04-16 01:54:29 -03:00
attitude_control . set_throttle_out_unstabilized ( 0 , true , g . throttle_filt ) ;
2015-07-01 15:38:32 -03:00
# endif
2014-01-25 04:24:43 -04:00
// set target to current position
wp_nav . init_loiter_target ( ) ;
2014-09-12 02:15:38 -03:00
# if LAND_REQUIRE_MIN_THROTTLE_TO_DISARM == ENABLED
// disarm when the landing detector says we've landed and throttle is at minimum
2014-10-07 12:29:24 -03:00
if ( ap . land_complete & & ( ap . throttle_zero | | failsafe . radio ) ) {
2014-09-12 02:15:38 -03:00
init_disarm_motors ( ) ;
}
# else
// disarm when the landing detector says we've landed
if ( ap . land_complete ) {
init_disarm_motors ( ) ;
}
# endif
// check if we've completed this stage of RTL
rtl_state_complete = ap . land_complete ;
2014-01-25 04:24:43 -04:00
return ;
}
2014-08-29 03:25:37 -03:00
// relax loiter target if we might be landed
2015-05-06 01:38:38 -03:00
if ( ap . land_complete_maybe ) {
2014-08-29 03:25:37 -03:00
wp_nav . loiter_soften_for_landing ( ) ;
}
2014-07-06 06:05:43 -03:00
// process pilot's input
2014-01-25 04:24:43 -04:00
if ( ! failsafe . radio ) {
2016-01-14 01:47:26 -04:00
if ( ( g . throttle_behavior & THR_BEHAVE_HIGH_THROTTLE_CANCELS_LAND ) ! = 0 & & rc_throttle_control_in_filter . get ( ) > LAND_CANCEL_TRIGGER_THR ) {
Log_Write_Event ( DATA_LAND_CANCELLED_BY_PILOT ) ;
2016-01-06 17:39:36 -04:00
// exit land if throttle is high
2016-01-25 19:40:41 -04:00
if ( ! set_mode ( LOITER , MODE_REASON_THROTTLE_LAND_ESCAPE ) ) {
set_mode ( ALT_HOLD , MODE_REASON_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
2014-07-06 06:05:43 -03:00
// process pilot's roll and pitch input
2015-05-11 23:24:13 -03:00
roll_control = channel_roll - > control_in ;
pitch_control = channel_pitch - > control_in ;
2014-07-06 06:05:43 -03:00
}
2014-04-25 02:15:57 -03:00
2014-01-25 04:24:43 -04:00
// get pilot's desired yaw rate
2015-05-11 23:24:13 -03:00
target_yaw_rate = get_pilot_desired_yaw_rate ( channel_yaw - > control_in ) ;
2014-01-25 04:24:43 -04:00
}
2016-01-13 03:11:50 -04:00
// set motors to full range
2016-02-02 08:16:42 -04:00
motors . set_desired_spool_state ( AP_Motors : : DESIRED_THROTTLE_UNLIMITED ) ;
2016-01-13 03:11:50 -04:00
2014-07-06 06:05:43 -03:00
// process pilot's roll and pitch input
wp_nav . set_pilot_desired_acceleration ( roll_control , pitch_control ) ;
2014-01-25 04:24:43 -04:00
// run loiter controller
2014-11-15 23:06:05 -04:00
wp_nav . update_loiter ( ekfGndSpdLimit , ekfNavVelGainScaler ) ;
2014-01-25 04:24:43 -04:00
// call z-axis position controller
2014-12-18 00:11:28 -04:00
float cmb_rate = get_land_descent_speed ( ) ;
2014-11-13 20:57:25 -04:00
pos_control . set_alt_target_from_climb_rate ( cmb_rate , G_Dt , true ) ;
2014-01-25 04:24:43 -04:00
pos_control . update_z_controller ( ) ;
2014-12-18 03:13:48 -04:00
// record desired climb rate for logging
2014-12-18 00:11:28 -04:00
desired_climb_rate = cmb_rate ;
2014-01-25 04:24:43 -04:00
// roll & pitch from waypoint controller, yaw rate from pilot
2015-11-28 13:57:14 -04: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
// check if we've completed this stage of RTL
rtl_state_complete = ap . land_complete ;
2014-01-24 02:47:42 -04:00
}
2016-04-22 08:44:57 -03:00
void Copter : : rtl_build_path ( bool terrain_following_allowed )
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 ;
pos_control . get_stopping_point_xy ( stopping_point ) ;
pos_control . get_stopping_point_z ( stopping_point ) ;
rtl_path . origin_point = Location_Class ( stopping_point ) ;
rtl_path . origin_point . change_alt_frame ( Location_Class : : ALT_FRAME_ABOVE_HOME ) ;
2016-01-06 02:52:20 -04:00
// set return target to nearest rally point or home position
# if AC_RALLY == ENABLED
2016-03-18 07:44:09 -03:00
rtl_path . return_target = rally . calc_best_rally_or_home_location ( current_loc , ahrs . get_home ( ) . alt ) ;
2016-01-06 02:52:20 -04:00
# else
2016-03-18 07:44:09 -03:00
rtl_path . return_target = ahrs . get_home ( ) ;
2016-01-06 02:52:20 -04:00
# endif
// compute return altitude
2016-04-22 08:44:57 -03:00
rtl_compute_return_alt ( rtl_path . origin_point , rtl_path . return_target , terrain_following_allowed ) ;
2016-01-06 02:52:20 -04:00
// climb target is above our origin point at the return altitude
2016-03-18 07:44:09 -03:00
rtl_path . climb_target = Location_Class ( 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
2016-03-18 07:44:09 -03:00
rtl_path . descent_target = Location_Class ( rtl_path . return_target . lat , rtl_path . return_target . lng , g . rtl_alt_final , Location_Class : : ALT_FRAME_ABOVE_HOME ) ;
2016-01-06 02:52:20 -04:00
// set land flag
rtl_path . land = g . rtl_alt_final < = 0 ;
}
2016-03-18 07:44:09 -03:00
// return altitude in cm above home at which vehicle should return home
// rtl_origin_point is the stopping point of the vehicle when rtl is initiated
// rtl_return_target is the home or rally point that the vehicle is returning to. It's lat, lng and alt values must already have been filled in before this function is called
// rtl_return_target's altitude is updated to a higher altitude that the vehicle can safely return at (frame may also be set)
2016-04-22 08:44:57 -03:00
void Copter : : rtl_compute_return_alt ( const Location_Class & rtl_origin_point , Location_Class & rtl_return_target , bool terrain_following_allowed )
2014-02-17 06:49:30 -04:00
{
2016-03-18 07:44:09 -03:00
float rtl_return_dist_cm = rtl_return_target . get_distance ( rtl_origin_point ) * 100.0f ;
// curr_alt is current altitude above home or above terrain depending upon use_terrain
int32_t curr_alt = current_loc . alt ;
// decide if we should use terrain altitudes
2016-04-22 08:44:57 -03:00
rtl_path . terrain_used = terrain_use ( ) & & terrain_following_allowed ;
if ( rtl_path . terrain_used ) {
2016-03-18 07:44:09 -03:00
// attempt to retrieve terrain alt for current location, stopping point and origin
int32_t origin_terr_alt , return_target_terr_alt ;
if ( ! rtl_origin_point . get_alt_cm ( Location_Class : : ALT_FRAME_ABOVE_TERRAIN , origin_terr_alt ) | |
! rtl_origin_point . get_alt_cm ( Location_Class : : ALT_FRAME_ABOVE_TERRAIN , return_target_terr_alt ) | |
! current_loc . get_alt_cm ( Location_Class : : ALT_FRAME_ABOVE_TERRAIN , curr_alt ) ) {
2016-04-22 08:44:57 -03:00
rtl_path . terrain_used = false ;
2016-03-18 07:44:09 -03:00
Log_Write_Error ( ERROR_SUBSYSTEM_TERRAIN , ERROR_CODE_MISSING_TERRAIN_DATA ) ;
}
}
2015-07-12 22:39:54 -03:00
// maximum of current altitude + climb_min and rtl altitude
2016-03-18 07:44:09 -03:00
float ret = MAX ( curr_alt + MAX ( 0 , g . rtl_climb_min ) , MAX ( g . rtl_altitude , RTL_ALT_MIN ) ) ;
2014-04-27 03:35:32 -03:00
2016-03-18 07:44:09 -03:00
// don't allow really shallow slopes
if ( g . rtl_cone_slope > = RTL_MIN_CONE_SLOPE ) {
ret = MAX ( curr_alt , MIN ( ret , MAX ( rtl_return_dist_cm * g . rtl_cone_slope , curr_alt + RTL_ABS_MIN_CLIMB ) ) ) ;
2016-01-06 03:00:29 -04:00
}
2014-04-27 03:35:32 -03:00
# if AC_FENCE == ENABLED
// ensure not above fence altitude if alt fence is enabled
2016-03-18 07:44:09 -03:00
// Note: we are assuming the fence alt is the same frame as ret
2014-04-27 03:35:32 -03:00
if ( ( fence . get_enabled_fences ( ) & AC_FENCE_TYPE_ALT_MAX ) ! = 0 ) {
2015-11-27 13:11:58 -04:00
ret = MIN ( ret , fence . get_safe_alt ( ) * 100.0f ) ;
2014-04-27 03:35:32 -03:00
}
# endif
2016-03-18 07:44:09 -03:00
// ensure we do not descend
ret = MAX ( ret , curr_alt ) ;
// convert return-target to alt-above-home or alt-above-terrain
2016-04-22 08:44:57 -03:00
if ( ! rtl_path . terrain_used | | ! rtl_return_target . change_alt_frame ( Location_Class : : ALT_FRAME_ABOVE_TERRAIN ) ) {
2016-03-18 07:44:09 -03:00
if ( ! rtl_return_target . change_alt_frame ( Location_Class : : ALT_FRAME_ABOVE_HOME ) ) {
// this should never happen but just in case
2016-04-28 07:54:09 -03:00
rtl_return_target . set_alt_cm ( 0 , Location_Class : : ALT_FRAME_ABOVE_HOME ) ;
2016-03-18 07:44:09 -03:00
}
}
2014-02-17 06:49:30 -04:00
2016-03-18 07:44:09 -03:00
// add ret to altitude
rtl_return_target . alt + = ret ;
2016-01-06 02:52:20 -04:00
}