2016-01-14 15:30:56 -04:00
# include "Sub.h"
2015-12-30 18:57:56 -04:00
/*
2017-03-09 13:25:54 -04:00
* control_auto . cpp
* Contains the mission , waypoint navigation and NAV_CMD item implementation
2015-12-30 18:57:56 -04:00
*
* While in the auto flight mode , navigation or do / now commands can be run .
* Code in this file implements the navigation commands
*/
2023-04-03 09:11:21 -03:00
bool ModeAuto : : init ( bool ignore_checks ) {
if ( ! sub . position_ok ( ) | | sub . mission . num_commands ( ) < 2 ) {
2017-04-14 16:10:29 -03:00
return false ;
}
2023-04-03 09:11:21 -03:00
sub . auto_mode = Auto_Loiter ;
2015-12-30 18:57:56 -04:00
2017-04-14 16:10:29 -03:00
// stop ROI from carrying over from previous runs of the mission
// To-Do: reset the yaw as part of auto_wp_start when the previous command was not a wp command to remove the need for this special ROI check
2023-04-03 09:11:21 -03:00
if ( sub . auto_yaw_mode = = AUTO_YAW_ROI ) {
2017-04-14 16:10:29 -03:00
set_auto_yaw_mode ( AUTO_YAW_HOLD ) ;
}
2015-12-30 18:57:56 -04:00
2020-06-09 21:15:51 -03:00
// initialise waypoint controller
2023-04-03 09:11:21 -03:00
sub . wp_nav . wp_and_spline_init ( ) ;
2015-12-30 18:57:56 -04:00
2017-04-14 16:10:29 -03:00
// clear guided limits
guided_limit_clear ( ) ;
2015-12-30 18:57:56 -04:00
2017-04-14 16:10:29 -03:00
// start/resume the mission (based on MIS_RESTART parameter)
2023-04-03 09:11:21 -03:00
sub . mission . start_or_resume ( ) ;
2017-04-14 16:10:29 -03:00
return true ;
2015-12-30 18:57:56 -04:00
}
2017-04-07 00:21:37 -03:00
// auto_run - runs the appropriate auto controller
// according to the current auto_mode
2023-04-03 09:11:21 -03:00
void ModeAuto : : run ( )
2015-12-30 18:57:56 -04:00
{
2023-04-03 09:11:21 -03:00
sub . mission . update ( ) ;
2017-04-07 00:21:37 -03:00
2015-12-30 18:57:56 -04:00
// call the correct auto controller
2023-04-03 09:11:21 -03:00
switch ( sub . auto_mode ) {
2015-12-30 18:57:56 -04:00
case Auto_WP :
case Auto_CircleMoveToEdge :
auto_wp_run ( ) ;
break ;
case Auto_Circle :
auto_circle_run ( ) ;
break ;
case Auto_NavGuided :
# if NAV_GUIDED == ENABLED
auto_nav_guided_run ( ) ;
# endif
break ;
case Auto_Loiter :
auto_loiter_run ( ) ;
break ;
2017-02-07 20:42:28 -04:00
case Auto_TerrainRecover :
2017-02-03 17:33:27 -04:00
auto_terrain_recover_run ( ) ;
break ;
2015-12-30 18:57:56 -04:00
}
}
// auto_wp_start - initialises waypoint controller to implement flying to a particular destination
2023-04-03 09:11:21 -03:00
void ModeAuto : : auto_wp_start ( const Vector3f & destination )
2015-12-30 18:57:56 -04:00
{
2023-04-03 09:11:21 -03:00
sub . auto_mode = Auto_WP ;
2015-12-30 18:57:56 -04:00
2016-05-03 01:45:37 -03:00
// initialise wpnav (no need to check return status because terrain data is not used)
2023-04-03 09:11:21 -03:00
sub . wp_nav . set_wp_destination ( destination , false ) ;
2016-05-03 01:45:37 -03:00
2017-02-03 17:33:27 -04:00
// initialise yaw
// To-Do: reset the yaw only when the previous navigation command is not a WP. this would allow removing the special check for ROI
2023-04-03 09:11:21 -03:00
if ( sub . auto_yaw_mode ! = AUTO_YAW_ROI ) {
2017-02-03 17:33:27 -04:00
set_auto_yaw_mode ( get_default_auto_yaw_mode ( false ) ) ;
}
2016-05-03 01:45:37 -03:00
}
// auto_wp_start - initialises waypoint controller to implement flying to a particular destination
2023-04-03 09:11:21 -03:00
void ModeAuto : : auto_wp_start ( const Location & dest_loc )
2016-05-03 01:45:37 -03:00
{
2023-04-03 09:11:21 -03:00
sub . auto_mode = Auto_WP ;
2016-05-03 01:45:37 -03:00
2017-02-03 17:33:27 -04:00
// send target to waypoint controller
2023-04-03 09:11:21 -03:00
if ( ! sub . wp_nav . set_wp_destination_loc ( dest_loc ) ) {
2017-02-03 17:33:27 -04:00
// failure to set destination can only be because of missing terrain data
2023-04-03 09:11:21 -03:00
sub . failsafe_terrain_on_event ( ) ;
2017-02-03 17:33:27 -04:00
return ;
}
2015-12-30 18:57:56 -04:00
// initialise yaw
// To-Do: reset the yaw only when the previous navigation command is not a WP. this would allow removing the special check for ROI
2023-04-03 09:11:21 -03:00
if ( sub . auto_yaw_mode ! = AUTO_YAW_ROI ) {
2015-12-30 18:57:56 -04:00
set_auto_yaw_mode ( get_default_auto_yaw_mode ( false ) ) ;
}
}
// auto_wp_run - runs the auto waypoint controller
// called by auto_run at 100hz or more
2023-04-03 09:11:21 -03:00
void ModeAuto : : auto_wp_run ( )
2015-12-30 18:57:56 -04:00
{
2017-04-13 16:34:58 -03:00
// if not armed set throttle to zero and exit immediately
2017-04-11 13:45:16 -03:00
if ( ! motors . armed ( ) ) {
2017-02-10 13:46:54 -04:00
// To-Do: reset waypoint origin to current location because vehicle is probably on the ground so we don't want it lurching left or right on take-off
2015-12-30 18:57:56 -04:00
// (of course it would be better if people just used take-off)
// call attitude controller
2017-02-10 13:46:54 -04:00
// Sub vehicles do not stabilize roll/pitch/yaw when disarmed
2019-04-09 20:09:55 -03:00
motors . set_desired_spool_state ( AP_Motors : : DesiredSpoolState : : GROUND_IDLE ) ;
2023-04-03 09:11:21 -03:00
attitude_control - > set_throttle_out ( 0 , true , g . throttle_filt ) ;
attitude_control - > relax_attitude_controllers ( ) ;
sub . wp_nav . wp_and_spline_init ( ) ; // Reset xy target
2015-12-30 18:57:56 -04:00
return ;
}
// process pilot's yaw input
float target_yaw_rate = 0 ;
2023-04-03 09:11:21 -03:00
if ( ! sub . failsafe . pilot_input ) {
2015-12-30 18:57:56 -04:00
// get pilot's desired yaw rate
2023-04-03 09:11:21 -03:00
target_yaw_rate = sub . get_pilot_desired_yaw_rate ( channel_yaw - > get_control_in ( ) ) ;
2015-12-30 18:57:56 -04:00
if ( ! is_zero ( target_yaw_rate ) ) {
set_auto_yaw_mode ( AUTO_YAW_HOLD ) ;
}
}
2016-04-05 00:17:39 -03:00
// set motors to full range
2019-04-09 20:09:55 -03:00
motors . set_desired_spool_state ( AP_Motors : : DesiredSpoolState : : THROTTLE_UNLIMITED ) ;
2016-04-05 00:17:39 -03:00
2015-12-30 18:57:56 -04:00
// run waypoint controller
2017-02-07 20:42:28 -04:00
// TODO logic for terrain tracking target going below fence limit
// TODO implement waypoint radius individually for each waypoint based on cmd.p2
// TODO fix auto yaw heading to switch to something appropriate when mission complete and switches to loiter
2023-04-03 09:11:21 -03:00
sub . failsafe_terrain_set_status ( sub . wp_nav . update_wpnav ( ) ) ;
2015-12-30 18:57:56 -04:00
2017-02-07 20:42:28 -04:00
///////////////////////
// update xy outputs //
float lateral_out , forward_out ;
2023-04-03 09:11:21 -03:00
sub . translate_wpnav_rp ( lateral_out , forward_out ) ;
2017-02-07 20:42:28 -04:00
2017-02-03 17:33:27 -04:00
// Send to forward/lateral outputs
motors . set_lateral ( lateral_out ) ;
motors . set_forward ( forward_out ) ;
2017-02-07 20:42:28 -04:00
2021-05-19 11:08:30 -03:00
// WP_Nav has set the vertical position control targets
// run the vertical position controller and set output throttle
2023-04-03 09:11:21 -03:00
position_control - > update_z_controller ( ) ;
2015-12-30 18:57:56 -04:00
2017-02-03 17:33:27 -04:00
////////////////////////////
// update attitude output //
2017-02-07 20:42:28 -04:00
// get pilot desired lean angles
float target_roll , target_pitch ;
2023-04-03 09:11:21 -03:00
sub . get_pilot_desired_lean_angles ( channel_roll - > get_control_in ( ) , channel_pitch - > get_control_in ( ) , target_roll , target_pitch , sub . aparm . angle_max ) ;
2017-02-07 20:42:28 -04:00
2015-12-30 18:57:56 -04:00
// call attitude controller
2023-04-03 09:11:21 -03:00
if ( sub . auto_yaw_mode = = AUTO_YAW_HOLD ) {
2022-05-24 10:24:05 -03:00
// roll & pitch & yaw rate from pilot
2023-04-03 09:11:21 -03:00
attitude_control - > input_euler_angle_roll_pitch_euler_rate_yaw ( target_roll , target_pitch , target_yaw_rate ) ;
2017-02-03 17:33:27 -04:00
} else {
2022-05-24 10:24:05 -03:00
// roll, pitch from pilot, yaw heading from auto_heading()
2023-04-03 09:11:21 -03:00
attitude_control - > input_euler_angle_roll_pitch_yaw ( target_roll , target_pitch , get_auto_heading ( ) , true ) ;
2015-12-30 18:57:56 -04:00
}
}
// auto_circle_movetoedge_start - initialise waypoint controller to move to edge of a circle with it's center at the specified location
2023-04-03 09:11:21 -03:00
// we assume the caller has set the circle's circle with sub.circle_nav.set_center()
2015-12-30 18:57:56 -04:00
// we assume the caller has performed all required GPS_ok checks
2023-04-03 09:11:21 -03:00
void ModeAuto : : auto_circle_movetoedge_start ( const Location & circle_center , float radius_m , bool ccw_turn )
2015-12-30 18:57:56 -04:00
{
2020-04-08 03:25:04 -03:00
// set circle center
2023-04-03 09:11:21 -03:00
sub . circle_nav . set_center ( circle_center ) ;
2017-02-03 17:33:27 -04:00
// set circle radius
if ( ! is_zero ( radius_m ) ) {
2023-04-03 09:11:21 -03:00
sub . circle_nav . set_radius_cm ( radius_m * 100.0f ) ;
2017-02-03 17:33:27 -04:00
}
2023-02-14 18:17:46 -04:00
// set circle direction by using rate
2023-04-03 09:11:21 -03:00
float current_rate = sub . circle_nav . get_rate ( ) ;
2023-02-14 18:17:46 -04:00
current_rate = ccw_turn ? - fabsf ( current_rate ) : fabsf ( current_rate ) ;
2023-04-03 09:11:21 -03:00
sub . circle_nav . set_rate ( current_rate ) ;
2023-02-14 18:17:46 -04:00
2017-02-03 17:33:27 -04:00
// check our distance from edge of circle
Vector3f circle_edge_neu ;
2023-04-03 09:11:21 -03:00
sub . circle_nav . get_closest_point_on_circle ( circle_edge_neu ) ;
2021-10-20 05:30:56 -03:00
float dist_to_edge = ( inertial_nav . get_position_neu_cm ( ) - circle_edge_neu ) . length ( ) ;
2017-02-03 17:33:27 -04:00
// if more than 3m then fly to edge
if ( dist_to_edge > 300.0f ) {
// set the state to move to the edge of the circle
2023-04-03 09:11:21 -03:00
sub . auto_mode = Auto_CircleMoveToEdge ;
2017-02-03 17:33:27 -04:00
2019-01-02 00:40:53 -04:00
// convert circle_edge_neu to Location
2021-03-17 18:17:48 -03:00
Location circle_edge ( circle_edge_neu , Location : : AltFrame : : ABOVE_ORIGIN ) ;
2017-02-03 17:33:27 -04:00
// convert altitude to same as command
circle_edge . set_alt_cm ( circle_center . alt , circle_center . get_alt_frame ( ) ) ;
// initialise wpnav to move to edge of circle
2023-04-03 09:11:21 -03:00
if ( ! sub . wp_nav . set_wp_destination_loc ( circle_edge ) ) {
2017-02-03 17:33:27 -04:00
// failure to set destination can only be because of missing terrain data
2023-04-03 09:11:21 -03:00
sub . failsafe_terrain_on_event ( ) ;
2017-02-03 17:33:27 -04:00
}
// if we are outside the circle, point at the edge, otherwise hold yaw
2023-04-03 09:11:21 -03:00
float dist_to_center = get_horizontal_distance_cm ( inertial_nav . get_position_xy_cm ( ) . topostype ( ) , sub . circle_nav . get_center ( ) . xy ( ) ) ;
if ( dist_to_center > sub . circle_nav . get_radius ( ) & & dist_to_center > 500 ) {
2017-02-03 17:33:27 -04:00
set_auto_yaw_mode ( get_default_auto_yaw_mode ( false ) ) ;
} else {
// vehicle is within circle so hold yaw to avoid spinning as we move to edge of circle
set_auto_yaw_mode ( AUTO_YAW_HOLD ) ;
}
} else {
auto_circle_start ( ) ;
}
2015-12-30 18:57:56 -04:00
}
// auto_circle_start - initialises controller to fly a circle in AUTO flight mode
2016-05-03 01:45:37 -03:00
// assumes that circle_nav object has already been initialised with circle center and radius
2023-04-03 09:11:21 -03:00
void ModeAuto : : auto_circle_start ( )
2015-12-30 18:57:56 -04:00
{
2023-04-03 09:11:21 -03:00
sub . auto_mode = Auto_Circle ;
2015-12-30 18:57:56 -04:00
// initialise circle controller
2023-04-03 09:11:21 -03:00
sub . circle_nav . init ( sub . circle_nav . get_center ( ) , sub . circle_nav . center_is_terrain_alt ( ) , sub . circle_nav . get_rate ( ) ) ;
2015-12-30 18:57:56 -04:00
}
// auto_circle_run - circle in AUTO flight mode
// called by auto_run at 100hz or more
2023-04-03 09:11:21 -03:00
void ModeAuto : : auto_circle_run ( )
2015-12-30 18:57:56 -04:00
{
// call circle controller
2023-04-03 09:11:21 -03:00
sub . failsafe_terrain_set_status ( sub . circle_nav . update ( ) ) ;
2015-12-30 18:57:56 -04:00
2017-03-04 15:41:26 -04:00
float lateral_out , forward_out ;
2023-04-03 09:11:21 -03:00
sub . translate_circle_nav_rp ( lateral_out , forward_out ) ;
2017-03-04 15:41:26 -04:00
// Send to forward/lateral outputs
motors . set_lateral ( lateral_out ) ;
motors . set_forward ( forward_out ) ;
2021-05-19 11:08:30 -03:00
// WP_Nav has set the vertical position control targets
// run the vertical position controller and set output throttle
2023-04-03 09:11:21 -03:00
position_control - > update_z_controller ( ) ;
2015-12-30 18:57:56 -04:00
// roll & pitch from waypoint controller, yaw rate from pilot
2023-04-03 09:11:21 -03:00
attitude_control - > input_euler_angle_roll_pitch_yaw ( channel_roll - > get_control_in ( ) , channel_pitch - > get_control_in ( ) , sub . circle_nav . get_yaw ( ) , true ) ;
2015-12-30 18:57:56 -04:00
}
# if NAV_GUIDED == ENABLED
// auto_nav_guided_start - hand over control to external navigation controller in AUTO mode
2023-04-03 09:11:21 -03:00
void ModeAuto : : auto_nav_guided_start ( )
2015-12-30 18:57:56 -04:00
{
2023-04-03 09:11:21 -03:00
sub . mode_guided . init ( true ) ;
sub . auto_mode = Auto_NavGuided ;
2015-12-30 18:57:56 -04:00
// initialise guided start time and position as reference for limit checking
2023-04-03 09:11:21 -03:00
sub . mode_auto . guided_limit_init_time_and_pos ( ) ;
2015-12-30 18:57:56 -04:00
}
// auto_nav_guided_run - allows control by external navigation controller
// called by auto_run at 100hz or more
2023-04-03 09:11:21 -03:00
void ModeAuto : : auto_nav_guided_run ( )
2015-12-30 18:57:56 -04:00
{
// call regular guided flight mode run function
2023-04-03 09:11:21 -03:00
sub . mode_guided . run ( ) ;
2015-12-30 18:57:56 -04:00
}
# endif // NAV_GUIDED
// auto_loiter_start - initialises loitering in auto mode
// returns success/failure because this can be called by exit_mission
2023-04-03 09:11:21 -03:00
bool ModeAuto : : auto_loiter_start ( )
2015-12-30 18:57:56 -04:00
{
// return failure if GPS is bad
2023-04-03 09:11:21 -03:00
if ( ! sub . position_ok ( ) ) {
2015-12-30 18:57:56 -04:00
return false ;
}
2023-04-03 09:11:21 -03:00
sub . auto_mode = Auto_Loiter ;
2015-12-30 18:57:56 -04:00
// calculate stopping point
Vector3f stopping_point ;
2023-04-03 09:11:21 -03:00
sub . wp_nav . get_wp_stopping_point ( stopping_point ) ;
2015-12-30 18:57:56 -04:00
// initialise waypoint controller target to stopping point
2023-04-03 09:11:21 -03:00
sub . wp_nav . set_wp_destination ( stopping_point ) ;
2015-12-30 18:57:56 -04:00
// hold yaw at current heading
set_auto_yaw_mode ( AUTO_YAW_HOLD ) ;
return true ;
}
// auto_loiter_run - loiter in AUTO flight mode
// called by auto_run at 100hz or more
2023-04-03 09:11:21 -03:00
void ModeAuto : : auto_loiter_run ( )
2015-12-30 18:57:56 -04:00
{
2017-04-13 16:34:58 -03:00
// if not armed set throttle to zero and exit immediately
2017-04-11 13:45:16 -03:00
if ( ! motors . armed ( ) ) {
2019-04-09 20:09:55 -03:00
motors . set_desired_spool_state ( AP_Motors : : DesiredSpoolState : : GROUND_IDLE ) ;
2017-02-10 13:46:54 -04:00
// Sub vehicles do not stabilize roll/pitch/yaw when disarmed
2023-04-03 09:11:21 -03:00
attitude_control - > set_throttle_out ( 0 , true , g . throttle_filt ) ;
attitude_control - > relax_attitude_controllers ( ) ;
2016-02-23 02:15:15 -04:00
2023-04-03 09:11:21 -03:00
sub . wp_nav . wp_and_spline_init ( ) ; // Reset xy target
2015-12-30 18:57:56 -04:00
return ;
}
// accept pilot input of yaw
float target_yaw_rate = 0 ;
2023-04-03 09:11:21 -03:00
if ( ! sub . failsafe . pilot_input ) {
target_yaw_rate = sub . get_pilot_desired_yaw_rate ( channel_yaw - > get_control_in ( ) ) ;
2015-12-30 18:57:56 -04:00
}
2016-04-05 00:17:39 -03:00
// set motors to full range
2019-04-09 20:09:55 -03:00
motors . set_desired_spool_state ( AP_Motors : : DesiredSpoolState : : THROTTLE_UNLIMITED ) ;
2016-04-05 00:17:39 -03:00
2016-05-03 01:45:37 -03:00
// run waypoint and z-axis position controller
2023-04-03 09:11:21 -03:00
sub . failsafe_terrain_set_status ( sub . wp_nav . update_wpnav ( ) ) ;
2016-05-03 01:45:37 -03:00
2017-02-07 20:42:28 -04:00
///////////////////////
// update xy outputs //
2017-02-03 17:33:27 -04:00
float lateral_out , forward_out ;
2023-04-03 09:11:21 -03:00
sub . translate_wpnav_rp ( lateral_out , forward_out ) ;
2017-02-07 20:42:28 -04:00
2017-02-03 17:33:27 -04:00
// Send to forward/lateral outputs
motors . set_lateral ( lateral_out ) ;
motors . set_forward ( forward_out ) ;
2017-02-07 20:42:28 -04:00
2021-05-19 11:08:30 -03:00
// WP_Nav has set the vertical position control targets
// run the vertical position controller and set output throttle
2023-04-03 09:11:21 -03:00
position_control - > update_z_controller ( ) ;
2017-02-07 20:42:28 -04:00
// get pilot desired lean angles
float target_roll , target_pitch ;
2023-04-03 09:11:21 -03:00
sub . get_pilot_desired_lean_angles ( channel_roll - > get_control_in ( ) , channel_pitch - > get_control_in ( ) , target_roll , target_pitch , sub . aparm . angle_max ) ;
2017-02-07 20:42:28 -04:00
2022-05-24 10:24:05 -03:00
// roll & pitch & yaw rate from pilot
2023-04-03 09:11:21 -03:00
attitude_control - > input_euler_angle_roll_pitch_euler_rate_yaw ( target_roll , target_pitch , target_yaw_rate ) ;
2015-12-30 18:57:56 -04:00
}
// set_auto_yaw_look_at_heading - sets the yaw look at heading for auto mode
2023-04-03 09:11:21 -03:00
void ModeAuto : : set_auto_yaw_look_at_heading ( float angle_deg , float turn_rate_dps , int8_t direction , uint8_t relative_angle )
2015-12-30 18:57:56 -04:00
{
2023-07-25 21:46:58 -03:00
// get current yaw
2023-04-03 09:11:21 -03:00
int32_t curr_yaw_target = attitude_control - > get_att_target_euler_cd ( ) . z ;
2015-12-30 18:57:56 -04:00
// get final angle, 1 = Relative, 0 = Absolute
if ( relative_angle = = 0 ) {
// absolute angle
2023-04-03 09:11:21 -03:00
sub . yaw_look_at_heading = wrap_360_cd ( angle_deg * 100 ) ;
2015-12-30 18:57:56 -04:00
} else {
// relative angle
if ( direction < 0 ) {
angle_deg = - angle_deg ;
}
2023-07-25 21:46:58 -03:00
sub . yaw_look_at_heading = wrap_360_cd ( ( angle_deg * 100 + curr_yaw_target ) ) ;
2015-12-30 18:57:56 -04:00
}
// get turn speed
if ( is_zero ( turn_rate_dps ) ) {
// default to regular auto slew rate
2023-04-03 09:11:21 -03:00
sub . yaw_look_at_heading_slew = AUTO_YAW_SLEW_RATE ;
2017-02-03 17:33:27 -04:00
} else {
2023-07-25 21:46:58 -03:00
sub . yaw_look_at_heading_slew = MIN ( turn_rate_dps , AUTO_YAW_SLEW_RATE ) ; // deg / sec
2015-12-30 18:57:56 -04:00
}
// set yaw mode
set_auto_yaw_mode ( AUTO_YAW_LOOK_AT_HEADING ) ;
// TO-DO: restore support for clockwise and counter clockwise rotation held in cmd.content.yaw.direction. 1 = clockwise, -1 = counterclockwise
}
2023-07-26 19:23:55 -03:00
// sets the desired yaw rate
2023-07-25 21:46:58 -03:00
void ModeAuto : : set_yaw_rate ( float turn_rate_dps )
2023-07-26 19:23:55 -03:00
{
// set sub to desired yaw rate
sub . yaw_look_at_heading_slew = MIN ( turn_rate_dps , AUTO_YAW_SLEW_RATE ) ; // deg / sec
// set yaw mode
set_auto_yaw_mode ( AUTO_YAW_RATE ) ;
}
2015-12-30 18:57:56 -04:00
// set_auto_yaw_roi - sets the yaw to look at roi for auto mode
2023-04-03 09:11:21 -03:00
void ModeAuto : : set_auto_yaw_roi ( const Location & roi_location )
2015-12-30 18:57:56 -04:00
{
// if location is zero lat, lon and altitude turn off ROI
if ( roi_location . alt = = 0 & & roi_location . lat = = 0 & & roi_location . lng = = 0 ) {
// set auto yaw mode back to default assuming the active command is a waypoint command. A more sophisticated method is required to ensure we return to the proper yaw control for the active command
set_auto_yaw_mode ( get_default_auto_yaw_mode ( false ) ) ;
2020-07-24 14:30:21 -03:00
# if HAL_MOUNT_ENABLED
2015-12-30 18:57:56 -04:00
// switch off the camera tracking if enabled
2023-04-03 09:11:21 -03:00
if ( sub . camera_mount . get_mode ( ) = = MAV_MOUNT_MODE_GPS_POINT ) {
sub . camera_mount . set_mode_to_default ( ) ;
2015-12-30 18:57:56 -04:00
}
2020-07-24 14:30:21 -03:00
# endif // HAL_MOUNT_ENABLED
2017-02-03 17:33:27 -04:00
} else {
2020-07-24 14:30:21 -03:00
# if HAL_MOUNT_ENABLED
2022-02-05 01:35:32 -04:00
// check if mount type requires us to rotate the sub
2023-04-03 09:11:21 -03:00
if ( ! sub . camera_mount . has_pan_control ( ) ) {
if ( roi_location . get_vector_from_origin_NEU ( sub . roi_WP ) ) {
2022-02-05 01:35:32 -04:00
set_auto_yaw_mode ( AUTO_YAW_ROI ) ;
}
2015-12-30 18:57:56 -04:00
}
// send the command to the camera mount
2023-04-03 09:11:21 -03:00
sub . camera_mount . set_roi_target ( roi_location ) ;
2015-12-30 18:57:56 -04:00
// TO-DO: expand handling of the do_nav_roi to support all modes of the MAVLink. Currently we only handle mode 4 (see below)
// 0: do nothing
// 1: point at next waypoint
// 2: point at a waypoint taken from WP# parameter (2nd parameter?)
// 3: point at a location given by alt, lon, lat parameters
// 4: point at a target given a target id (can't be implemented)
# else
2022-02-05 01:35:32 -04:00
// if we have no camera mount aim the sub at the location
2023-04-03 09:11:21 -03:00
if ( roi_location . get_vector_from_origin_NEU ( sub . roi_WP ) ) {
2022-02-05 01:35:32 -04:00
set_auto_yaw_mode ( AUTO_YAW_ROI ) ;
}
2020-07-24 14:30:21 -03:00
# endif // HAL_MOUNT_ENABLED
2015-12-30 18:57:56 -04:00
}
}
2017-02-07 20:42:28 -04:00
// Return true if it is possible to recover from a rangefinder failure
2023-04-03 09:11:21 -03:00
bool ModeAuto : : auto_terrain_recover_start ( )
2017-02-03 17:33:27 -04:00
{
// Check rangefinder status to see if recovery is possible
2023-04-03 09:11:21 -03:00
switch ( sub . rangefinder . status_orient ( ROTATION_PITCH_270 ) ) {
2017-02-07 20:42:28 -04:00
2019-11-01 02:12:53 -03:00
case RangeFinder : : Status : : OutOfRangeLow :
case RangeFinder : : Status : : OutOfRangeHigh :
2017-02-07 20:42:28 -04:00
2019-11-01 02:12:53 -03:00
// RangeFinder::Good if just one valid sample was obtained recently, but ::rangefinder_state.alt_healthy
2017-02-03 17:33:27 -04:00
// requires several consecutive valid readings for wpnav to accept rangefinder data
2019-11-01 02:12:53 -03:00
case RangeFinder : : Status : : Good :
2023-04-03 09:11:21 -03:00
sub . auto_mode = Auto_TerrainRecover ;
2017-02-03 17:33:27 -04:00
break ;
2017-02-07 20:42:28 -04:00
2017-02-03 17:33:27 -04:00
// Not connected or no data
default :
return false ; // Rangefinder is not connected, or has stopped responding
}
2017-02-07 20:42:28 -04:00
2017-02-03 17:33:27 -04:00
// Initialize recovery timeout time
2023-04-03 09:11:21 -03:00
sub . fs_terrain_recover_start_ms = AP_HAL : : millis ( ) ;
2017-02-07 20:42:28 -04:00
2017-02-03 17:33:27 -04:00
// Stop mission
2023-04-03 09:11:21 -03:00
sub . mission . stop ( ) ;
2017-02-07 20:42:28 -04:00
2017-02-03 17:33:27 -04:00
// Reset xy target
2023-04-03 09:11:21 -03:00
sub . loiter_nav . clear_pilot_desired_acceleration ( ) ;
sub . loiter_nav . init_target ( ) ;
2017-02-07 20:42:28 -04:00
2017-02-03 17:33:27 -04:00
// Reset z axis controller
2023-04-03 09:11:21 -03:00
position_control - > relax_z_controller ( motors . get_throttle_hover ( ) ) ;
2017-02-07 20:42:28 -04:00
2021-04-27 03:50:06 -03:00
// initialize vertical maximum speeds and acceleration
2023-04-03 09:11:21 -03:00
position_control - > set_max_speed_accel_z ( sub . wp_nav . get_default_speed_down ( ) , sub . wp_nav . get_default_speed_up ( ) , sub . wp_nav . get_accel_z ( ) ) ;
position_control - > set_correction_speed_accel_z ( sub . wp_nav . get_default_speed_down ( ) , sub . wp_nav . get_default_speed_up ( ) , sub . wp_nav . get_accel_z ( ) ) ;
2017-02-07 20:42:28 -04:00
2017-07-08 22:51:41 -03:00
gcs ( ) . send_text ( MAV_SEVERITY_WARNING , " Attempting auto failsafe recovery " ) ;
2017-02-03 17:33:27 -04:00
return true ;
2017-02-07 20:42:28 -04:00
}
// Attempt recovery from terrain failsafe
// If recovery is successful resume mission
// If recovery fails revert to failsafe action
2023-04-03 09:11:21 -03:00
void ModeAuto : : auto_terrain_recover_run ( )
2017-02-03 17:33:27 -04:00
{
float target_climb_rate = 0 ;
static uint32_t rangefinder_recovery_ms = 0 ;
2017-02-07 20:42:28 -04:00
// if not armed set throttle to zero and exit immediately
2017-04-11 13:45:16 -03:00
if ( ! motors . armed ( ) ) {
2019-04-09 20:09:55 -03:00
motors . set_desired_spool_state ( AP_Motors : : DesiredSpoolState : : GROUND_IDLE ) ;
2023-04-03 09:11:21 -03:00
attitude_control - > set_throttle_out ( 0 , true , g . throttle_filt ) ;
attitude_control - > relax_attitude_controllers ( ) ;
2021-09-20 04:28:39 -03:00
2023-04-03 09:11:21 -03:00
sub . loiter_nav . init_target ( ) ; // Reset xy target
position_control - > relax_z_controller ( motors . get_throttle_hover ( ) ) ; // Reset z axis controller
2017-02-07 20:42:28 -04:00
return ;
}
2023-04-03 09:11:21 -03:00
switch ( sub . rangefinder . status_orient ( ROTATION_PITCH_270 ) ) {
2017-02-07 20:42:28 -04:00
2019-11-01 02:12:53 -03:00
case RangeFinder : : Status : : OutOfRangeLow :
2023-04-03 09:11:21 -03:00
target_climb_rate = sub . wp_nav . get_default_speed_up ( ) ;
2017-02-03 17:33:27 -04:00
rangefinder_recovery_ms = 0 ;
break ;
2017-02-07 20:42:28 -04:00
2019-11-01 02:12:53 -03:00
case RangeFinder : : Status : : OutOfRangeHigh :
2023-04-03 09:11:21 -03:00
target_climb_rate = sub . wp_nav . get_default_speed_down ( ) ;
2017-02-03 17:33:27 -04:00
rangefinder_recovery_ms = 0 ;
break ;
2017-02-07 20:42:28 -04:00
2019-11-01 02:12:53 -03:00
case RangeFinder : : Status : : Good : // exit on success (recovered rangefinder data)
2017-02-07 20:42:28 -04:00
2017-02-03 17:33:27 -04:00
target_climb_rate = 0 ; // Attempt to hold current depth
2017-02-07 20:42:28 -04:00
2023-04-03 09:11:21 -03:00
if ( sub . rangefinder_state . alt_healthy ) {
2017-02-07 20:42:28 -04:00
2017-02-03 17:33:27 -04:00
// Start timer as soon as rangefinder is healthy
if ( rangefinder_recovery_ms = = 0 ) {
rangefinder_recovery_ms = AP_HAL : : millis ( ) ;
2023-04-03 09:11:21 -03:00
position_control - > relax_z_controller ( motors . get_throttle_hover ( ) ) ; // Reset alt hold targets
2017-02-03 17:33:27 -04:00
}
2017-02-07 20:42:28 -04:00
2017-02-03 17:33:27 -04:00
// 1.5 seconds of healthy rangefinder means we can resume mission with terrain enabled
if ( AP_HAL : : millis ( ) > rangefinder_recovery_ms + 1500 ) {
2017-07-08 22:51:41 -03:00
gcs ( ) . send_text ( MAV_SEVERITY_INFO , " Terrain failsafe recovery successful! " ) ;
2023-04-03 09:11:21 -03:00
sub . failsafe_terrain_set_status ( true ) ; // Reset failsafe timers
sub . failsafe . terrain = false ; // Clear flag
sub . auto_mode = Auto_Loiter ; // Switch back to loiter for next iteration
sub . mission . resume ( ) ; // Resume mission
2017-02-03 17:33:27 -04:00
rangefinder_recovery_ms = 0 ; // Reset for subsequent recoveries
}
2017-02-07 20:42:28 -04:00
2017-02-03 17:33:27 -04:00
}
break ;
2017-02-07 20:42:28 -04:00
2017-02-03 17:33:27 -04:00
// Not connected, or no data
default :
// Terrain failsafe recovery has failed, terrain data is not available
// and rangefinder is not connected, or has stopped responding
2017-07-08 22:51:41 -03:00
gcs ( ) . send_text ( MAV_SEVERITY_CRITICAL , " Terrain failsafe recovery failure: No Rangefinder! " ) ;
2023-04-03 09:11:21 -03:00
sub . failsafe_terrain_act ( ) ;
2017-02-03 17:33:27 -04:00
rangefinder_recovery_ms = 0 ;
return ;
}
2017-02-07 20:42:28 -04:00
2017-02-03 17:33:27 -04:00
// exit on failure (timeout)
2023-04-03 09:11:21 -03:00
if ( AP_HAL : : millis ( ) > sub . fs_terrain_recover_start_ms + FS_TERRAIN_RECOVER_TIMEOUT_MS ) {
2017-02-03 17:33:27 -04:00
// Recovery has failed, revert to failsafe action
2017-07-08 22:51:41 -03:00
gcs ( ) . send_text ( MAV_SEVERITY_CRITICAL , " Terrain failsafe recovery timeout! " ) ;
2023-04-03 09:11:21 -03:00
sub . failsafe_terrain_act ( ) ;
2017-02-03 17:33:27 -04:00
}
2017-02-07 20:42:28 -04:00
2017-02-03 17:33:27 -04:00
// run loiter controller
2023-04-03 09:11:21 -03:00
sub . loiter_nav . update ( ) ;
2017-02-07 20:42:28 -04:00
///////////////////////
// update xy targets //
2017-02-03 17:33:27 -04:00
float lateral_out , forward_out ;
2023-04-03 09:11:21 -03:00
sub . translate_wpnav_rp ( lateral_out , forward_out ) ;
2017-02-07 20:42:28 -04:00
2017-02-03 17:33:27 -04:00
// Send to forward/lateral outputs
motors . set_lateral ( lateral_out ) ;
motors . set_forward ( forward_out ) ;
2017-02-07 20:42:28 -04:00
2017-02-03 17:33:27 -04:00
/////////////////////
// update z target //
2023-04-03 09:11:21 -03:00
position_control - > set_pos_target_z_from_climb_rate_cm ( target_climb_rate ) ;
position_control - > update_z_controller ( ) ;
2017-02-07 20:42:28 -04:00
2017-02-03 17:33:27 -04:00
////////////////////////////
// update angular targets //
float target_roll = 0 ;
float target_pitch = 0 ;
2017-02-07 20:42:28 -04:00
2017-02-03 17:33:27 -04:00
// convert pilot input to lean angles
2023-04-03 09:11:21 -03:00
// To-Do: convert sub.get_pilot_desired_lean_angles to return angles as floats
sub . get_pilot_desired_lean_angles ( channel_roll - > get_control_in ( ) , channel_pitch - > get_control_in ( ) , target_roll , target_pitch , sub . aparm . angle_max ) ;
2017-02-07 20:42:28 -04:00
2017-02-03 17:33:27 -04:00
float target_yaw_rate = 0 ;
2017-02-07 20:42:28 -04:00
2017-02-03 17:33:27 -04:00
// call attitude controller
2023-04-03 09:11:21 -03:00
attitude_control - > input_euler_angle_roll_pitch_euler_rate_yaw ( target_roll , target_pitch , target_yaw_rate ) ;
2017-02-07 20:42:28 -04:00
}