2017-07-18 23:17:45 -03:00
# include "Rover.h"
2019-03-08 01:41:50 -04:00
# define AUTO_GUIDED_SEND_TARGET_MS 1000
2017-07-18 23:17:45 -03:00
bool ModeAuto : : _enter ( )
{
2017-07-11 06:58:47 -03:00
// fail to enter auto if no mission commands
2018-12-03 07:56:39 -04:00
if ( mission . num_commands ( ) < = 1 ) {
2017-07-11 06:58:47 -03:00
gcs ( ) . send_text ( MAV_SEVERITY_NOTICE , " No Mission. Can't set AUTO. " ) ;
return false ;
}
2022-01-05 20:01:49 -04:00
// initialise waypoint navigation library
g2 . wp_nav . init ( ) ;
2017-12-05 21:41:28 -04:00
2017-08-03 05:11:45 -03:00
// other initialisation
2017-07-18 23:17:45 -03:00
auto_triggered = false ;
2017-08-03 05:11:45 -03:00
2019-03-08 04:53:22 -04:00
// clear guided limits
rover . mode_guided . limit_clear ( ) ;
2021-04-20 22:35:06 -03:00
// initialise submode to stop or loiter
if ( rover . is_boat ( ) ) {
if ( ! start_loiter ( ) ) {
start_stop ( ) ;
}
} else {
start_stop ( ) ;
}
2021-11-15 02:06:45 -04:00
// set flag to start mission
waiting_to_start = true ;
2017-07-18 23:17:45 -03:00
return true ;
}
void ModeAuto : : _exit ( )
{
2017-08-03 03:19:57 -03:00
// stop running the mission
2017-07-18 23:17:45 -03:00
if ( mission . state ( ) = = AP_Mission : : MISSION_RUNNING ) {
mission . stop ( ) ;
}
}
void ModeAuto : : update ( )
{
2023-03-23 21:01:47 -03:00
// check if mission exists (due to being cleared while disarmed in AUTO,
// if no mission, then stop...needs mode change out of AUTO, mission load,
// and change back to AUTO to run a mission at this point
if ( ! hal . util - > get_soft_armed ( ) & & mission . num_commands ( ) < = 1 ) {
start_stop ( ) ;
}
2021-11-15 02:06:45 -04:00
// start or update mission
if ( waiting_to_start ) {
// don't start the mission until we have an origin
Location loc ;
if ( ahrs . get_origin ( loc ) ) {
// start/resume the mission (based on MIS_RESTART parameter)
mission . start_or_resume ( ) ;
waiting_to_start = false ;
2021-11-15 06:27:35 -04:00
// initialise mission change check
IGNORE_RETURN ( mis_change_detector . check_for_mission_change ( ) ) ;
2021-11-15 02:06:45 -04:00
}
} else {
2021-11-15 06:27:35 -04:00
// check for mission changes
if ( mis_change_detector . check_for_mission_change ( ) ) {
// if mission is running restart the current command if it is a waypoint command
2023-09-21 10:56:25 -03:00
if ( ( mission . state ( ) = = AP_Mission : : MISSION_RUNNING ) & & ( _submode = = SubMode : : WP ) ) {
2021-11-15 06:27:35 -04:00
if ( mission . restart_current_nav_cmd ( ) ) {
gcs ( ) . send_text ( MAV_SEVERITY_CRITICAL , " Auto mission changed, restarted command " ) ;
} else {
// failed to restart mission for some reason
gcs ( ) . send_text ( MAV_SEVERITY_CRITICAL , " Auto mission changed but failed to restart command " ) ;
}
}
}
2021-11-15 02:06:45 -04:00
mission . update ( ) ;
}
2017-08-03 05:11:45 -03:00
switch ( _submode ) {
2023-09-21 10:56:25 -03:00
case SubMode : : WP :
2017-08-03 05:11:45 -03:00
{
2021-11-18 23:38:12 -04:00
// check if we've reached the destination
if ( ! g2 . wp_nav . reached_destination ( ) | | g2 . wp_nav . is_fast_waypoint ( ) ) {
2019-04-29 03:31:45 -03:00
// update navigation controller
navigate_to_waypoint ( ) ;
2017-08-03 05:11:45 -03:00
} else {
2019-01-06 14:21:57 -04:00
// we have reached the destination so stay here
if ( rover . is_boat ( ) ) {
if ( ! start_loiter ( ) ) {
2021-11-18 23:38:12 -04:00
start_stop ( ) ;
2019-01-06 14:21:57 -04:00
}
} else {
2021-11-18 23:38:12 -04:00
start_stop ( ) ;
2019-01-06 14:21:57 -04:00
}
2019-04-29 03:31:45 -03:00
// update distance to destination
_distance_to_destination = rover . current_loc . get_distance ( g2 . wp_nav . get_destination ( ) ) ;
2017-08-03 05:11:45 -03:00
}
break ;
}
2023-09-21 10:56:25 -03:00
case SubMode : : HeadingAndSpeed :
2017-08-03 05:11:45 -03:00
{
if ( ! _reached_heading ) {
// run steering and throttle controllers
2018-09-10 04:25:15 -03:00
calc_steering_to_heading ( _desired_yaw_cd ) ;
2019-05-04 00:09:24 -03:00
calc_throttle ( calc_speed_nudge ( _desired_speed , is_negative ( _desired_speed ) ) , true ) ;
2017-12-23 01:54:35 -04:00
// check if we have reached within 5 degrees of target
_reached_heading = ( fabsf ( _desired_yaw_cd - ahrs . yaw_sensor ) < 500 ) ;
2017-08-03 05:11:45 -03:00
} else {
2019-01-06 14:21:57 -04:00
// we have reached the destination so stay here
if ( rover . is_boat ( ) ) {
if ( ! start_loiter ( ) ) {
stop_vehicle ( ) ;
}
} else {
stop_vehicle ( ) ;
}
2017-08-03 05:11:45 -03:00
}
break ;
}
2017-11-22 08:38:57 -04:00
2023-09-21 10:56:25 -03:00
case SubMode : : RTL :
2019-01-06 14:21:57 -04:00
rover . mode_rtl . update ( ) ;
break ;
2019-03-08 01:41:50 -04:00
2023-09-21 10:56:25 -03:00
case SubMode : : Loiter :
2019-01-06 14:21:57 -04:00
rover . mode_loiter . update ( ) ;
2017-11-22 08:38:57 -04:00
break ;
2019-03-08 01:41:50 -04:00
2023-09-21 10:56:25 -03:00
case SubMode : : Guided :
2019-03-08 01:41:50 -04:00
{
// send location target to offboard navigation system
send_guided_position_target ( ) ;
rover . mode_guided . update ( ) ;
break ;
}
2019-08-13 23:26:11 -03:00
2023-09-21 10:56:25 -03:00
case SubMode : : Stop :
2019-08-13 23:26:11 -03:00
stop_vehicle ( ) ;
break ;
2022-02-19 01:36:35 -04:00
2023-09-21 10:56:25 -03:00
case SubMode : : NavScriptTime :
2022-02-19 01:36:35 -04:00
rover . mode_guided . update ( ) ;
break ;
2023-04-20 08:53:05 -03:00
2023-09-21 10:56:25 -03:00
case SubMode : : Circle :
2023-04-20 08:53:05 -03:00
rover . g2 . mode_circle . update ( ) ;
break ;
2017-07-18 23:17:45 -03:00
}
}
2019-05-04 00:09:24 -03:00
void ModeAuto : : calc_throttle ( float target_speed , bool avoidance_enabled )
2019-03-15 21:43:49 -03:00
{
// If not autostarting set the throttle to minimum
if ( ! check_trigger ( ) ) {
stop_vehicle ( ) ;
return ;
}
2019-05-04 00:09:24 -03:00
Mode : : calc_throttle ( target_speed , avoidance_enabled ) ;
2019-03-15 21:43:49 -03:00
}
2023-04-20 08:53:05 -03:00
// return heading (in degrees) to target destination (aka waypoint)
float ModeAuto : : wp_bearing ( ) const
{
switch ( _submode ) {
2023-09-21 10:56:25 -03:00
case SubMode : : WP :
2023-04-20 08:53:05 -03:00
return g2 . wp_nav . wp_bearing_cd ( ) * 0.01f ;
2023-09-21 10:56:25 -03:00
case SubMode : : HeadingAndSpeed :
case SubMode : : Stop :
2023-04-20 08:53:05 -03:00
return 0.0f ;
2023-09-21 10:56:25 -03:00
case SubMode : : RTL :
2023-04-20 08:53:05 -03:00
return rover . mode_rtl . wp_bearing ( ) ;
2023-09-21 10:56:25 -03:00
case SubMode : : Loiter :
2023-04-20 08:53:05 -03:00
return rover . mode_loiter . wp_bearing ( ) ;
2023-09-21 10:56:25 -03:00
case SubMode : : Guided :
case SubMode : : NavScriptTime :
2023-04-20 08:53:05 -03:00
return rover . mode_guided . wp_bearing ( ) ;
2023-09-21 10:56:25 -03:00
case SubMode : : Circle :
2023-04-20 08:53:05 -03:00
return rover . g2 . mode_circle . wp_bearing ( ) ;
}
// this line should never be reached
return 0.0f ;
}
// return short-term target heading in degrees (i.e. target heading back to line between waypoints)
float ModeAuto : : nav_bearing ( ) const
{
switch ( _submode ) {
2023-09-21 10:56:25 -03:00
case SubMode : : WP :
2023-04-20 08:53:05 -03:00
return g2 . wp_nav . nav_bearing_cd ( ) * 0.01f ;
2023-09-21 10:56:25 -03:00
case SubMode : : HeadingAndSpeed :
case SubMode : : Stop :
2023-04-20 08:53:05 -03:00
return 0.0f ;
2023-09-21 10:56:25 -03:00
case SubMode : : RTL :
2023-04-20 08:53:05 -03:00
return rover . mode_rtl . nav_bearing ( ) ;
2023-09-21 10:56:25 -03:00
case SubMode : : Loiter :
2023-04-20 08:53:05 -03:00
return rover . mode_loiter . nav_bearing ( ) ;
2023-09-21 10:56:25 -03:00
case SubMode : : Guided :
case SubMode : : NavScriptTime :
2023-04-20 08:53:05 -03:00
return rover . mode_guided . nav_bearing ( ) ;
2023-09-21 10:56:25 -03:00
case SubMode : : Circle :
2023-04-20 08:53:05 -03:00
return rover . g2 . mode_circle . nav_bearing ( ) ;
}
// this line should never be reached
return 0.0f ;
}
// return cross track error (i.e. vehicle's distance from the line between waypoints)
float ModeAuto : : crosstrack_error ( ) const
{
switch ( _submode ) {
2023-09-21 10:56:25 -03:00
case SubMode : : WP :
2023-04-20 08:53:05 -03:00
return g2 . wp_nav . crosstrack_error ( ) ;
2023-09-21 10:56:25 -03:00
case SubMode : : HeadingAndSpeed :
case SubMode : : Stop :
2023-04-20 08:53:05 -03:00
return 0.0f ;
2023-09-21 10:56:25 -03:00
case SubMode : : RTL :
2023-04-20 08:53:05 -03:00
return rover . mode_rtl . crosstrack_error ( ) ;
2023-09-21 10:56:25 -03:00
case SubMode : : Loiter :
2023-04-20 08:53:05 -03:00
return rover . mode_loiter . crosstrack_error ( ) ;
2023-09-21 10:56:25 -03:00
case SubMode : : Guided :
case SubMode : : NavScriptTime :
2023-04-20 08:53:05 -03:00
return rover . mode_guided . crosstrack_error ( ) ;
2023-09-21 10:56:25 -03:00
case SubMode : : Circle :
2023-04-20 08:53:05 -03:00
return rover . g2 . mode_circle . crosstrack_error ( ) ;
}
// this line should never be reached
return 0.0f ;
}
// return desired lateral acceleration
float ModeAuto : : get_desired_lat_accel ( ) const
{
switch ( _submode ) {
2023-09-21 10:56:25 -03:00
case SubMode : : WP :
2023-04-20 08:53:05 -03:00
return g2 . wp_nav . get_lat_accel ( ) ;
2023-09-21 10:56:25 -03:00
case SubMode : : HeadingAndSpeed :
case SubMode : : Stop :
2023-04-20 08:53:05 -03:00
return 0.0f ;
2023-09-21 10:56:25 -03:00
case SubMode : : RTL :
2023-04-20 08:53:05 -03:00
return rover . mode_rtl . get_desired_lat_accel ( ) ;
2023-09-21 10:56:25 -03:00
case SubMode : : Loiter :
2023-04-20 08:53:05 -03:00
return rover . mode_loiter . get_desired_lat_accel ( ) ;
2023-09-21 10:56:25 -03:00
case SubMode : : Guided :
case SubMode : : NavScriptTime :
2023-04-20 08:53:05 -03:00
return rover . mode_guided . get_desired_lat_accel ( ) ;
2023-09-21 10:56:25 -03:00
case SubMode : : Circle :
2023-04-20 08:53:05 -03:00
return rover . g2 . mode_circle . get_desired_lat_accel ( ) ;
}
// this line should never be reached
return 0.0f ;
}
2017-12-08 23:32:53 -04:00
// return distance (in meters) to destination
float ModeAuto : : get_distance_to_destination ( ) const
{
2019-04-29 03:31:45 -03:00
switch ( _submode ) {
2023-09-21 10:56:25 -03:00
case SubMode : : WP :
2019-04-29 03:31:45 -03:00
return _distance_to_destination ;
2023-09-21 10:56:25 -03:00
case SubMode : : HeadingAndSpeed :
case SubMode : : Stop :
2019-04-29 03:31:45 -03:00
// no valid distance so return zero
return 0.0f ;
2023-09-21 10:56:25 -03:00
case SubMode : : RTL :
2019-01-06 14:21:57 -04:00
return rover . mode_rtl . get_distance_to_destination ( ) ;
2023-09-21 10:56:25 -03:00
case SubMode : : Loiter :
2019-04-29 03:31:45 -03:00
return rover . mode_loiter . get_distance_to_destination ( ) ;
2023-09-21 10:56:25 -03:00
case SubMode : : Guided :
case SubMode : : NavScriptTime :
2019-04-29 03:31:45 -03:00
return rover . mode_guided . get_distance_to_destination ( ) ;
2023-09-21 10:56:25 -03:00
case SubMode : : Circle :
2023-04-20 08:53:05 -03:00
return rover . g2 . mode_circle . get_distance_to_destination ( ) ;
2017-12-08 23:32:53 -04:00
}
2019-04-29 03:31:45 -03:00
// this line should never be reached
return 0.0f ;
2017-12-08 23:32:53 -04:00
}
2019-05-17 03:55:31 -03:00
// get desired location
bool ModeAuto : : get_desired_location ( Location & destination ) const
{
switch ( _submode ) {
2023-09-21 10:56:25 -03:00
case SubMode : : WP :
2019-05-17 03:55:31 -03:00
if ( g2 . wp_nav . is_destination_valid ( ) ) {
2019-05-10 02:59:52 -03:00
destination = g2 . wp_nav . get_oa_destination ( ) ;
2019-05-17 03:55:31 -03:00
return true ;
}
return false ;
2023-09-21 10:56:25 -03:00
case SubMode : : HeadingAndSpeed :
case SubMode : : Stop :
2019-05-17 03:55:31 -03:00
// no desired location for this submode
return false ;
2023-09-21 10:56:25 -03:00
case SubMode : : RTL :
2019-05-17 03:55:31 -03:00
return rover . mode_rtl . get_desired_location ( destination ) ;
2023-09-21 10:56:25 -03:00
case SubMode : : Loiter :
2019-05-17 03:55:31 -03:00
return rover . mode_loiter . get_desired_location ( destination ) ;
2023-09-21 10:56:25 -03:00
case SubMode : : Guided :
case SubMode : : NavScriptTime :
2023-05-22 06:36:02 -03:00
return rover . mode_guided . get_desired_location ( destination ) ;
2023-09-21 10:56:25 -03:00
case SubMode : : Circle :
2023-04-20 08:53:05 -03:00
return rover . g2 . mode_circle . get_desired_location ( destination ) ;
2019-05-17 03:55:31 -03:00
}
// we should never reach here but just in case
return false ;
}
2017-08-03 05:11:45 -03:00
// set desired location to drive to
2021-11-18 23:38:12 -04:00
bool ModeAuto : : set_desired_location ( const Location & destination , Location next_destination )
2017-08-03 05:11:45 -03:00
{
// call parent
2021-11-18 23:38:12 -04:00
if ( ! Mode : : set_desired_location ( destination , next_destination ) ) {
2019-05-08 21:54:40 -03:00
return false ;
}
2017-08-03 05:11:45 -03:00
2023-09-21 10:56:25 -03:00
_submode = SubMode : : WP ;
2019-05-08 21:54:40 -03:00
return true ;
2017-08-03 05:11:45 -03:00
}
// return true if vehicle has reached or even passed destination
2019-03-15 01:26:01 -03:00
bool ModeAuto : : reached_destination ( ) const
2017-07-18 23:17:45 -03:00
{
2019-03-08 01:41:50 -04:00
switch ( _submode ) {
2023-09-21 10:56:25 -03:00
case SubMode : : WP :
2019-04-29 03:31:45 -03:00
return g2 . wp_nav . reached_destination ( ) ;
2019-03-08 01:41:50 -04:00
break ;
2023-09-21 10:56:25 -03:00
case SubMode : : HeadingAndSpeed :
case SubMode : : Stop :
2019-03-08 01:41:50 -04:00
// always return true because this is the safer option to allow missions to continue
return true ;
break ;
2023-09-21 10:56:25 -03:00
case SubMode : : RTL :
2019-01-06 14:21:57 -04:00
return rover . mode_rtl . reached_destination ( ) ;
2019-03-08 01:41:50 -04:00
break ;
2023-09-21 10:56:25 -03:00
case SubMode : : Loiter :
2019-03-08 01:41:50 -04:00
return rover . mode_loiter . reached_destination ( ) ;
break ;
2023-09-21 10:56:25 -03:00
case SubMode : : Guided :
case SubMode : : NavScriptTime :
2019-03-08 01:41:50 -04:00
return rover . mode_guided . reached_destination ( ) ;
2023-09-21 10:56:25 -03:00
case SubMode : : Circle :
2023-04-20 08:53:05 -03:00
return rover . g2 . mode_circle . reached_destination ( ) ;
2017-11-22 08:38:57 -04:00
}
2019-03-08 01:41:50 -04:00
2017-08-03 05:11:45 -03:00
// we should never reach here but just in case, return true to allow missions to continue
return true ;
}
2019-11-04 04:31:13 -04:00
// set desired speed in m/s
bool ModeAuto : : set_desired_speed ( float speed )
2017-08-03 05:11:45 -03:00
{
2019-11-04 04:31:13 -04:00
switch ( _submode ) {
2023-09-21 10:56:25 -03:00
case SubMode : : WP :
case SubMode : : Stop :
2022-01-05 20:43:58 -04:00
return g2 . wp_nav . set_speed_max ( speed ) ;
2023-09-21 10:56:25 -03:00
case SubMode : : HeadingAndSpeed :
2019-11-04 04:31:13 -04:00
_desired_speed = speed ;
return true ;
2023-09-21 10:56:25 -03:00
case SubMode : : RTL :
2019-11-04 04:31:13 -04:00
return rover . mode_rtl . set_desired_speed ( speed ) ;
2023-09-21 10:56:25 -03:00
case SubMode : : Loiter :
2019-11-04 04:31:13 -04:00
return rover . mode_loiter . set_desired_speed ( speed ) ;
2023-09-21 10:56:25 -03:00
case SubMode : : Guided :
case SubMode : : NavScriptTime :
2019-11-04 04:31:13 -04:00
return rover . mode_guided . set_desired_speed ( speed ) ;
2023-09-21 10:56:25 -03:00
case SubMode : : Circle :
2023-04-20 08:53:05 -03:00
return rover . g2 . mode_circle . set_desired_speed ( speed ) ;
2017-08-03 05:11:45 -03:00
}
2019-11-04 04:31:13 -04:00
return false ;
2017-07-18 23:17:45 -03:00
}
2017-11-22 08:38:57 -04:00
// start RTL (within auto)
void ModeAuto : : start_RTL ( )
{
2019-01-06 14:21:57 -04:00
if ( rover . mode_rtl . enter ( ) ) {
2023-09-21 10:56:25 -03:00
_submode = SubMode : : RTL ;
2017-11-22 08:38:57 -04:00
}
}
2022-02-19 01:36:35 -04:00
// lua scripts use this to retrieve the contents of the active command
2022-10-13 21:37:52 -03:00
bool ModeAuto : : nav_script_time ( uint16_t & id , uint8_t & cmd , float & arg1 , float & arg2 , int16_t & arg3 , int16_t & arg4 )
2022-02-19 01:36:35 -04:00
{
# if AP_SCRIPTING_ENABLED
2023-09-21 10:56:25 -03:00
if ( _submode = = SubMode : : NavScriptTime ) {
2022-02-19 01:36:35 -04:00
id = nav_scripting . id ;
cmd = nav_scripting . command ;
arg1 = nav_scripting . arg1 ;
arg2 = nav_scripting . arg2 ;
2022-10-13 21:37:52 -03:00
arg3 = nav_scripting . arg3 ;
arg4 = nav_scripting . arg4 ;
2022-02-19 01:36:35 -04:00
return true ;
}
# endif
return false ;
}
// lua scripts use this to indicate when they have complete the command
void ModeAuto : : nav_script_time_done ( uint16_t id )
{
# if AP_SCRIPTING_ENABLED
2023-09-21 10:56:25 -03:00
if ( ( _submode = = SubMode : : NavScriptTime ) & & ( id = = nav_scripting . id ) ) {
2022-02-19 01:36:35 -04:00
nav_scripting . done = true ;
}
# endif
}
2019-03-15 21:43:49 -03:00
// check for triggering of start of auto mode
2017-07-18 23:17:45 -03:00
bool ModeAuto : : check_trigger ( void )
{
// check for user pressing the auto trigger to off
if ( auto_triggered & & g . auto_trigger_pin ! = - 1 & & rover . check_digital_pin ( g . auto_trigger_pin ) = = 1 ) {
gcs ( ) . send_text ( MAV_SEVERITY_WARNING , " AUTO triggered off " ) ;
auto_triggered = false ;
return false ;
}
// if already triggered, then return true, so you don't
// need to hold the switch down
if ( auto_triggered ) {
return true ;
}
// return true if auto trigger and kickstart are disabled
if ( g . auto_trigger_pin = = - 1 & & is_zero ( g . auto_kickstart ) ) {
// no trigger configured - let's go!
auto_triggered = true ;
return true ;
}
// check if trigger pin has been pushed
if ( g . auto_trigger_pin ! = - 1 & & rover . check_digital_pin ( g . auto_trigger_pin ) = = 0 ) {
gcs ( ) . send_text ( MAV_SEVERITY_WARNING , " Triggered AUTO with pin " ) ;
auto_triggered = true ;
return true ;
}
// check if mission is started by giving vehicle a kick with acceleration > AUTO_KICKSTART
if ( ! is_zero ( g . auto_kickstart ) ) {
const float xaccel = rover . ins . get_accel ( ) . x ;
if ( xaccel > = g . auto_kickstart ) {
gcs ( ) . send_text ( MAV_SEVERITY_WARNING , " Triggered AUTO xaccel=%.1f " , static_cast < double > ( xaccel ) ) ;
auto_triggered = true ;
return true ;
}
}
return false ;
}
2019-01-06 14:21:57 -04:00
bool ModeAuto : : start_loiter ( )
{
if ( rover . mode_loiter . enter ( ) ) {
2023-09-21 10:56:25 -03:00
_submode = SubMode : : Loiter ;
2019-01-06 14:21:57 -04:00
return true ;
}
return false ;
}
2019-03-15 21:43:49 -03:00
// hand over control to external navigation controller in AUTO mode
void ModeAuto : : start_guided ( const Location & loc )
{
if ( rover . mode_guided . enter ( ) ) {
2023-09-21 10:56:25 -03:00
_submode = SubMode : : Guided ;
2019-03-15 21:43:49 -03:00
// initialise guided start time and position as reference for limit checking
rover . mode_guided . limit_init_time_and_location ( ) ;
// sanity check target location
if ( ( loc . lat ! = 0 ) | | ( loc . lng ! = 0 ) ) {
guided_target . loc = loc ;
2019-03-26 21:34:07 -03:00
guided_target . loc . sanitize ( rover . current_loc ) ;
2019-03-15 21:43:49 -03:00
guided_target . valid = true ;
} else {
guided_target . valid = false ;
}
}
}
2019-08-13 23:26:11 -03:00
// start stopping vehicle as quickly as possible
void ModeAuto : : start_stop ( )
{
2023-09-21 10:56:25 -03:00
_submode = SubMode : : Stop ;
2019-08-13 23:26:11 -03:00
}
2019-03-15 21:43:49 -03:00
// send latest position target to offboard navigation system
void ModeAuto : : send_guided_position_target ( )
{
if ( ! guided_target . valid ) {
return ;
}
// send at maximum of 1hz
const uint32_t now_ms = AP_HAL : : millis ( ) ;
if ( ( guided_target . last_sent_ms = = 0 ) | | ( now_ms - guided_target . last_sent_ms > AUTO_GUIDED_SEND_TARGET_MS ) ) {
guided_target . last_sent_ms = now_ms ;
// get system id and component id of offboard navigation system
uint8_t sysid ;
uint8_t compid ;
mavlink_channel_t chan ;
if ( GCS_MAVLINK : : find_by_mavtype ( MAV_TYPE_ONBOARD_CONTROLLER , sysid , compid , chan ) ) {
2019-06-19 08:26:19 -03:00
gcs ( ) . chan ( chan - MAVLINK_COMM_0 ) - > send_set_position_target_global_int ( sysid , compid , guided_target . loc ) ;
2019-03-15 21:43:49 -03:00
}
}
}
2019-03-15 22:14:34 -03:00
/********************************************************************************/
// Command Event Handlers
/********************************************************************************/
bool ModeAuto : : start_command ( const AP_Mission : : Mission_Command & cmd )
{
// log when new commands start
if ( rover . should_log ( MASK_LOG_CMD ) ) {
rover . logger . Write_Mission_Cmd ( mission , cmd ) ;
}
switch ( cmd . id ) {
case MAV_CMD_NAV_WAYPOINT : // Navigate to Waypoint
2019-05-08 21:54:40 -03:00
return do_nav_wp ( cmd , false ) ;
2019-03-15 22:14:34 -03:00
case MAV_CMD_NAV_RETURN_TO_LAUNCH :
do_RTL ( ) ;
break ;
case MAV_CMD_NAV_LOITER_UNLIM : // Loiter indefinitely
case MAV_CMD_NAV_LOITER_TIME : // Loiter for specified time
2019-05-08 21:54:40 -03:00
return do_nav_wp ( cmd , true ) ;
2019-03-15 22:14:34 -03:00
2023-04-20 08:53:05 -03:00
case MAV_CMD_NAV_LOITER_TURNS :
return do_circle ( cmd ) ;
2019-03-15 22:14:34 -03:00
case MAV_CMD_NAV_GUIDED_ENABLE : // accept navigation commands from external nav computer
do_nav_guided_enable ( cmd ) ;
break ;
case MAV_CMD_NAV_SET_YAW_SPEED :
do_nav_set_yaw_speed ( cmd ) ;
break ;
2019-08-09 15:42:19 -03:00
case MAV_CMD_NAV_DELAY : // 93 Delay the next navigation command
do_nav_delay ( cmd ) ;
break ;
2022-02-19 01:36:35 -04:00
# if AP_SCRIPTING_ENABLED
case MAV_CMD_NAV_SCRIPT_TIME :
do_nav_script_time ( cmd ) ;
break ;
# endif
2019-03-15 22:14:34 -03:00
// Conditional commands
case MAV_CMD_CONDITION_DELAY :
do_wait_delay ( cmd ) ;
break ;
case MAV_CMD_CONDITION_DISTANCE :
do_within_distance ( cmd ) ;
break ;
// Do commands
case MAV_CMD_DO_CHANGE_SPEED :
do_change_speed ( cmd ) ;
break ;
case MAV_CMD_DO_SET_HOME :
do_set_home ( cmd ) ;
break ;
2020-07-24 14:23:45 -03:00
# if HAL_MOUNT_ENABLED
2019-03-15 22:14:34 -03:00
// Sets the region of interest (ROI) for a sensor set or the
// vehicle itself. This can then be used by the vehicles control
// system to control the vehicle attitude and the attitude of various
// devices such as cameras.
// |Region of interest mode. (see MAV_ROI enum)| Waypoint index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple cameras etc.)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z|
case MAV_CMD_DO_SET_ROI :
if ( cmd . content . location . alt = = 0 & & cmd . content . location . lat = = 0 & & cmd . content . location . lng = = 0 ) {
// switch off the camera tracking if enabled
if ( rover . camera_mount . get_mode ( ) = = MAV_MOUNT_MODE_GPS_POINT ) {
rover . camera_mount . set_mode_to_default ( ) ;
}
} else {
// send the command to the camera mount
rover . camera_mount . set_roi_target ( cmd . content . location ) ;
}
break ;
# endif
case MAV_CMD_DO_SET_REVERSE :
do_set_reverse ( cmd ) ;
break ;
case MAV_CMD_DO_FENCE_ENABLE :
2022-07-19 08:33:13 -03:00
# if AP_FENCE_ENABLED
2019-03-15 22:14:34 -03:00
if ( cmd . p1 = = 0 ) { //disable
2022-03-04 12:41:00 -04:00
rover . fence . enable ( false ) ;
2019-03-15 22:14:34 -03:00
gcs ( ) . send_text ( MAV_SEVERITY_INFO , " Fence Disabled " ) ;
} else { //enable fence
2022-03-04 12:41:00 -04:00
rover . fence . enable ( true ) ;
2019-03-15 22:14:34 -03:00
gcs ( ) . send_text ( MAV_SEVERITY_INFO , " Fence Enabled " ) ;
}
2022-03-04 12:41:00 -04:00
# endif
2019-03-15 22:14:34 -03:00
break ;
case MAV_CMD_DO_GUIDED_LIMITS :
do_guided_limits ( cmd ) ;
break ;
default :
// return false for unhandled commands
return false ;
}
// if we got this far we must have been successful
return true ;
}
// exit_mission - callback function called from ap-mission when the mission has completed
void ModeAuto : : exit_mission ( )
{
// play a tone
AP_Notify : : events . mission_complete = 1 ;
// send message
gcs ( ) . send_text ( MAV_SEVERITY_NOTICE , " Mission Complete " ) ;
2019-10-08 01:21:18 -03:00
if ( g2 . mis_done_behave = = MIS_DONE_BEHAVE_LOITER & & start_loiter ( ) ) {
2019-03-15 22:14:34 -03:00
return ;
}
2019-10-17 00:48:47 -03:00
if ( g2 . mis_done_behave = = MIS_DONE_BEHAVE_ACRO & & rover . set_mode ( rover . mode_acro , ModeReason : : MISSION_END ) ) {
2019-03-15 22:14:34 -03:00
return ;
}
2020-02-20 13:25:54 -04:00
if ( g2 . mis_done_behave = = MIS_DONE_BEHAVE_MANUAL & & rover . set_mode ( rover . mode_manual , ModeReason : : MISSION_END ) ) {
return ;
}
2019-10-08 01:21:18 -03:00
start_stop ( ) ;
2019-03-15 22:14:34 -03:00
}
// verify_command_callback - callback function called from ap-mission at 10hz or higher when a command is being run
// we double check that the flight mode is AUTO to avoid the possibility of ap-mission triggering actions while we're not in AUTO mode
bool ModeAuto : : verify_command_callback ( const AP_Mission : : Mission_Command & cmd )
{
const bool cmd_complete = verify_command ( cmd ) ;
// send message to GCS
if ( cmd_complete ) {
gcs ( ) . send_mission_item_reached_message ( cmd . index ) ;
}
return cmd_complete ;
}
/*******************************************************************************
Verify command Handlers
Each type of mission element has a " verify " operation . The verify
operation returns true when the mission element has completed and we
should move onto the next mission element .
Return true if we do not recognize the command so that we move on to the next command
* * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * */
bool ModeAuto : : verify_command ( const AP_Mission : : Mission_Command & cmd )
{
switch ( cmd . id ) {
case MAV_CMD_NAV_WAYPOINT :
return verify_nav_wp ( cmd ) ;
case MAV_CMD_NAV_RETURN_TO_LAUNCH :
return verify_RTL ( ) ;
case MAV_CMD_NAV_LOITER_UNLIM :
return verify_loiter_unlimited ( cmd ) ;
2023-04-20 08:53:05 -03:00
case MAV_CMD_NAV_LOITER_TURNS :
return verify_circle ( cmd ) ;
2019-03-15 22:14:34 -03:00
case MAV_CMD_NAV_LOITER_TIME :
return verify_loiter_time ( cmd ) ;
case MAV_CMD_NAV_GUIDED_ENABLE :
return verify_nav_guided_enable ( cmd ) ;
2019-08-09 15:42:19 -03:00
case MAV_CMD_NAV_DELAY :
2022-02-19 02:06:56 -04:00
return verify_nav_delay ( cmd ) ;
2019-08-09 15:42:19 -03:00
2022-02-19 01:36:35 -04:00
# if AP_SCRIPTING_ENABLED
case MAV_CMD_NAV_SCRIPT_TIME :
return verify_nav_script_time ( ) ;
# endif
2019-03-15 22:14:34 -03:00
case MAV_CMD_CONDITION_DELAY :
return verify_wait_delay ( ) ;
case MAV_CMD_CONDITION_DISTANCE :
return verify_within_distance ( ) ;
case MAV_CMD_NAV_SET_YAW_SPEED :
return verify_nav_set_yaw_speed ( ) ;
// do commands (always return true)
case MAV_CMD_DO_CHANGE_SPEED :
case MAV_CMD_DO_SET_HOME :
case MAV_CMD_DO_SET_CAM_TRIGG_DIST :
case MAV_CMD_DO_SET_ROI :
case MAV_CMD_DO_SET_REVERSE :
case MAV_CMD_DO_FENCE_ENABLE :
case MAV_CMD_DO_GUIDED_LIMITS :
return true ;
default :
// error message
gcs ( ) . send_text ( MAV_SEVERITY_WARNING , " Skipping invalid cmd #%i " , cmd . id ) ;
// return true if we do not recognize the command so that we move on to the next command
return true ;
}
}
/********************************************************************************/
// Nav (Must) commands
/********************************************************************************/
void ModeAuto : : do_RTL ( void )
{
// start rtl in auto mode
start_RTL ( ) ;
}
2019-05-08 21:54:40 -03:00
bool ModeAuto : : do_nav_wp ( const AP_Mission : : Mission_Command & cmd , bool always_stop_at_destination )
2019-03-15 22:14:34 -03:00
{
// retrieve and sanitize target location
Location cmdloc = cmd . content . location ;
2019-03-26 21:34:07 -03:00
cmdloc . sanitize ( rover . current_loc ) ;
2021-11-18 23:38:12 -04:00
// delayed stored in p1 in seconds
loiter_duration = ( ( int16_t ) cmd . p1 < 0 ) ? 0 : cmd . p1 ;
loiter_start_time = 0 ;
if ( loiter_duration > 0 ) {
always_stop_at_destination = true ;
}
// do not add next wp if there are no more navigation commands
AP_Mission : : Mission_Command next_cmd ;
if ( always_stop_at_destination | | ! mission . get_next_nav_cmd ( cmd . index + 1 , next_cmd ) ) {
// single destination
if ( ! set_desired_location ( cmdloc ) ) {
return false ;
}
} else {
// retrieve and sanitize next destination location
Location next_cmdloc = next_cmd . content . location ;
next_cmdloc . sanitize ( cmdloc ) ;
if ( ! set_desired_location ( cmdloc , next_cmdloc ) ) {
return false ;
}
2019-05-08 21:54:40 -03:00
}
// just starting so we haven't previously reached the waypoint
previously_reached_wp = false ;
return true ;
2019-03-15 22:14:34 -03:00
}
2019-08-09 15:42:19 -03:00
// do_nav_delay - Delay the next navigation command
void ModeAuto : : do_nav_delay ( const AP_Mission : : Mission_Command & cmd )
{
nav_delay_time_start_ms = millis ( ) ;
2019-08-13 23:26:11 -03:00
// boats loiter, cars and balancebots stop
if ( rover . is_boat ( ) ) {
if ( ! start_loiter ( ) ) {
start_stop ( ) ;
}
} else {
start_stop ( ) ;
}
2019-08-09 15:42:19 -03:00
if ( cmd . content . nav_delay . seconds > 0 ) {
// relative delay
nav_delay_time_max_ms = cmd . content . nav_delay . seconds * 1000 ; // convert seconds to milliseconds
} else {
// absolute delay to utc time
2023-10-05 04:40:35 -03:00
# if AP_RTC_ENABLED
2019-08-09 15:42:19 -03:00
nav_delay_time_max_ms = AP : : rtc ( ) . get_time_utc ( cmd . content . nav_delay . hour_utc , cmd . content . nav_delay . min_utc , cmd . content . nav_delay . sec_utc , 0 ) ;
2023-10-05 04:40:35 -03:00
# else
nav_delay_time_max_ms = 0 ;
# endif
2019-08-09 15:42:19 -03:00
}
2019-08-18 23:37:51 -03:00
gcs ( ) . send_text ( MAV_SEVERITY_INFO , " Delaying %u sec " , ( unsigned ) ( nav_delay_time_max_ms / 1000 ) ) ;
2019-08-09 15:42:19 -03:00
}
2019-03-15 22:14:34 -03:00
// start guided within auto to allow external navigation system to control vehicle
void ModeAuto : : do_nav_guided_enable ( const AP_Mission : : Mission_Command & cmd )
{
if ( cmd . p1 > 0 ) {
start_guided ( cmd . content . location ) ;
}
}
2019-11-04 04:30:54 -04:00
// do_set_yaw_speed - turn to a specified heading and achieve a given speed
2019-03-15 22:14:34 -03:00
void ModeAuto : : do_nav_set_yaw_speed ( const AP_Mission : : Mission_Command & cmd )
{
float desired_heading_cd ;
// get final angle, 1 = Relative, 0 = Absolute
if ( cmd . content . set_yaw_speed . relative_angle > 0 ) {
// relative angle
desired_heading_cd = wrap_180_cd ( ahrs . yaw_sensor + cmd . content . set_yaw_speed . angle_deg * 100.0f ) ;
} else {
// absolute angle
desired_heading_cd = cmd . content . set_yaw_speed . angle_deg * 100.0f ;
}
2019-11-04 04:31:13 -04:00
// set targets
2019-04-29 03:31:45 -03:00
const float speed_max = g2 . wp_nav . get_default_speed ( ) ;
2019-11-04 04:31:13 -04:00
_desired_speed = constrain_float ( cmd . content . set_yaw_speed . speed , - speed_max , speed_max ) ;
_desired_yaw_cd = desired_heading_cd ;
_reached_heading = false ;
2023-09-21 10:56:25 -03:00
_submode = SubMode : : HeadingAndSpeed ;
2019-03-15 22:14:34 -03:00
}
/********************************************************************************/
// Verify Nav (Must) commands
/********************************************************************************/
bool ModeAuto : : verify_nav_wp ( const AP_Mission : : Mission_Command & cmd )
{
// exit immediately if we haven't reached the destination
if ( ! reached_destination ( ) ) {
return false ;
}
// Check if this is the first time we have noticed reaching the waypoint
if ( ! previously_reached_wp ) {
previously_reached_wp = true ;
// check if we are loitering at this waypoint - the message sent to the GCS is different
if ( loiter_duration > 0 ) {
// send message including loiter time
gcs ( ) . send_text ( MAV_SEVERITY_INFO , " Reached waypoint #%u. Loiter for %u seconds " ,
2019-07-29 03:35:10 -03:00
( unsigned int ) cmd . index ,
( unsigned int ) loiter_duration ) ;
2019-03-15 22:14:34 -03:00
// record the current time i.e. start timer
loiter_start_time = millis ( ) ;
} else {
// send simpler message to GCS
2019-07-29 03:35:10 -03:00
gcs ( ) . send_text ( MAV_SEVERITY_INFO , " Reached waypoint #%u " , ( unsigned int ) cmd . index ) ;
2019-03-15 22:14:34 -03:00
}
}
// Check if we have loitered long enough
if ( loiter_duration = = 0 ) {
return true ;
} else {
return ( ( ( millis ( ) - loiter_start_time ) / 1000 ) > = loiter_duration ) ;
}
}
2019-08-09 15:42:19 -03:00
// verify_nav_delay - check if we have waited long enough
bool ModeAuto : : verify_nav_delay ( const AP_Mission : : Mission_Command & cmd )
{
if ( millis ( ) - nav_delay_time_start_ms > nav_delay_time_max_ms ) {
nav_delay_time_max_ms = 0 ;
return true ;
}
return false ;
}
2021-02-01 12:26:24 -04:00
bool ModeAuto : : verify_RTL ( ) const
2019-03-15 22:14:34 -03:00
{
return reached_destination ( ) ;
}
bool ModeAuto : : verify_loiter_unlimited ( const AP_Mission : : Mission_Command & cmd )
{
verify_nav_wp ( cmd ) ;
return false ;
}
// verify_loiter_time - check if we have loitered long enough
bool ModeAuto : : verify_loiter_time ( const AP_Mission : : Mission_Command & cmd )
{
const bool result = verify_nav_wp ( cmd ) ;
if ( result ) {
gcs ( ) . send_text ( MAV_SEVERITY_WARNING , " Finished active loiter " ) ;
}
return result ;
}
// check if guided has completed
bool ModeAuto : : verify_nav_guided_enable ( const AP_Mission : : Mission_Command & cmd )
{
// if we failed to enter guided or this command disables guided
// return true so we move to next command
2023-09-21 10:56:25 -03:00
if ( _submode ! = SubMode : : Guided | | cmd . p1 = = 0 ) {
2019-03-15 22:14:34 -03:00
return true ;
}
// if a location target was set, return true once vehicle is close
if ( guided_target . valid ) {
2019-04-29 03:31:45 -03:00
if ( rover . current_loc . get_distance ( guided_target . loc ) < = rover . g2 . wp_nav . get_radius ( ) ) {
2019-03-15 22:14:34 -03:00
return true ;
}
}
// guided command complete once a limit is breached
return rover . mode_guided . limit_breached ( ) ;
}
// verify_yaw - return true if we have reached the desired heading
bool ModeAuto : : verify_nav_set_yaw_speed ( )
{
2023-09-21 10:56:25 -03:00
if ( _submode = = SubMode : : HeadingAndSpeed ) {
2019-11-04 04:31:13 -04:00
return _reached_heading ;
}
// we should never reach here but just in case, return true to allow missions to continue
return true ;
2019-03-15 22:14:34 -03:00
}
2023-04-20 08:53:05 -03:00
bool ModeAuto : : do_circle ( const AP_Mission : : Mission_Command & cmd )
{
// retrieve and sanitize target location
Location circle_center = cmd . content . location ;
circle_center . sanitize ( rover . current_loc ) ;
// calculate radius
uint16_t circle_radius_m = HIGHBYTE ( cmd . p1 ) ; // circle radius held in high byte of p1
if ( cmd . id = = MAV_CMD_NAV_LOITER_TURNS & &
cmd . type_specific_bits & ( 1U < < 0 ) ) {
// special storage handling allows for larger radii
circle_radius_m * = 10 ;
}
// initialise circle mode
if ( g2 . mode_circle . set_center ( circle_center , circle_radius_m , cmd . content . location . loiter_ccw ) ) {
2023-09-21 10:56:25 -03:00
_submode = SubMode : : Circle ;
2023-04-20 08:53:05 -03:00
return true ;
}
return false ;
}
bool ModeAuto : : verify_circle ( const AP_Mission : : Mission_Command & cmd )
{
// check if we have completed circling
return ( ( g2 . mode_circle . get_angle_total_rad ( ) / M_2PI ) > = LOWBYTE ( cmd . p1 ) ) ;
}
2019-03-15 22:14:34 -03:00
/********************************************************************************/
// Condition (May) commands
/********************************************************************************/
void ModeAuto : : do_wait_delay ( const AP_Mission : : Mission_Command & cmd )
{
condition_start = millis ( ) ;
condition_value = static_cast < int32_t > ( cmd . content . delay . seconds * 1000 ) ; // convert seconds to milliseconds
}
void ModeAuto : : do_within_distance ( const AP_Mission : : Mission_Command & cmd )
{
condition_value = cmd . content . distance . meters ;
}
/********************************************************************************/
// Verify Condition (May) commands
/********************************************************************************/
bool ModeAuto : : verify_wait_delay ( )
{
if ( static_cast < uint32_t > ( millis ( ) - condition_start ) > static_cast < uint32_t > ( condition_value ) ) {
condition_value = 0 ;
return true ;
}
return false ;
}
bool ModeAuto : : verify_within_distance ( )
{
if ( get_distance_to_destination ( ) < condition_value ) {
condition_value = 0 ;
return true ;
}
return false ;
}
/********************************************************************************/
// Do (Now) commands
/********************************************************************************/
void ModeAuto : : do_change_speed ( const AP_Mission : : Mission_Command & cmd )
{
// set speed for active mode
if ( set_desired_speed ( cmd . content . speed . target_ms ) ) {
gcs ( ) . send_text ( MAV_SEVERITY_INFO , " speed: %.1f m/s " , static_cast < double > ( cmd . content . speed . target_ms ) ) ;
}
}
void ModeAuto : : do_set_home ( const AP_Mission : : Mission_Command & cmd )
{
if ( cmd . p1 = = 1 & & rover . have_position ) {
if ( ! rover . set_home_to_current_location ( false ) ) {
// ignored...
}
} else {
if ( ! rover . set_home ( cmd . content . location , false ) ) {
// ignored...
}
}
}
void ModeAuto : : do_set_reverse ( const AP_Mission : : Mission_Command & cmd )
{
set_reversed ( cmd . p1 = = 1 ) ;
}
// set timeout and position limits for guided within auto
void ModeAuto : : do_guided_limits ( const AP_Mission : : Mission_Command & cmd )
{
rover . mode_guided . limit_set (
cmd . p1 * 1000 , // convert seconds to ms
cmd . content . guided_limits . horiz_max ) ;
}
2022-02-19 01:36:35 -04:00
# if AP_SCRIPTING_ENABLED
// start accepting position, velocity and acceleration targets from lua scripts
void ModeAuto : : do_nav_script_time ( const AP_Mission : : Mission_Command & cmd )
{
// call regular guided flight mode initialisation
if ( rover . mode_guided . enter ( ) ) {
2023-09-21 10:56:25 -03:00
_submode = SubMode : : NavScriptTime ;
2022-02-19 01:36:35 -04:00
nav_scripting . done = false ;
nav_scripting . id + + ;
nav_scripting . start_ms = millis ( ) ;
nav_scripting . command = cmd . content . nav_script_time . command ;
nav_scripting . timeout_s = cmd . content . nav_script_time . timeout_s ;
2022-10-19 01:14:51 -03:00
nav_scripting . arg1 = cmd . content . nav_script_time . arg1 . get ( ) ;
nav_scripting . arg2 = cmd . content . nav_script_time . arg2 . get ( ) ;
2022-10-13 21:37:52 -03:00
nav_scripting . arg3 = cmd . content . nav_script_time . arg3 ;
nav_scripting . arg4 = cmd . content . nav_script_time . arg4 ;
2022-02-19 01:36:35 -04:00
} else {
// for safety we set nav_scripting to done to protect against the mission getting stuck
nav_scripting . done = true ;
}
}
// check if verify_nav_script_time command has completed
bool ModeAuto : : verify_nav_script_time ( )
{
// if done or timeout then return true
if ( nav_scripting . done | |
2022-02-23 01:08:39 -04:00
( ( nav_scripting . timeout_s > 0 ) & &
( AP_HAL : : millis ( ) - nav_scripting . start_ms ) > ( nav_scripting . timeout_s * 1000 ) ) ) {
2022-02-19 01:36:35 -04:00
return true ;
}
return false ;
}
# endif