2015-05-29 23:12:49 -03:00
# include "Copter.h"
2024-09-04 00:48:37 -03:00
# if MODE_AUTO_ENABLED
2018-02-21 22:06:07 -04:00
2014-01-23 01:14:58 -04:00
/*
2016-07-25 15:45:29 -03:00
* Init and run calls for auto flight mode
2014-01-24 22:37:42 -04:00
*
* This file contains the implementation for Land , Waypoint navigation and Takeoff from Auto mode
* Command execution code ( i . e . command_logic . pde ) should :
2014-01-27 23:20:39 -04:00
* a ) switch to Auto flight mode with set_mode ( ) function . This will cause auto_init to be called
* b ) call one of the three auto initialisation functions : auto_wp_start ( ) , auto_takeoff_start ( ) , auto_land_start ( )
2014-01-24 22:37:42 -04:00
* c ) call one of the verify functions auto_wp_verify ( ) , auto_takeoff_verify , auto_land_verify repeated to check if the command has completed
* The main loop ( i . e . fast loop ) will call update_flight_modes ( ) which will in turn call auto_run ( ) which , based upon the auto_mode variable will call
* correct auto_wp_run , auto_takeoff_run or auto_land_run to actually implement the feature
*/
/*
* While in the auto flight mode , navigation or do / now commands can be run .
2014-01-27 23:20:39 -04:00
* Code in this file implements the navigation commands
2014-01-23 01:14:58 -04:00
*/
// auto_init - initialise auto controller
2019-05-09 23:18:49 -03:00
bool ModeAuto : : init ( bool ignore_checks )
2014-01-23 01:14:58 -04:00
{
2021-07-24 20:25:18 -03:00
auto_RTL = false ;
2019-02-27 23:56:36 -04:00
if ( mission . num_commands ( ) > 1 | | ignore_checks ) {
2017-01-05 14:07:14 -04:00
// reject switching to auto mode if landed with motors armed but first command is not a takeoff (reduce chance of flips)
2019-05-09 23:18:49 -03:00
if ( motors - > armed ( ) & & copter . ap . land_complete & & ! mission . starts_with_takeoff_cmd ( ) ) {
2017-07-08 21:56:49 -03:00
gcs ( ) . send_text ( MAV_SEVERITY_CRITICAL , " Auto: Missing Takeoff Cmd " ) ;
2016-05-19 07:34:07 -03:00
return false ;
}
2022-03-16 00:55:13 -03:00
_mode = SubMode : : LOITER ;
2014-02-18 08:35:29 -04: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
2022-09-24 11:12:33 -03:00
if ( auto_yaw . mode ( ) = = AutoYaw : : Mode : : ROI ) {
auto_yaw . set_mode ( AutoYaw : : Mode : : HOLD ) ;
2014-02-18 08:35:29 -04:00
}
2014-05-07 03:03:26 -03:00
// initialise waypoint and spline controller
2017-01-09 03:31:26 -04:00
wp_nav - > wp_and_spline_init ( ) ;
2014-05-07 03:03:26 -03:00
2023-11-28 07:36:08 -04:00
// initialise desired speed overrides
desired_speed_override = { 0 , 0 , 0 } ;
2021-03-04 01:04:02 -04:00
// set flag to start mission
waiting_to_start = true ;
2021-03-04 04:19:05 -04:00
// initialise mission change check (ignore results)
2022-01-07 21:25:10 -04:00
IGNORE_RETURN ( mis_change_detector . check_for_mission_change ( ) ) ;
2021-03-04 04:19:05 -04:00
2014-10-13 05:41:48 -03:00
// clear guided limits
2018-02-07 22:21:09 -04:00
copter . mode_guided . limit_clear ( ) ;
2014-10-13 05:41:48 -03:00
2021-09-28 01:15:46 -03:00
// reset flag indicating if pilot has applied roll or pitch inputs during landing
copter . ap . land_repo_active = false ;
2023-03-22 05:45:41 -03:00
# if AC_PRECLAND_ENABLED
2021-07-21 16:33:37 -03:00
// initialise precland state machine
copter . precland_statemachine . init ( ) ;
# endif
2014-01-23 01:14:58 -04:00
return true ;
2017-11-09 15:20:53 -04:00
} else {
2014-01-23 01:14:58 -04:00
return false ;
}
}
2021-04-20 09:36:36 -03:00
// stop mission when we leave auto mode
void ModeAuto : : exit ( )
{
if ( copter . mode_auto . mission . state ( ) = = AP_Mission : : MISSION_RUNNING ) {
copter . mode_auto . mission . stop ( ) ;
}
# if HAL_MOUNT_ENABLED
copter . camera_mount . set_mode_to_default ( ) ;
# endif // HAL_MOUNT_ENABLED
2021-07-24 20:25:18 -03:00
auto_RTL = false ;
2021-04-20 09:36:36 -03:00
}
2014-01-23 01:14:58 -04:00
// auto_run - runs the auto controller
// should be called at 100hz or more
2019-05-09 23:18:49 -03:00
void ModeAuto : : run ( )
2014-01-23 01:14:58 -04:00
{
2021-03-04 01:04:02 -04:00
// start or update mission
if ( waiting_to_start ) {
// don't start the mission until we have an origin
Location loc ;
if ( copter . ahrs . get_origin ( loc ) ) {
// start/resume the mission (based on MIS_RESTART parameter)
mission . start_or_resume ( ) ;
waiting_to_start = false ;
2021-03-04 04:19:05 -04:00
// initialise mission change check (ignore results)
2022-01-07 21:25:10 -04:00
IGNORE_RETURN ( mis_change_detector . check_for_mission_change ( ) ) ;
2021-03-04 01:04:02 -04:00
}
} else {
2021-03-04 04:19:05 -04:00
// check for mission changes
2022-01-07 21:25:10 -04:00
if ( mis_change_detector . check_for_mission_change ( ) ) {
2021-03-04 04:19:05 -04:00
// if mission is running restart the current command if it is a waypoint or spline command
2022-01-07 21:25:10 -04:00
if ( ( mission . state ( ) = = AP_Mission : : MISSION_RUNNING ) & & ( _mode = = SubMode : : WP ) ) {
2021-03-04 04:19:05 -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-03-04 01:04:02 -04:00
mission . update ( ) ;
}
2014-01-24 22:37:42 -04:00
// call the correct auto controller
2016-03-21 00:45:50 -03:00
switch ( _mode ) {
2014-01-24 22:37:42 -04:00
2021-04-13 12:06:43 -03:00
case SubMode : : TAKEOFF :
2016-03-21 00:45:50 -03:00
takeoff_run ( ) ;
2014-01-24 22:37:42 -04:00
break ;
2021-04-13 12:06:43 -03:00
case SubMode : : WP :
case SubMode : : CIRCLE_MOVE_TO_EDGE :
2016-03-21 00:45:50 -03:00
wp_run ( ) ;
2014-01-24 22:37:42 -04:00
break ;
2021-04-13 12:06:43 -03:00
case SubMode : : LAND :
2016-03-21 00:45:50 -03:00
land_run ( ) ;
2014-01-24 22:37:42 -04:00
break ;
2014-01-27 10:43:48 -04:00
2021-04-13 12:06:43 -03:00
case SubMode : : RTL :
2016-03-21 00:45:50 -03:00
rtl_run ( ) ;
2014-01-27 23:20:39 -04:00
break ;
2021-04-13 12:06:43 -03:00
case SubMode : : CIRCLE :
2016-03-21 00:45:50 -03:00
circle_run ( ) ;
2014-01-27 10:43:48 -04:00
break ;
2014-03-22 00:48:54 -03:00
2021-04-13 12:06:43 -03:00
case SubMode : : NAVGUIDED :
2022-02-17 08:59:16 -04:00
case SubMode : : NAV_SCRIPT_TIME :
2024-09-04 00:48:37 -03:00
# if AC_NAV_GUIDED || AP_SCRIPTING_ENABLED
2016-03-21 00:45:50 -03:00
nav_guided_run ( ) ;
2014-05-23 02:29:08 -03:00
# endif
2014-10-16 09:30:07 -03:00
break ;
2014-10-12 05:06:51 -03:00
2021-04-13 12:06:43 -03:00
case SubMode : : LOITER :
2016-03-21 00:45:50 -03:00
loiter_run ( ) ;
2014-10-12 05:06:51 -03:00
break ;
2016-11-17 01:19:22 -04:00
2021-04-13 12:06:43 -03:00
case SubMode : : LOITER_TO_ALT :
2018-07-25 00:39:43 -03:00
loiter_to_alt_run ( ) ;
break ;
2023-10-28 03:06:45 -03:00
# if AP_MISSION_NAV_PAYLOAD_PLACE_ENABLED && AC_PAYLOAD_PLACE_ENABLED
2021-04-13 12:06:43 -03:00
case SubMode : : NAV_PAYLOAD_PLACE :
2023-09-27 22:24:36 -03:00
payload_place . run ( ) ;
2016-11-17 01:19:22 -04:00
break ;
2023-10-18 23:34:30 -03:00
# endif
2022-05-25 02:20:27 -03:00
case SubMode : : NAV_ATTITUDE_TIME :
nav_attitude_time_run ( ) ;
break ;
2014-01-24 22:37:42 -04:00
}
2021-07-24 20:25:18 -03:00
// only pretend to be in auto RTL so long as mission still thinks its in a landing sequence or the mission has completed
2024-03-02 20:12:23 -04:00
const bool auto_rtl_active = mission . get_in_landing_sequence_flag ( ) | | mission . get_in_return_path_flag ( ) | | mission . state ( ) = = AP_Mission : : mission_state : : MISSION_COMPLETE ;
if ( auto_RTL & & ! auto_rtl_active ) {
2021-07-24 20:25:18 -03:00
auto_RTL = false ;
2021-08-31 11:48:24 -03:00
// log exit from Auto RTL
2023-07-13 21:58:09 -03:00
# if HAL_LOGGING_ENABLED
2021-08-31 11:48:24 -03:00
copter . logger . Write_Mode ( ( uint8_t ) copter . flightmode - > mode_number ( ) , ModeReason : : AUTO_RTL_EXIT ) ;
2023-07-13 21:58:09 -03:00
# endif
2021-07-24 20:25:18 -03:00
}
2014-01-24 22:37:42 -04:00
}
2022-05-25 09:26:00 -03:00
// return true if a position estimate is required
bool ModeAuto : : requires_GPS ( ) const
{
// position estimate is required in all sub modes except attitude control
return _mode ! = SubMode : : NAV_ATTITUDE_TIME ;
}
// set submode. This may re-trigger the vehicle's EKF failsafe if the new submode requires a position estimate
void ModeAuto : : set_submode ( SubMode new_submode )
{
// return immediately if the submode has not been changed
if ( new_submode = = _mode ) {
return ;
}
// backup old mode
SubMode old_submode = _mode ;
// set mode
_mode = new_submode ;
// if changing out of the nav-attitude-time submode, recheck the EKF failsafe
// this may trigger a flight mode change if the EKF failsafe is active
if ( old_submode = = SubMode : : NAV_ATTITUDE_TIME ) {
copter . failsafe_ekf_recheck ( ) ;
}
}
2024-07-16 21:33:25 -03:00
bool ModeAuto : : option_is_enabled ( Option option ) const
{
return ( ( copter . g2 . auto_options & ( uint32_t ) option ) ! = 0 ) ;
}
2020-12-31 20:49:01 -04:00
bool ModeAuto : : allows_arming ( AP_Arming : : Method method ) const
2020-10-14 02:27:10 -03:00
{
2024-07-16 21:33:25 -03:00
if ( auto_RTL ) {
return false ;
}
return option_is_enabled ( Option : : AllowArming ) ;
}
2020-10-14 02:27:10 -03:00
2024-09-04 00:48:37 -03:00
# if WEATHERVANE_ENABLED
2022-04-14 06:58:27 -03:00
bool ModeAuto : : allows_weathervaning ( ) const
{
2024-07-16 21:33:25 -03:00
return option_is_enabled ( Option : : AllowWeatherVaning ) ;
2022-04-14 06:58:27 -03:00
}
# endif
2021-07-24 20:25:18 -03:00
// Go straight to landing sequence via DO_LAND_START, if succeeds pretend to be Auto RTL mode
bool ModeAuto : : jump_to_landing_sequence_auto_RTL ( ModeReason reason )
{
2024-03-02 20:12:23 -04:00
if ( ! mission . jump_to_landing_sequence ( get_stopping_point ( ) ) ) {
LOGGER_WRITE_ERROR ( LogErrorSubsystem : : FLIGHT_MODE , LogErrorCode ( Number : : AUTO_RTL ) ) ;
// make sad noise
if ( copter . ap . initialised ) {
AP_Notify : : events . user_mode_change_failed = 1 ;
}
gcs ( ) . send_text ( MAV_SEVERITY_WARNING , " Mode change to AUTO RTL failed: No landing sequence found " ) ;
return false ;
}
return enter_auto_rtl ( reason ) ;
}
// Join mission after DO_RETURN_PATH_START waypoint, if succeeds pretend to be Auto RTL mode
bool ModeAuto : : return_path_start_auto_RTL ( ModeReason reason )
{
if ( ! mission . jump_to_closest_mission_leg ( get_stopping_point ( ) ) ) {
LOGGER_WRITE_ERROR ( LogErrorSubsystem : : FLIGHT_MODE , LogErrorCode ( Number : : AUTO_RTL ) ) ;
// make sad noise
if ( copter . ap . initialised ) {
AP_Notify : : events . user_mode_change_failed = 1 ;
}
gcs ( ) . send_text ( MAV_SEVERITY_WARNING , " Mode change to AUTO RTL failed: No return path found " ) ;
return false ;
}
return enter_auto_rtl ( reason ) ;
}
// Try join return path else do land start
bool ModeAuto : : return_path_or_jump_to_landing_sequence_auto_RTL ( ModeReason reason )
{
const Location stopping_point = get_stopping_point ( ) ;
if ( ! mission . jump_to_closest_mission_leg ( stopping_point ) & & ! mission . jump_to_landing_sequence ( stopping_point ) ) {
LOGGER_WRITE_ERROR ( LogErrorSubsystem : : FLIGHT_MODE , LogErrorCode ( Number : : AUTO_RTL ) ) ;
// make sad noise
if ( copter . ap . initialised ) {
AP_Notify : : events . user_mode_change_failed = 1 ;
}
gcs ( ) . send_text ( MAV_SEVERITY_WARNING , " Mode change to AUTO RTL failed: No return path or landing sequence found " ) ;
return false ;
}
return enter_auto_rtl ( reason ) ;
}
// Enter auto rtl pseudo mode
bool ModeAuto : : enter_auto_rtl ( ModeReason reason )
{
mission . set_force_resume ( true ) ;
// if not already in auto switch to auto
if ( ( copter . flightmode = = this ) | | set_mode ( Mode : : Number : : AUTO , reason ) ) {
auto_RTL = true ;
2023-07-13 21:58:09 -03:00
# if HAL_LOGGING_ENABLED
2024-03-02 20:12:23 -04:00
// log entry into AUTO RTL
copter . logger . Write_Mode ( ( uint8_t ) copter . flightmode - > mode_number ( ) , reason ) ;
2023-07-13 21:58:09 -03:00
# endif
2021-08-31 11:48:24 -03:00
2024-03-02 20:12:23 -04:00
// make happy noise
if ( copter . ap . initialised ) {
AP_Notify : : events . user_mode_change = 1 ;
2021-07-24 20:25:18 -03:00
}
2024-03-02 20:12:23 -04:00
return true ;
2021-08-31 11:48:24 -03:00
}
2024-03-02 20:12:23 -04:00
// mode change failed, revert force resume flag
mission . set_force_resume ( false ) ;
2023-07-13 21:58:09 -03:00
LOGGER_WRITE_ERROR ( LogErrorSubsystem : : FLIGHT_MODE , LogErrorCode ( Number : : AUTO_RTL ) ) ;
2021-08-31 11:48:24 -03:00
// make sad noise
if ( copter . ap . initialised ) {
AP_Notify : : events . user_mode_change_failed = 1 ;
2021-07-24 20:25:18 -03:00
}
return false ;
}
2022-02-17 08:59:16 -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-17 08:59:16 -04:00
{
# if AP_SCRIPTING_ENABLED
if ( _mode = = SubMode : : NAV_SCRIPT_TIME ) {
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-17 08:59:16 -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
if ( ( _mode = = SubMode : : NAV_SCRIPT_TIME ) & & ( id = = nav_scripting . id ) ) {
nav_scripting . done = true ;
}
# endif
}
2018-03-22 10:25:18 -03:00
// auto_loiter_start - initialises loitering in auto mode
// returns success/failure because this can be called by exit_mission
2019-05-09 23:18:49 -03:00
bool ModeAuto : : loiter_start ( )
2018-03-22 10:25:18 -03:00
{
// return failure if GPS is bad
if ( ! copter . position_ok ( ) ) {
return false ;
}
2021-04-13 12:06:43 -03:00
_mode = SubMode : : LOITER ;
2018-03-22 10:25:18 -03:00
// calculate stopping point
Vector3f stopping_point ;
wp_nav - > get_wp_stopping_point ( stopping_point ) ;
// initialise waypoint controller target to stopping point
wp_nav - > set_wp_destination ( stopping_point ) ;
// hold yaw at current heading
2022-09-24 11:12:33 -03:00
auto_yaw . set_mode ( AutoYaw : : Mode : : HOLD ) ;
2018-03-22 10:25:18 -03:00
return true ;
}
// auto_rtl_start - initialises RTL in AUTO flight mode
2019-05-09 23:18:49 -03:00
void ModeAuto : : rtl_start ( )
2018-03-22 10:25:18 -03:00
{
// call regular rtl flight mode initialisation and ask it to ignore checks
2022-03-16 00:55:13 -03:00
if ( copter . mode_rtl . init ( true ) ) {
2022-05-25 09:26:00 -03:00
set_submode ( SubMode : : RTL ) ;
2022-03-16 00:55:13 -03:00
} else {
// this should never happen because RTL never fails init if argument is true
INTERNAL_ERROR ( AP_InternalError : : error_t : : flow_of_control ) ;
}
2018-03-22 10:25:18 -03:00
}
2022-05-26 01:13:45 -03:00
// initialise waypoint controller to implement take-off
2019-05-09 23:18:49 -03:00
void ModeAuto : : takeoff_start ( const Location & dest_loc )
2014-01-24 22:37:42 -04:00
{
2019-06-12 23:11:12 -03:00
if ( ! copter . current_loc . initialised ( ) ) {
2022-03-16 00:55:13 -03:00
// this should never happen because mission commands are not executed until
// the AHRS/EKF origin is set by which time current_loc should also have been set
INTERNAL_ERROR ( AP_InternalError : : error_t : : flow_of_control ) ;
2019-06-12 23:11:12 -03:00
return ;
}
2022-02-10 23:05:43 -04:00
// calculate current and target altitudes
// by default current_alt_cm and alt_target_cm are alt-above-EKF-origin
int32_t alt_target_cm ;
bool alt_target_terrain = false ;
float current_alt_cm = inertial_nav . get_position_z_up_cm ( ) ;
float terrain_offset ; // terrain's altitude in cm above the ekf origin
if ( ( dest_loc . get_alt_frame ( ) = = Location : : AltFrame : : ABOVE_TERRAIN ) & & wp_nav - > get_terrain_offset ( terrain_offset ) ) {
// subtract terrain offset to convert vehicle's alt-above-ekf-origin to alt-above-terrain
current_alt_cm - = terrain_offset ;
2015-10-05 05:23:58 -03:00
2022-02-10 23:05:43 -04:00
// specify alt_target_cm as alt-above-terrain
alt_target_cm = dest_loc . alt ;
alt_target_terrain = true ;
} else {
// set horizontal target
Location dest ( dest_loc ) ;
dest . lat = copter . current_loc . lat ;
dest . lng = copter . current_loc . lng ;
// get altitude target above EKF origin
if ( ! dest . get_alt_cm ( Location : : AltFrame : : ABOVE_ORIGIN , alt_target_cm ) ) {
// this failure could only happen if take-off alt was specified as an alt-above terrain and we have no terrain data
2023-07-13 21:58:09 -03:00
LOGGER_WRITE_ERROR ( LogErrorSubsystem : : TERRAIN , LogErrorCode : : MISSING_TERRAIN_DATA ) ;
2022-02-10 23:05:43 -04:00
// fall back to altitude above current altitude
alt_target_cm = current_alt_cm + dest . alt ;
}
2015-10-05 05:23:58 -03:00
}
// sanity check target
2022-02-10 23:05:43 -04:00
int32_t alt_target_min_cm = current_alt_cm + ( copter . ap . land_complete ? 100 : 0 ) ;
alt_target_cm = MAX ( alt_target_cm , alt_target_min_cm ) ;
2014-01-24 22:37:42 -04:00
// initialise yaw
2022-09-24 11:12:33 -03:00
auto_yaw . set_mode ( AutoYaw : : Mode : : HOLD ) ;
2014-02-03 09:04:35 -04:00
2015-07-01 22:37:12 -03:00
// clear i term when we're taking off
2022-08-24 09:02:44 -03:00
pos_control - > init_z_controller ( ) ;
2016-06-04 23:37:55 -03:00
2022-02-10 23:05:43 -04:00
// initialise alt for WP_NAVALT_MIN and set completion alt
2023-09-28 02:05:51 -03:00
auto_takeoff . start ( alt_target_cm , alt_target_terrain ) ;
2022-05-25 09:26:00 -03:00
// set submode
set_submode ( SubMode : : TAKEOFF ) ;
2014-01-24 22:37:42 -04:00
}
2015-08-16 16:10:23 -03:00
// auto_wp_start - initialises waypoint controller to implement flying to a particular destination
2022-12-23 03:34:20 -04:00
bool ModeAuto : : wp_start ( const Location & dest_loc )
2015-08-16 16:10:23 -03:00
{
2022-02-10 23:05:43 -04:00
// init wpnav and set origin if transitioning from takeoff
if ( ! wp_nav - > is_active ( ) ) {
Vector3f stopping_point ;
if ( _mode = = SubMode : : TAKEOFF ) {
Vector3p takeoff_complete_pos ;
2024-09-10 09:12:31 -03:00
if ( auto_takeoff . get_completion_pos ( takeoff_complete_pos ) ) {
2022-02-10 23:05:43 -04:00
stopping_point = takeoff_complete_pos . tofloat ( ) ;
}
}
2023-11-28 07:36:08 -04:00
float des_speed_xy_cm = is_positive ( desired_speed_override . xy ) ? ( desired_speed_override . xy * 100 ) : 0 ;
wp_nav - > wp_and_spline_init ( des_speed_xy_cm , stopping_point ) ;
// override speeds up and down if necessary
if ( is_positive ( desired_speed_override . up ) ) {
wp_nav - > set_speed_up ( desired_speed_override . up * 100.0 ) ;
}
if ( is_positive ( desired_speed_override . down ) ) {
wp_nav - > set_speed_down ( desired_speed_override . down * 100.0 ) ;
}
2022-02-10 23:05:43 -04:00
}
2021-01-19 22:50:48 -04:00
if ( ! wp_nav - > set_wp_destination_loc ( dest_loc ) ) {
2022-12-23 03:34:20 -04:00
return false ;
2015-08-16 16:10:23 -03: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
2024-09-26 02:24:53 -03:00
if ( auto_yaw . mode ( ) ! = AutoYaw : : Mode : : ROI & & ! ( auto_yaw . mode ( ) = = AutoYaw : : Mode : : FIXED & & copter . g . wp_yaw_behavior = = WP_YAW_BEHAVIOR_NONE ) ) {
2017-12-25 23:55:42 -04:00
auto_yaw . set_mode_to_default ( false ) ;
2015-08-16 16:10:23 -03:00
}
2022-05-25 09:26:00 -03:00
// set submode
set_submode ( SubMode : : WP ) ;
2022-12-23 03:34:20 -04:00
return true ;
2015-08-16 16:10:23 -03:00
}
2014-01-24 22:37:42 -04:00
// auto_land_start - initialises controller to implement a landing
2019-05-09 23:18:49 -03:00
void ModeAuto : : land_start ( )
2014-01-24 22:37:42 -04:00
{
2022-02-22 09:23:00 -04:00
// set horizontal speed and acceleration limits
pos_control - > set_max_speed_accel_xy ( wp_nav - > get_default_speed_xy ( ) , wp_nav - > get_wp_acceleration ( ) ) ;
pos_control - > set_correction_speed_accel_xy ( wp_nav - > get_default_speed_xy ( ) , wp_nav - > get_wp_acceleration ( ) ) ;
2014-01-24 22:37:42 -04:00
2022-02-22 09:23:00 -04:00
// initialise the vertical position controller
if ( ! pos_control - > is_active_xy ( ) ) {
pos_control - > init_xy_controller ( ) ;
}
2014-01-24 22:37:42 -04:00
2022-02-22 09:23:00 -04:00
// set vertical speed and acceleration limits
pos_control - > set_max_speed_accel_z ( wp_nav - > get_default_speed_down ( ) , wp_nav - > get_default_speed_up ( ) , wp_nav - > get_accel_z ( ) ) ;
pos_control - > set_correction_speed_accel_z ( wp_nav - > get_default_speed_down ( ) , wp_nav - > get_default_speed_up ( ) , wp_nav - > get_accel_z ( ) ) ;
2014-01-25 00:40:32 -04:00
2021-05-19 11:07:38 -03:00
// initialise the vertical position controller
2017-01-09 03:31:26 -04:00
if ( ! pos_control - > is_active_z ( ) ) {
2021-05-11 01:42:02 -03:00
pos_control - > init_z_controller ( ) ;
2016-10-14 09:28:32 -03:00
}
2014-01-24 22:37:42 -04:00
// initialise yaw
2022-09-24 11:12:33 -03:00
auto_yaw . set_mode ( AutoYaw : : Mode : : HOLD ) ;
2020-02-20 23:08:26 -04:00
2022-10-01 07:21:38 -03:00
# if AP_LANDINGGEAR_ENABLED
2020-02-20 23:08:26 -04:00
// optionally deploy landing gear
copter . landinggear . deploy_for_landing ( ) ;
2021-02-06 23:29:33 -04:00
# endif
2021-01-06 11:19:23 -04:00
2021-09-05 17:07:57 -03:00
// reset flag indicating if pilot has applied roll or pitch inputs during landing
copter . ap . land_repo_active = false ;
// this will be set true if prec land is later active
copter . ap . prec_land_active = false ;
2022-05-25 09:26:00 -03:00
// set submode
set_submode ( SubMode : : LAND ) ;
2014-01-24 22:37:42 -04:00
}
2024-09-11 08:21:19 -03:00
// circle_movetoedge_start - initialise waypoint controller to move to edge of a circle with it's center at the specified location
2014-04-16 04:23:24 -03:00
// we assume the caller has performed all required GPS_ok checks
2023-02-14 18:17:31 -04:00
void ModeAuto : : circle_movetoedge_start ( const Location & circle_center , float radius_m , bool ccw_turn )
2014-04-16 04:23:24 -03:00
{
2020-04-08 03:21:13 -03:00
// set circle center
copter . circle_nav - > set_center ( circle_center ) ;
2014-04-16 04:23:24 -03:00
2016-03-09 07:21:08 -04:00
// set circle radius
if ( ! is_zero ( radius_m ) ) {
2022-02-06 12:35:17 -04:00
copter . circle_nav - > set_radius_cm ( radius_m * 100.0f ) ;
2016-03-09 07:21:08 -04:00
}
2014-04-16 04:23:24 -03:00
2023-02-14 18:17:31 -04:00
// set circle direction by using rate
float current_rate = copter . circle_nav - > get_rate ( ) ;
current_rate = ccw_turn ? - fabsf ( current_rate ) : fabsf ( current_rate ) ;
copter . circle_nav - > set_rate ( current_rate ) ;
2016-03-09 07:21:08 -04:00
// check our distance from edge of circle
Vector3f circle_edge_neu ;
2024-09-11 08:24:34 -03:00
float dist_to_edge ;
copter . circle_nav - > get_closest_point_on_circle ( circle_edge_neu , dist_to_edge ) ;
2016-03-09 07:21:08 -04:00
// if more than 3m then fly to edge
if ( dist_to_edge > 300.0f ) {
2019-01-01 22:54:31 -04:00
// convert circle_edge_neu to Location
2021-03-17 18:17:14 -03:00
Location circle_edge ( circle_edge_neu , Location : : AltFrame : : ABOVE_ORIGIN ) ;
2016-03-09 07:21:08 -04:00
// convert altitude to same as command
2016-04-28 07:53:45 -03:00
circle_edge . set_alt_cm ( circle_center . alt , circle_center . get_alt_frame ( ) ) ;
2016-03-09 07:21:08 -04:00
// initialise wpnav to move to edge of circle
2021-01-19 22:50:48 -04:00
if ( ! wp_nav - > set_wp_destination_loc ( circle_edge ) ) {
2016-04-22 08:45:28 -03:00
// failure to set destination can only be because of missing terrain data
2018-02-07 22:21:09 -04:00
copter . failsafe_terrain_on_event ( ) ;
2016-03-09 07:21:08 -04:00
}
2014-04-16 04:23:24 -03:00
2016-03-09 07:21:08 -04:00
// if we are outside the circle, point at the edge, otherwise hold yaw
2021-10-20 05:29:57 -03:00
const float dist_to_center = get_horizontal_distance_cm ( inertial_nav . get_position_xy_cm ( ) . topostype ( ) , copter . circle_nav - > get_center ( ) . xy ( ) ) ;
2017-01-24 14:37:00 -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
2022-09-24 11:12:33 -03:00
if ( auto_yaw . mode ( ) ! = AutoYaw : : Mode : : ROI ) {
2017-01-24 14:37:00 -04:00
if ( dist_to_center > copter . circle_nav - > get_radius ( ) & & dist_to_center > 500 ) {
auto_yaw . set_mode_to_default ( false ) ;
} else {
// vehicle is within circle so hold yaw to avoid spinning as we move to edge of circle
2022-09-24 11:12:33 -03:00
auto_yaw . set_mode ( AutoYaw : : Mode : : HOLD ) ;
2017-01-24 14:37:00 -04:00
}
2016-03-09 07:21:08 -04:00
}
2022-05-25 09:26:00 -03:00
// set the submode to move to the edge of the circle
set_submode ( SubMode : : CIRCLE_MOVE_TO_EDGE ) ;
2014-04-16 04:23:24 -03:00
} else {
2016-03-21 00:45:50 -03:00
circle_start ( ) ;
2014-04-16 04:23:24 -03:00
}
}
2014-01-27 10:43:48 -04:00
// auto_circle_start - initialises controller to fly a circle in AUTO flight mode
2016-03-09 07:21:08 -04:00
// assumes that circle_nav object has already been initialised with circle center and radius
2019-05-09 23:18:49 -03:00
void ModeAuto : : circle_start ( )
2014-01-27 10:43:48 -04:00
{
2014-04-16 04:23:24 -03:00
// initialise circle controller
2023-02-14 18:17:31 -04:00
copter . circle_nav - > init ( copter . circle_nav - > get_center ( ) , copter . circle_nav - > center_is_terrain_alt ( ) , copter . circle_nav - > get_rate ( ) ) ;
2020-04-09 07:41:06 -03:00
2022-09-24 11:12:33 -03:00
if ( auto_yaw . mode ( ) ! = AutoYaw : : Mode : : ROI ) {
auto_yaw . set_mode ( AutoYaw : : Mode : : CIRCLE ) ;
2020-04-09 07:41:06 -03:00
}
2022-05-25 09:26:00 -03:00
// set submode to circle
set_submode ( SubMode : : CIRCLE ) ;
2014-01-27 10:43:48 -04:00
}
2024-09-04 00:48:37 -03:00
# if AC_NAV_GUIDED
2018-03-22 10:25:18 -03:00
// auto_nav_guided_start - hand over control to external navigation controller in AUTO mode
2019-05-09 23:18:49 -03:00
void ModeAuto : : nav_guided_start ( )
2018-03-22 10:25:18 -03:00
{
// call regular guided flight mode initialisation
2022-03-16 00:55:13 -03:00
if ( ! copter . mode_guided . init ( true ) ) {
// this should never happen because guided mode never fails to init
INTERNAL_ERROR ( AP_InternalError : : error_t : : flow_of_control ) ;
return ;
}
2018-03-22 10:25:18 -03:00
// initialise guided start time and position as reference for limit checking
copter . mode_guided . limit_init_time_and_pos ( ) ;
2022-05-25 09:26:00 -03:00
// set submode
set_submode ( SubMode : : NAVGUIDED ) ;
2018-03-22 10:25:18 -03:00
}
2023-08-02 19:34:05 -03:00
# endif //AC_NAV_GUIDED
2018-03-22 10:25:18 -03:00
2019-05-09 23:18:49 -03:00
bool ModeAuto : : is_landing ( ) const
2018-04-30 06:50:04 -03:00
{
switch ( _mode ) {
2021-04-13 12:06:43 -03:00
case SubMode : : LAND :
2018-04-30 06:50:04 -03:00
return true ;
2021-04-13 12:06:43 -03:00
case SubMode : : RTL :
2018-04-30 06:50:04 -03:00
return copter . mode_rtl . is_landing ( ) ;
default :
return false ;
}
return false ;
}
2019-05-09 23:18:49 -03:00
bool ModeAuto : : is_taking_off ( ) const
2018-04-30 06:50:04 -03:00
{
2023-09-28 02:05:51 -03:00
return ( ( _mode = = SubMode : : TAKEOFF ) & & ! auto_takeoff . complete ) ;
2018-04-30 06:50:04 -03:00
}
2023-10-18 23:34:30 -03:00
# if AC_PAYLOAD_PLACE_ENABLED
2018-03-22 10:25:18 -03:00
// auto_payload_place_start - initialises controller to implement a placing
2023-09-27 22:24:36 -03:00
void PayloadPlace : : start_descent ( )
2018-03-22 10:25:18 -03:00
{
2023-09-27 22:24:36 -03:00
auto * pos_control = copter . pos_control ;
auto * wp_nav = copter . wp_nav ;
2022-02-22 09:23:00 -04:00
// set horizontal speed and acceleration limits
pos_control - > set_max_speed_accel_xy ( wp_nav - > get_default_speed_xy ( ) , wp_nav - > get_wp_acceleration ( ) ) ;
pos_control - > set_correction_speed_accel_xy ( wp_nav - > get_default_speed_xy ( ) , wp_nav - > get_wp_acceleration ( ) ) ;
// initialise the vertical position controller
if ( ! pos_control - > is_active_xy ( ) ) {
pos_control - > init_xy_controller ( ) ;
}
// set vertical speed and acceleration limits
pos_control - > set_max_speed_accel_z ( wp_nav - > get_default_speed_down ( ) , wp_nav - > get_default_speed_up ( ) , wp_nav - > get_accel_z ( ) ) ;
pos_control - > set_correction_speed_accel_z ( wp_nav - > get_default_speed_down ( ) , wp_nav - > get_default_speed_up ( ) , wp_nav - > get_accel_z ( ) ) ;
// initialise the vertical position controller
if ( ! pos_control - > is_active_z ( ) ) {
pos_control - > init_z_controller ( ) ;
}
2018-03-22 10:25:18 -03:00
2022-02-22 09:23:00 -04:00
// initialise yaw
2023-09-27 22:24:36 -03:00
copter . flightmode - > auto_yaw . set_mode ( Mode : : AutoYaw : : Mode : : HOLD ) ;
2022-12-30 22:11:31 -04:00
2023-09-27 22:24:36 -03:00
state = PayloadPlace : : State : : Descent_Start ;
2018-03-22 10:25:18 -03:00
}
2023-10-18 23:34:30 -03:00
# endif
2018-03-22 10:25:18 -03:00
2020-11-12 20:15:53 -04:00
// returns true if pilot's yaw input should be used to adjust vehicle's heading
bool ModeAuto : : use_pilot_yaw ( void ) const
{
2024-07-16 21:33:25 -03:00
const bool allow_yaw_option = ! option_is_enabled ( Option : : IgnorePilotYaw ) ;
2022-10-06 21:38:52 -03:00
const bool rtl_allow_yaw = ( _mode = = SubMode : : RTL ) & & copter . mode_rtl . use_pilot_yaw ( ) ;
const bool landing = _mode = = SubMode : : LAND ;
return allow_yaw_option | | rtl_allow_yaw | | landing ;
2020-11-12 20:15:53 -04:00
}
2022-07-27 06:20:29 -03:00
bool ModeAuto : : set_speed_xy ( float speed_xy_cms )
{
copter . wp_nav - > set_speed_xy ( speed_xy_cms ) ;
2023-11-28 07:36:08 -04:00
desired_speed_override . xy = speed_xy_cms * 0.01 ;
2022-07-27 06:20:29 -03:00
return true ;
}
bool ModeAuto : : set_speed_up ( float speed_up_cms )
{
copter . wp_nav - > set_speed_up ( speed_up_cms ) ;
2023-11-28 07:36:08 -04:00
desired_speed_override . up = speed_up_cms * 0.01 ;
2022-07-27 06:20:29 -03:00
return true ;
}
bool ModeAuto : : set_speed_down ( float speed_down_cms )
{
copter . wp_nav - > set_speed_down ( speed_down_cms ) ;
2023-11-28 07:36:08 -04:00
desired_speed_override . down = speed_down_cms * 0.01 ;
2022-07-27 06:20:29 -03:00
return true ;
}
2018-03-22 10:25:18 -03:00
// start_command - this function will be called when the ap_mission lib wishes to start a new command
2019-05-09 23:18:49 -03:00
bool ModeAuto : : start_command ( const AP_Mission : : Mission_Command & cmd )
2018-03-22 10:25:18 -03:00
{
switch ( cmd . id ) {
///
/// navigation commands
///
2022-05-16 19:10:29 -03:00
case MAV_CMD_NAV_VTOL_TAKEOFF :
2018-03-22 10:25:18 -03:00
case MAV_CMD_NAV_TAKEOFF : // 22
do_takeoff ( cmd ) ;
break ;
case MAV_CMD_NAV_WAYPOINT : // 16 Navigate to Waypoint
do_nav_wp ( cmd ) ;
break ;
2022-05-16 19:10:29 -03:00
case MAV_CMD_NAV_VTOL_LAND :
2018-03-22 10:25:18 -03:00
case MAV_CMD_NAV_LAND : // 21 LAND to Waypoint
do_land ( cmd ) ;
break ;
case MAV_CMD_NAV_LOITER_UNLIM : // 17 Loiter indefinitely
do_loiter_unlimited ( cmd ) ;
break ;
case MAV_CMD_NAV_LOITER_TURNS : //18 Loiter N Times
do_circle ( cmd ) ;
break ;
case MAV_CMD_NAV_LOITER_TIME : // 19
do_loiter_time ( cmd ) ;
break ;
2018-07-25 00:39:43 -03:00
case MAV_CMD_NAV_LOITER_TO_ALT :
do_loiter_to_alt ( cmd ) ;
break ;
2018-03-22 10:25:18 -03:00
case MAV_CMD_NAV_RETURN_TO_LAUNCH : //20
do_RTL ( ) ;
break ;
case MAV_CMD_NAV_SPLINE_WAYPOINT : // 82 Navigate to Waypoint using spline
do_spline_wp ( cmd ) ;
break ;
2024-09-04 00:48:37 -03:00
# if AC_NAV_GUIDED
2018-03-22 10:25:18 -03:00
case MAV_CMD_NAV_GUIDED_ENABLE : // 92 accept navigation commands from external nav computer
do_nav_guided_enable ( cmd ) ;
break ;
# endif
2019-03-08 01:40:41 -04:00
case MAV_CMD_NAV_DELAY : // 93 Delay the next navigation command
2018-03-22 10:25:18 -03:00
do_nav_delay ( cmd ) ;
break ;
2023-10-28 03:06:45 -03:00
# if AP_MISSION_NAV_PAYLOAD_PLACE_ENABLED && AC_PAYLOAD_PLACE_ENABLED
2019-03-08 01:40:41 -04:00
case MAV_CMD_NAV_PAYLOAD_PLACE : // 94 place at Waypoint
do_payload_place ( cmd ) ;
break ;
2023-10-18 23:34:30 -03:00
# endif
2019-03-08 01:40:41 -04:00
2022-02-17 08:59:16 -04:00
# if AP_SCRIPTING_ENABLED
case MAV_CMD_NAV_SCRIPT_TIME :
do_nav_script_time ( cmd ) ;
break ;
# endif
2022-05-25 02:20:27 -03:00
case MAV_CMD_NAV_ATTITUDE_TIME :
do_nav_attitude_time ( cmd ) ;
break ;
2018-03-22 10:25:18 -03:00
//
// conditional commands
//
case MAV_CMD_CONDITION_DELAY : // 112
do_wait_delay ( cmd ) ;
break ;
case MAV_CMD_CONDITION_DISTANCE : // 114
do_within_distance ( cmd ) ;
break ;
case MAV_CMD_CONDITION_YAW : // 115
do_yaw ( cmd ) ;
break ;
///
/// do commands
///
case MAV_CMD_DO_CHANGE_SPEED : // 178
do_change_speed ( cmd ) ;
break ;
case MAV_CMD_DO_SET_HOME : // 179
do_set_home ( cmd ) ;
break ;
case MAV_CMD_DO_SET_ROI : // 201
// point the copter and camera at a region of interest (ROI)
do_roi ( cmd ) ;
break ;
2024-09-21 06:47:10 -03:00
# if HAL_MOUNT_ENABLED
2018-03-22 10:25:18 -03:00
case MAV_CMD_DO_MOUNT_CONTROL : // 205
// point the camera to a specified angle
do_mount_control ( cmd ) ;
break ;
2024-09-21 06:47:10 -03:00
# endif
2018-03-22 10:25:18 -03:00
2024-09-04 00:48:37 -03:00
# if AC_NAV_GUIDED
2018-03-22 10:25:18 -03:00
case MAV_CMD_DO_GUIDED_LIMITS : // 220 accept guided mode limits
do_guided_limits ( cmd ) ;
break ;
# endif
2023-03-03 00:13:14 -04:00
# if AP_WINCH_ENABLED
2018-03-22 10:25:18 -03:00
case MAV_CMD_DO_WINCH : // Mission command to control winch
do_winch ( cmd ) ;
break ;
# endif
2024-03-02 20:12:23 -04:00
case MAV_CMD_DO_RETURN_PATH_START :
2021-07-24 20:25:18 -03:00
case MAV_CMD_DO_LAND_START :
break ;
2018-03-22 10:25:18 -03:00
default :
2018-08-22 17:55:32 -03:00
// unable to use the command, allow the vehicle to try the next command
return false ;
2018-03-22 10:25:18 -03:00
}
// always return success
return true ;
}
// exit_mission - function that is called once the mission completes
2019-05-09 23:18:49 -03:00
void ModeAuto : : exit_mission ( )
2018-03-22 10:25:18 -03:00
{
// play a tone
AP_Notify : : events . mission_complete = 1 ;
// if we are not on the ground switch to loiter or land
2019-05-09 23:18:49 -03:00
if ( ! copter . ap . land_complete ) {
2018-03-22 10:25:18 -03:00
// try to enter loiter but if that fails land
2018-06-04 00:42:43 -03:00
if ( ! loiter_start ( ) ) {
2019-10-17 00:49:22 -03:00
set_mode ( Mode : : Number : : LAND , ModeReason : : MISSION_END ) ;
2018-03-22 10:25:18 -03:00
}
2018-06-04 00:42:43 -03:00
} else {
2018-03-22 10:25:18 -03:00
// if we've landed it's safe to disarm
2020-02-21 09:09:57 -04:00
copter . arming . disarm ( AP_Arming : : Method : : MISSIONEXIT ) ;
2018-03-22 10:25:18 -03:00
}
}
// do_guided - start guided mode
2019-05-09 23:18:49 -03:00
bool ModeAuto : : do_guided ( const AP_Mission : : Mission_Command & cmd )
2018-03-22 10:25:18 -03:00
{
// only process guided waypoint if we are in guided mode
2024-09-15 12:21:52 -03:00
if ( ! copter . flightmode - > in_guided_mode ( ) ) {
2018-03-22 10:25:18 -03:00
return false ;
}
// switch to handle different commands
switch ( cmd . id ) {
case MAV_CMD_NAV_WAYPOINT :
{
// set wp_nav's destination
2019-01-01 22:54:31 -04:00
Location dest ( cmd . content . location ) ;
2018-03-22 10:25:18 -03:00
return copter . mode_guided . set_destination ( dest ) ;
}
case MAV_CMD_CONDITION_YAW :
do_yaw ( cmd ) ;
return true ;
default :
// reject unrecognised command
return false ;
}
return true ;
}
2019-05-09 23:18:49 -03:00
uint32_t ModeAuto : : wp_distance ( ) const
2018-03-22 10:25:18 -03:00
{
2019-04-24 23:48:39 -03:00
switch ( _mode ) {
2021-04-13 12:06:43 -03:00
case SubMode : : CIRCLE :
2019-04-24 23:48:39 -03:00
return copter . circle_nav - > get_distance_to_target ( ) ;
2021-04-13 12:06:43 -03:00
case SubMode : : WP :
case SubMode : : CIRCLE_MOVE_TO_EDGE :
2019-04-24 23:48:39 -03:00
default :
return wp_nav - > get_wp_distance_to_destination ( ) ;
}
2018-03-22 10:25:18 -03:00
}
2019-05-09 23:18:49 -03:00
int32_t ModeAuto : : wp_bearing ( ) const
2018-03-22 10:25:18 -03:00
{
2019-04-24 23:48:39 -03:00
switch ( _mode ) {
2021-04-13 12:06:43 -03:00
case SubMode : : CIRCLE :
2019-04-24 23:48:39 -03:00
return copter . circle_nav - > get_bearing_to_target ( ) ;
2021-04-13 12:06:43 -03:00
case SubMode : : WP :
case SubMode : : CIRCLE_MOVE_TO_EDGE :
2019-04-24 23:48:39 -03:00
default :
return wp_nav - > get_wp_bearing_to_destination ( ) ;
}
2018-03-22 10:25:18 -03:00
}
2021-07-06 18:02:26 -03:00
bool ModeAuto : : get_wp ( Location & destination ) const
2018-05-11 08:59:05 -03:00
{
switch ( _mode ) {
2021-04-13 12:06:43 -03:00
case SubMode : : NAVGUIDED :
2018-05-11 08:59:05 -03:00
return copter . mode_guided . get_wp ( destination ) ;
2021-04-13 12:06:43 -03:00
case SubMode : : WP :
2019-06-05 07:47:32 -03:00
return wp_nav - > get_oa_wp_destination ( destination ) ;
2021-04-13 12:06:43 -03:00
case SubMode : : RTL :
2019-06-05 07:47:32 -03:00
return copter . mode_rtl . get_wp ( destination ) ;
2018-05-11 08:59:05 -03:00
default :
return false ;
}
}
2018-03-22 10:25:18 -03:00
/*******************************************************************************
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
* * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * */
2018-04-24 20:31:01 -03:00
// verify_command - 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
2019-05-09 23:18:49 -03:00
bool ModeAuto : : verify_command ( const AP_Mission : : Mission_Command & cmd )
2018-03-22 10:25:18 -03:00
{
2018-04-24 20:31:01 -03:00
if ( copter . flightmode ! = & copter . mode_auto ) {
return false ;
}
bool cmd_complete = false ;
2018-06-04 00:42:43 -03:00
switch ( cmd . id ) {
2018-03-22 10:25:18 -03:00
//
// navigation commands
//
2022-05-16 19:10:29 -03:00
case MAV_CMD_NAV_VTOL_TAKEOFF :
2018-03-22 10:25:18 -03:00
case MAV_CMD_NAV_TAKEOFF :
2018-04-24 20:31:01 -03:00
cmd_complete = verify_takeoff ( ) ;
break ;
2018-03-22 10:25:18 -03:00
case MAV_CMD_NAV_WAYPOINT :
2018-04-24 20:31:01 -03:00
cmd_complete = verify_nav_wp ( cmd ) ;
break ;
2018-03-22 10:25:18 -03:00
2022-05-16 19:10:29 -03:00
case MAV_CMD_NAV_VTOL_LAND :
2018-03-22 10:25:18 -03:00
case MAV_CMD_NAV_LAND :
2018-04-24 20:31:01 -03:00
cmd_complete = verify_land ( ) ;
break ;
2018-03-22 10:25:18 -03:00
2023-10-28 03:06:45 -03:00
# if AP_MISSION_NAV_PAYLOAD_PLACE_ENABLED && AC_PAYLOAD_PLACE_ENABLED
2018-03-22 10:25:18 -03:00
case MAV_CMD_NAV_PAYLOAD_PLACE :
2023-09-27 22:24:36 -03:00
cmd_complete = payload_place . verify ( ) ;
2018-04-24 20:31:01 -03:00
break ;
2023-10-18 23:34:30 -03:00
# endif
2018-03-22 10:25:18 -03:00
case MAV_CMD_NAV_LOITER_UNLIM :
2018-04-24 20:31:01 -03:00
cmd_complete = verify_loiter_unlimited ( ) ;
break ;
2018-03-22 10:25:18 -03:00
case MAV_CMD_NAV_LOITER_TURNS :
2018-04-24 20:31:01 -03:00
cmd_complete = verify_circle ( cmd ) ;
break ;
2018-03-22 10:25:18 -03:00
case MAV_CMD_NAV_LOITER_TIME :
2019-02-25 16:38:38 -04:00
cmd_complete = verify_loiter_time ( cmd ) ;
2018-04-24 20:31:01 -03:00
break ;
2018-03-22 10:25:18 -03:00
2018-07-25 00:39:43 -03:00
case MAV_CMD_NAV_LOITER_TO_ALT :
return verify_loiter_to_alt ( ) ;
2018-03-22 10:25:18 -03:00
case MAV_CMD_NAV_RETURN_TO_LAUNCH :
2018-04-24 20:31:01 -03:00
cmd_complete = verify_RTL ( ) ;
break ;
2018-03-22 10:25:18 -03:00
case MAV_CMD_NAV_SPLINE_WAYPOINT :
2018-04-24 20:31:01 -03:00
cmd_complete = verify_spline_wp ( cmd ) ;
break ;
2018-03-22 10:25:18 -03:00
2024-09-04 00:48:37 -03:00
# if AC_NAV_GUIDED
2018-03-22 10:25:18 -03:00
case MAV_CMD_NAV_GUIDED_ENABLE :
2018-04-24 20:31:01 -03:00
cmd_complete = verify_nav_guided_enable ( cmd ) ;
break ;
2018-03-22 10:25:18 -03:00
# endif
case MAV_CMD_NAV_DELAY :
2018-04-24 20:31:01 -03:00
cmd_complete = verify_nav_delay ( cmd ) ;
break ;
2018-03-22 10:25:18 -03:00
2022-02-17 08:59:16 -04:00
# if AP_SCRIPTING_ENABLED
case MAV_CMD_NAV_SCRIPT_TIME :
cmd_complete = verify_nav_script_time ( ) ;
break ;
# endif
2022-05-25 02:20:27 -03:00
case MAV_CMD_NAV_ATTITUDE_TIME :
cmd_complete = verify_nav_attitude_time ( cmd ) ;
break ;
2018-03-22 10:25:18 -03:00
///
/// conditional commands
///
case MAV_CMD_CONDITION_DELAY :
2018-04-24 20:31:01 -03:00
cmd_complete = verify_wait_delay ( ) ;
break ;
2018-03-22 10:25:18 -03:00
case MAV_CMD_CONDITION_DISTANCE :
2018-04-24 20:31:01 -03:00
cmd_complete = verify_within_distance ( ) ;
break ;
2018-03-22 10:25:18 -03:00
case MAV_CMD_CONDITION_YAW :
2018-04-24 20:31:01 -03:00
cmd_complete = verify_yaw ( ) ;
break ;
2018-03-22 10:25:18 -03:00
// do commands (always return true)
case MAV_CMD_DO_CHANGE_SPEED :
case MAV_CMD_DO_SET_HOME :
case MAV_CMD_DO_SET_ROI :
2024-09-21 06:47:10 -03:00
# if HAL_MOUNT_ENABLED
2018-03-22 10:25:18 -03:00
case MAV_CMD_DO_MOUNT_CONTROL :
2024-09-21 06:47:10 -03:00
# endif
# if AC_NAV_GUIDED
2018-03-22 10:25:18 -03:00
case MAV_CMD_DO_GUIDED_LIMITS :
2024-09-21 06:47:10 -03:00
# endif
# if AP_FENCE_ENABLED
2018-03-22 10:25:18 -03:00
case MAV_CMD_DO_FENCE_ENABLE :
2024-09-21 06:47:10 -03:00
# endif
# if AP_WINCH_ENABLED
2018-03-22 10:25:18 -03:00
case MAV_CMD_DO_WINCH :
2024-09-21 06:47:10 -03:00
# endif
2024-03-02 20:12:23 -04:00
case MAV_CMD_DO_RETURN_PATH_START :
2021-07-24 20:25:18 -03:00
case MAV_CMD_DO_LAND_START :
2018-04-24 20:31:01 -03:00
cmd_complete = true ;
break ;
2018-03-22 10:25:18 -03:00
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
2018-04-24 20:31:01 -03:00
cmd_complete = true ;
break ;
2018-03-22 10:25:18 -03:00
}
2018-04-24 20:31:01 -03:00
// send message to GCS
if ( cmd_complete ) {
gcs ( ) . send_mission_item_reached_message ( cmd . index ) ;
}
return cmd_complete ;
2018-03-22 10:25:18 -03:00
}
2020-07-09 09:00:20 -03:00
// takeoff_run - takeoff in auto mode
2018-03-22 10:25:18 -03:00
// called by auto_run at 100hz or more
2019-05-09 23:18:49 -03:00
void ModeAuto : : takeoff_run ( )
2018-03-22 10:25:18 -03:00
{
2020-09-24 20:42:34 -03:00
// if the user doesn't want to raise the throttle we can set it automatically
// note that this can defeat the disarm check on takeoff
2024-07-16 21:33:25 -03:00
if ( option_is_enabled ( Option : : AllowTakeOffWithoutRaisingThrottle ) ) {
2020-09-24 20:42:34 -03:00
copter . set_auto_armed ( true ) ;
}
2023-09-28 02:05:51 -03:00
auto_takeoff . run ( ) ;
2018-03-22 10:25:18 -03:00
}
// auto_wp_run - runs the auto waypoint controller
// called by auto_run at 100hz or more
2019-05-09 23:18:49 -03:00
void ModeAuto : : wp_run ( )
2018-03-22 10:25:18 -03:00
{
2019-02-28 05:03:23 -04:00
// if not armed set throttle to zero and exit immediately
2019-04-08 05:15:57 -03:00
if ( is_disarmed_or_landed ( ) ) {
2020-10-13 20:19:42 -03:00
make_safe_ground_handling ( ) ;
2019-02-28 05:03:23 -04:00
return ;
}
2018-03-22 10:25:18 -03:00
// set motors to full range
2019-04-09 09:16:58 -03:00
motors - > set_desired_spool_state ( AP_Motors : : DesiredSpoolState : : THROTTLE_UNLIMITED ) ;
2018-03-22 10:25:18 -03:00
// run waypoint controller
copter . failsafe_terrain_set_status ( wp_nav - > update_wpnav ( ) ) ;
2021-05-19 11:07:38 -03:00
// WP_Nav has set the vertical position control targets
// run the vertical position controller and set output throttle
2018-03-22 10:25:18 -03:00
pos_control - > update_z_controller ( ) ;
2022-09-24 11:12:33 -03:00
// call attitude controller with auto yaw
attitude_control - > input_thrust_vector_heading ( pos_control - > get_thrust_vector ( ) , auto_yaw . get_heading ( ) ) ;
2018-03-22 10:25:18 -03:00
}
// auto_land_run - lands in auto mode
// called by auto_run at 100hz or more
2019-05-09 23:18:49 -03:00
void ModeAuto : : land_run ( )
2018-03-22 10:25:18 -03:00
{
2019-02-28 05:03:23 -04:00
// if not armed set throttle to zero and exit immediately
2019-04-08 05:15:57 -03:00
if ( is_disarmed_or_landed ( ) ) {
2020-10-13 20:19:42 -03:00
make_safe_ground_handling ( ) ;
2018-03-22 10:25:18 -03:00
return ;
}
// set motors to full range
2019-04-09 09:16:58 -03:00
motors - > set_desired_spool_state ( AP_Motors : : DesiredSpoolState : : THROTTLE_UNLIMITED ) ;
2021-07-21 16:33:37 -03:00
2021-08-23 06:00:09 -03:00
// run normal landing or precision landing (if enabled)
2021-08-25 02:53:56 -03:00
land_run_normal_or_precland ( ) ;
2018-03-22 10:25:18 -03:00
}
// auto_rtl_run - rtl in AUTO flight mode
// called by auto_run at 100hz or more
2019-05-09 23:18:49 -03:00
void ModeAuto : : rtl_run ( )
2018-03-22 10:25:18 -03:00
{
// call regular rtl flight mode run function
copter . mode_rtl . run ( false ) ;
}
// auto_circle_run - circle in AUTO flight mode
// called by auto_run at 100hz or more
2019-05-09 23:18:49 -03:00
void ModeAuto : : circle_run ( )
2018-03-22 10:25:18 -03:00
{
2014-01-27 10:43:48 -04:00
// call circle controller
2020-04-08 03:21:13 -03:00
copter . failsafe_terrain_set_status ( copter . circle_nav - > update ( ) ) ;
2014-01-27 10:43:48 -04:00
2021-05-19 11:07:38 -03:00
// WP_Nav has set the vertical position control targets
// run the vertical position controller and set output throttle
2018-03-22 10:25:18 -03:00
pos_control - > update_z_controller ( ) ;
2022-09-24 11:12:33 -03:00
// call attitude controller with auto yaw
attitude_control - > input_thrust_vector_heading ( pos_control - > get_thrust_vector ( ) , auto_yaw . get_heading ( ) ) ;
2018-03-22 10:25:18 -03:00
}
2024-09-04 00:48:37 -03:00
# if AC_NAV_GUIDED || AP_SCRIPTING_ENABLED
2018-03-22 10:25:18 -03:00
// auto_nav_guided_run - allows control by external navigation controller
// called by auto_run at 100hz or more
2019-05-09 23:18:49 -03:00
void ModeAuto : : nav_guided_run ( )
2018-03-22 10:25:18 -03:00
{
// call regular guided flight mode run function
copter . mode_guided . run ( ) ;
}
2023-08-02 19:34:05 -03:00
# endif // AC_NAV_GUIDED || AP_SCRIPTING_ENABLED
2018-03-22 10:25:18 -03:00
// auto_loiter_run - loiter in AUTO flight mode
// called by auto_run at 100hz or more
2019-05-09 23:18:49 -03:00
void ModeAuto : : loiter_run ( )
2018-03-22 10:25:18 -03:00
{
2019-02-28 05:03:23 -04:00
// if not armed set throttle to zero and exit immediately
2019-04-08 05:15:57 -03:00
if ( is_disarmed_or_landed ( ) ) {
2020-10-13 20:19:42 -03:00
make_safe_ground_handling ( ) ;
2018-03-22 10:25:18 -03:00
return ;
}
// set motors to full range
2019-04-09 09:16:58 -03:00
motors - > set_desired_spool_state ( AP_Motors : : DesiredSpoolState : : THROTTLE_UNLIMITED ) ;
2018-03-22 10:25:18 -03:00
// run waypoint and z-axis position controller
copter . failsafe_terrain_set_status ( wp_nav - > update_wpnav ( ) ) ;
pos_control - > update_z_controller ( ) ;
2022-09-24 11:12:33 -03:00
// call attitude controller with auto yaw
attitude_control - > input_thrust_vector_heading ( pos_control - > get_thrust_vector ( ) , auto_yaw . get_heading ( ) ) ;
2018-03-22 10:25:18 -03:00
}
2018-07-25 00:39:43 -03:00
// auto_loiter_run - loiter to altitude in AUTO flight mode
// called by auto_run at 100hz or more
2019-05-09 23:18:49 -03:00
void ModeAuto : : loiter_to_alt_run ( )
2018-07-25 00:39:43 -03:00
{
// if not auto armed or motor interlock not enabled set throttle to zero and exit immediately
2019-04-08 05:15:57 -03:00
if ( is_disarmed_or_landed ( ) | | ! motors - > get_interlock ( ) ) {
2022-05-13 21:38:49 -03:00
make_safe_ground_handling ( ) ;
2018-07-25 00:39:43 -03:00
return ;
}
// possibly just run the waypoint controller:
if ( ! loiter_to_alt . reached_destination_xy ) {
loiter_to_alt . reached_destination_xy = wp_nav - > reached_wp_destination_xy ( ) ;
if ( ! loiter_to_alt . reached_destination_xy ) {
wp_run ( ) ;
return ;
}
}
if ( ! loiter_to_alt . loiter_start_done ) {
2022-02-22 09:23:00 -04:00
// set horizontal speed and acceleration limits
pos_control - > set_max_speed_accel_xy ( wp_nav - > get_default_speed_xy ( ) , wp_nav - > get_wp_acceleration ( ) ) ;
pos_control - > set_correction_speed_accel_xy ( wp_nav - > get_default_speed_xy ( ) , wp_nav - > get_wp_acceleration ( ) ) ;
if ( ! pos_control - > is_active_xy ( ) ) {
pos_control - > init_xy_controller ( ) ;
}
2018-07-25 00:39:43 -03:00
loiter_to_alt . loiter_start_done = true ;
}
const float alt_error_cm = copter . current_loc . alt - loiter_to_alt . alt ;
if ( fabsf ( alt_error_cm ) < 5.0 ) { // random numbers R US
loiter_to_alt . reached_alt = true ;
} else if ( alt_error_cm * loiter_to_alt . alt_error_cm < 0 ) {
// we were above and are now below, or vice-versa
loiter_to_alt . reached_alt = true ;
}
loiter_to_alt . alt_error_cm = alt_error_cm ;
// loiter...
land_run_horizontal_control ( ) ;
// Compute a vertical velocity demand such that the vehicle
// approaches the desired altitude.
2020-12-15 08:48:30 -04:00
float target_climb_rate = sqrt_controller (
2018-07-25 00:39:43 -03:00
- alt_error_cm ,
pos_control - > get_pos_z_p ( ) . kP ( ) ,
2021-05-11 01:42:02 -03:00
pos_control - > get_max_accel_z_cmss ( ) ,
2018-07-25 00:39:43 -03:00
G_Dt ) ;
2021-12-22 06:24:26 -04:00
target_climb_rate = constrain_float ( target_climb_rate , pos_control - > get_max_speed_down_cms ( ) , pos_control - > get_max_speed_up_cms ( ) ) ;
2018-07-25 00:39:43 -03:00
// get avoidance adjusted climb rate
target_climb_rate = get_avoidance_adjusted_climbrate ( target_climb_rate ) ;
2023-11-07 18:23:41 -04:00
# if AP_RANGEFINDER_ENABLED
2021-08-31 01:17:59 -03:00
// update the vertical offset based on the surface measurement
copter . surface_tracking . update_surface_offset ( ) ;
2023-11-07 18:23:41 -04:00
# endif
2021-08-31 01:17:59 -03:00
// Send the commanded climb rate to the position controller
pos_control - > set_pos_target_z_from_climb_rate_cm ( target_climb_rate ) ;
2018-07-25 00:39:43 -03:00
pos_control - > update_z_controller ( ) ;
}
2022-05-25 02:20:27 -03:00
// maintain an attitude for a specified time
void ModeAuto : : nav_attitude_time_run ( )
{
// if not auto armed or motor interlock not enabled set throttle to zero and exit immediately
if ( is_disarmed_or_landed ( ) | | ! motors - > get_interlock ( ) ) {
make_safe_ground_handling ( ) ;
return ;
}
// constrain climb rate
float target_climb_rate_cms = constrain_float ( nav_attitude_time . climb_rate * 100.0 , pos_control - > get_max_speed_down_cms ( ) , pos_control - > get_max_speed_up_cms ( ) ) ;
// get avoidance adjusted climb rate
target_climb_rate_cms = get_avoidance_adjusted_climbrate ( target_climb_rate_cms ) ;
// limit and scale lean angles
const float angle_limit_cd = MAX ( 1000.0f , MIN ( copter . aparm . angle_max , attitude_control - > get_althold_lean_angle_max_cd ( ) ) ) ;
Vector2f target_rp_cd ( nav_attitude_time . roll_deg * 100 , nav_attitude_time . pitch_deg * 100 ) ;
target_rp_cd . limit_length ( angle_limit_cd ) ;
// send targets to attitude controller
attitude_control - > input_euler_angle_roll_pitch_yaw ( target_rp_cd . x , target_rp_cd . y , nav_attitude_time . yaw_deg * 100 , true ) ;
// Send the commanded climb rate to the position controller
pos_control - > set_pos_target_z_from_climb_rate_cm ( target_climb_rate_cms ) ;
pos_control - > update_z_controller ( ) ;
}
2023-10-18 23:34:30 -03:00
# if AC_PAYLOAD_PLACE_ENABLED
2018-03-22 10:25:18 -03:00
// auto_payload_place_run - places an object in auto mode
// called by auto_run at 100hz or more
2023-09-27 22:24:36 -03:00
void PayloadPlace : : run ( )
2018-03-22 10:25:18 -03:00
{
2022-12-30 22:11:31 -04:00
const char * prefix_str = " PayloadPlace: " ;
2023-10-04 21:50:51 -03:00
if ( copter . flightmode - > is_disarmed_or_landed ( ) ) {
copter . flightmode - > make_safe_ground_handling ( ) ;
2018-03-22 10:25:18 -03:00
return ;
}
// set motors to full range
2023-09-27 22:24:36 -03:00
copter . motors - > set_desired_spool_state ( AP_Motors : : DesiredSpoolState : : THROTTLE_UNLIMITED ) ;
2018-03-22 10:25:18 -03:00
2022-12-30 22:11:31 -04:00
const uint32_t descent_thrust_cal_duration_ms = 2000 ; // milliseconds
const uint32_t placed_check_duration_ms = 500 ; // how long we have to be below a throttle threshold before considering placed
2024-07-15 05:12:57 -03:00
auto & g2 = copter . g2 ;
const auto & g = copter . g ;
2023-09-27 22:24:36 -03:00
auto * attitude_control = copter . attitude_control ;
2024-07-15 05:12:57 -03:00
const auto & pos_control = copter . pos_control ;
const auto & wp_nav = copter . wp_nav ;
// Vertical thrust is taken from the attitude controller before angle boost is added
2022-12-30 22:11:31 -04:00
const float thrust_level = attitude_control - > get_throttle_in ( ) ;
const uint32_t now_ms = AP_HAL : : millis ( ) ;
2024-07-15 05:12:57 -03:00
// relax position target if we might be landed
2022-12-30 22:11:31 -04:00
// if we discover we've landed then immediately release the load:
if ( copter . ap . land_complete | | copter . ap . land_complete_maybe ) {
2024-07-15 05:12:57 -03:00
pos_control - > soften_for_landing_xy ( ) ;
2023-09-27 22:24:36 -03:00
switch ( state ) {
case State : : FlyToLocation :
2022-12-30 22:11:31 -04:00
// this is handled in wp_run()
break ;
2023-09-27 22:24:36 -03:00
case State : : Descent_Start :
2022-12-30 22:11:31 -04:00
// do nothing on this loop
break ;
2023-09-27 22:24:36 -03:00
case State : : Descent :
2022-12-30 22:11:31 -04:00
gcs ( ) . send_text ( MAV_SEVERITY_INFO , " %s landed " , prefix_str ) ;
2023-09-27 22:24:36 -03:00
state = State : : Release ;
2022-12-30 22:11:31 -04:00
break ;
2023-09-27 22:24:36 -03:00
case State : : Release :
case State : : Releasing :
case State : : Delay :
case State : : Ascent_Start :
case State : : Ascent :
case State : : Done :
2022-12-30 22:11:31 -04:00
break ;
}
}
2024-09-04 00:48:37 -03:00
# if AP_GRIPPER_ENABLED
2022-12-30 22:11:31 -04:00
// if pilot releases load manually:
2024-02-21 02:40:35 -04:00
if ( AP : : gripper ( ) . valid ( ) & & AP : : gripper ( ) . released ( ) ) {
2023-09-27 22:24:36 -03:00
switch ( state ) {
case State : : FlyToLocation :
case State : : Descent_Start :
2024-07-15 05:12:57 -03:00
gcs ( ) . send_text ( MAV_SEVERITY_INFO , " %s Abort: Gripper Open " , prefix_str ) ;
// Descent_Start has not run so we must also initalise descent_start_altitude_cm
2024-10-02 03:49:45 -03:00
descent_start_altitude_cm = pos_control - > get_pos_desired_z_cm ( ) ;
2023-09-27 22:24:36 -03:00
state = State : : Done ;
2022-12-30 22:11:31 -04:00
break ;
2023-09-27 22:24:36 -03:00
case State : : Descent :
2022-12-30 22:11:31 -04:00
gcs ( ) . send_text ( MAV_SEVERITY_INFO , " %s Manual release " , prefix_str ) ;
2023-09-27 22:24:36 -03:00
state = State : : Release ;
2022-12-30 22:11:31 -04:00
break ;
2023-09-27 22:24:36 -03:00
case State : : Release :
case State : : Releasing :
case State : : Delay :
case State : : Ascent_Start :
case State : : Ascent :
case State : : Done :
2022-12-30 22:11:31 -04:00
break ;
}
}
# endif
2023-09-27 22:24:36 -03:00
switch ( state ) {
case State : : FlyToLocation :
2022-12-30 22:11:31 -04:00
if ( copter . wp_nav - > reached_wp_destination ( ) ) {
2023-09-27 22:24:36 -03:00
start_descent ( ) ;
2022-12-30 22:11:31 -04:00
}
break ;
2023-09-27 22:24:36 -03:00
case State : : Descent_Start :
descent_established_time_ms = now_ms ;
2024-10-02 03:49:45 -03:00
descent_start_altitude_cm = pos_control - > get_pos_desired_z_cm ( ) ;
2022-12-30 22:11:31 -04:00
// limiting the decent rate to the limit set in wp_nav is not necessary but done for safety
2023-09-27 22:24:36 -03:00
descent_speed_cms = MIN ( ( is_positive ( g2 . pldp_descent_speed_ms ) ) ? g2 . pldp_descent_speed_ms * 100.0 : abs ( g . land_speed ) , wp_nav - > get_default_speed_down ( ) ) ;
descent_thrust_level = 1.0 ;
state = State : : Descent ;
2022-12-30 22:11:31 -04:00
FALLTHROUGH ;
2023-09-27 22:24:36 -03:00
case State : : Descent :
2022-12-30 22:11:31 -04:00
// check maximum decent distance
2023-09-27 22:24:36 -03:00
if ( ! is_zero ( descent_max_cm ) & &
2024-10-02 03:49:45 -03:00
descent_start_altitude_cm - pos_control - > get_pos_desired_z_cm ( ) > descent_max_cm ) {
2023-09-27 22:24:36 -03:00
state = State : : Ascent_Start ;
2022-12-30 22:11:31 -04:00
gcs ( ) . send_text ( MAV_SEVERITY_WARNING , " %s Reached maximum descent " , prefix_str ) ;
break ;
}
// calibrate the decent thrust after aircraft has reached constant decent rate and release if threshold is reached
2023-09-27 22:24:36 -03:00
if ( pos_control - > get_vel_desired_cms ( ) . z > - 0.95 * descent_speed_cms ) {
2022-12-30 22:11:31 -04:00
// decent rate has not reached descent_speed_cms
2023-09-27 22:24:36 -03:00
descent_established_time_ms = now_ms ;
2022-12-30 22:11:31 -04:00
break ;
2023-09-27 22:24:36 -03:00
} else if ( now_ms - descent_established_time_ms < descent_thrust_cal_duration_ms ) {
2022-12-30 22:11:31 -04:00
// record minimum thrust for descent_thrust_cal_duration_ms
2023-09-27 22:24:36 -03:00
descent_thrust_level = MIN ( descent_thrust_level , thrust_level ) ;
place_start_time_ms = now_ms ;
2022-12-30 22:11:31 -04:00
break ;
2023-09-27 22:24:36 -03:00
} else if ( thrust_level > g2 . pldp_thrust_placed_fraction * descent_thrust_level ) {
2022-12-30 22:11:31 -04:00
// thrust is above minimum threshold
2023-09-27 22:24:36 -03:00
place_start_time_ms = now_ms ;
2022-12-30 22:11:31 -04:00
break ;
2024-03-05 00:11:52 -04:00
} else if ( is_positive ( g2 . pldp_range_finder_maximum_m ) ) {
2022-12-30 22:11:31 -04:00
if ( ! copter . rangefinder_state . enabled ) {
// abort payload place because rangefinder is not enabled
2023-09-27 22:24:36 -03:00
state = State : : Ascent_Start ;
2024-03-05 00:11:52 -04:00
gcs ( ) . send_text ( MAV_SEVERITY_WARNING , " %s PLDP_RNG_MAX set and rangefinder not enabled " , prefix_str ) ;
2022-12-30 22:11:31 -04:00
break ;
2024-03-05 00:11:52 -04:00
} else if ( copter . rangefinder_alt_ok ( ) & & ( copter . rangefinder_state . glitch_count = = 0 ) & & ( copter . rangefinder_state . alt_cm > g2 . pldp_range_finder_maximum_m * 100.0 ) ) {
// range finder altitude is above maximum
2023-09-27 22:24:36 -03:00
place_start_time_ms = now_ms ;
2022-12-30 22:11:31 -04:00
break ;
}
}
// If we get here:
// 1. we have reached decent velocity
// 2. measured the thrust level required for decent
// 3. detected that our thrust requirements have reduced
// 4. rangefinder range has dropped below minimum if set
// 5. place_start_time_ms has been initialised
// payload touchdown must be detected for 0.5 seconds
2023-09-27 22:24:36 -03:00
if ( now_ms - place_start_time_ms > placed_check_duration_ms ) {
state = State : : Release ;
gcs ( ) . send_text ( MAV_SEVERITY_INFO , " %s payload release thrust threshold: %f " , prefix_str , static_cast < double > ( g2 . pldp_thrust_placed_fraction * descent_thrust_level ) ) ;
2022-12-30 22:11:31 -04:00
}
break ;
2023-09-27 22:24:36 -03:00
case State : : Release :
2022-12-30 22:11:31 -04:00
// Reinitialise vertical position controller to remove discontinuity due to touch down of payload
pos_control - > init_z_controller_no_descent ( ) ;
2024-09-04 00:48:37 -03:00
# if AP_GRIPPER_ENABLED
2024-02-21 02:40:35 -04:00
if ( AP : : gripper ( ) . valid ( ) ) {
2022-12-30 22:11:31 -04:00
gcs ( ) . send_text ( MAV_SEVERITY_INFO , " %s Releasing the gripper " , prefix_str ) ;
2024-02-21 02:40:35 -04:00
AP : : gripper ( ) . release ( ) ;
2023-09-27 22:24:36 -03:00
state = State : : Releasing ;
2022-12-30 22:11:31 -04:00
} else {
2023-09-27 22:24:36 -03:00
state = State : : Delay ;
2022-12-30 22:11:31 -04:00
}
# else
2023-09-27 22:24:36 -03:00
state = State : : Delay ;
2022-12-30 22:11:31 -04:00
# endif
break ;
2023-09-27 22:24:36 -03:00
case State : : Releasing :
2024-02-21 02:40:35 -04:00
# if AP_GRIPPER_ENABLED
if ( AP : : gripper ( ) . valid ( ) & & ! AP : : gripper ( ) . released ( ) ) {
2022-12-30 22:11:31 -04:00
break ;
}
# endif
2023-09-27 22:24:36 -03:00
state = State : : Delay ;
2022-12-30 22:11:31 -04:00
FALLTHROUGH ;
2023-09-27 22:24:36 -03:00
case State : : Delay :
2022-12-30 22:11:31 -04:00
// If we get here we have finished releasing the gripper
2023-09-27 22:24:36 -03:00
if ( now_ms - place_start_time_ms < placed_check_duration_ms + g2 . pldp_delay_s * 1000.0 ) {
2022-12-30 22:11:31 -04:00
break ;
}
FALLTHROUGH ;
2023-09-27 22:24:36 -03:00
case State : : Ascent_Start :
state = State : : Ascent ;
2023-10-04 22:45:16 -03:00
FALLTHROUGH ;
2022-12-30 22:11:31 -04:00
2023-10-04 22:45:16 -03:00
case State : : Ascent : {
// Ascent complete when we are less than 10% of the stopping
// distance from the target altitude stopping distance from
// vel_threshold_fraction * max velocity
const float vel_threshold_fraction = 0.1 ;
const float stop_distance = 0.5 * sq ( vel_threshold_fraction * copter . pos_control - > get_max_speed_up_cms ( ) ) / copter . pos_control - > get_max_accel_z_cmss ( ) ;
2024-10-02 03:49:45 -03:00
bool reached_altitude = pos_control - > get_pos_desired_z_cm ( ) > = descent_start_altitude_cm - stop_distance ;
2023-10-04 22:45:16 -03:00
if ( reached_altitude ) {
2023-09-27 22:24:36 -03:00
state = State : : Done ;
2022-12-30 22:11:31 -04:00
}
break ;
2023-10-04 22:45:16 -03:00
}
2023-09-27 22:24:36 -03:00
case State : : Done :
2022-12-30 22:11:31 -04:00
break ;
default :
// this should never happen
INTERNAL_ERROR ( AP_InternalError : : error_t : : flow_of_control ) ;
break ;
}
2023-09-27 22:24:36 -03:00
switch ( state ) {
case State : : FlyToLocation :
2022-12-30 22:11:31 -04:00
// this should never happen
2023-09-27 22:24:36 -03:00
return copter . mode_auto . wp_run ( ) ;
case State : : Descent_Start :
case State : : Descent :
2023-10-04 22:12:10 -03:00
copter . flightmode - > land_run_horizontal_control ( ) ;
// update altitude target and call position controller
pos_control - > land_at_climb_rate_cm ( - descent_speed_cms , true ) ;
2024-08-08 02:26:39 -03:00
break ;
2023-09-27 22:24:36 -03:00
case State : : Release :
case State : : Releasing :
case State : : Delay :
case State : : Ascent_Start :
2023-10-04 22:12:10 -03:00
copter . flightmode - > land_run_horizontal_control ( ) ;
// update altitude target and call position controller
pos_control - > land_at_climb_rate_cm ( 0.0 , false ) ;
2024-08-08 02:26:39 -03:00
break ;
2023-09-27 22:24:36 -03:00
case State : : Ascent :
case State : : Done :
2023-10-04 22:45:16 -03:00
float vel = 0.0 ;
copter . flightmode - > land_run_horizontal_control ( ) ;
pos_control - > input_pos_vel_accel_z ( descent_start_altitude_cm , vel , 0.0 ) ;
break ;
2018-03-22 10:25:18 -03:00
}
2024-08-08 02:26:39 -03:00
pos_control - > update_z_controller ( ) ;
2018-03-22 10:25:18 -03:00
}
2023-10-18 23:34:30 -03:00
# endif
2018-03-22 10:25:18 -03:00
2022-06-15 00:46:55 -03:00
// sets the target_loc's alt to the vehicle's current alt but does not change target_loc's frame
// in the case of terrain altitudes either the terrain database or the rangefinder may be used
// returns true on success, false on failure
bool ModeAuto : : shift_alt_to_current_alt ( Location & target_loc ) const
{
// if terrain alt using rangefinder is being used then set alt to current rangefinder altitude
if ( ( target_loc . get_alt_frame ( ) = = Location : : AltFrame : : ABOVE_TERRAIN ) & &
( wp_nav - > get_terrain_source ( ) = = AC_WPNav : : TerrainSource : : TERRAIN_FROM_RANGEFINDER ) ) {
int32_t curr_rngfnd_alt_cm ;
if ( copter . get_rangefinder_height_interpolated_cm ( curr_rngfnd_alt_cm ) ) {
2024-08-02 06:31:50 -03:00
// subtract position offset (if any)
curr_rngfnd_alt_cm - = pos_control - > get_pos_offset_z_cm ( ) ;
2022-06-15 00:46:55 -03:00
// wp_nav is using rangefinder so use current rangefinder alt
target_loc . set_alt_cm ( MAX ( curr_rngfnd_alt_cm , 200 ) , Location : : AltFrame : : ABOVE_TERRAIN ) ;
return true ;
}
return false ;
}
2018-03-22 10:25:18 -03:00
2022-06-15 00:46:55 -03:00
// take copy of current location and change frame to match target
Location currloc = copter . current_loc ;
if ( ! currloc . change_alt_frame ( target_loc . get_alt_frame ( ) ) ) {
// this could fail due missing terrain database alt
return false ;
2018-03-22 10:25:18 -03:00
}
2022-06-15 00:46:55 -03:00
2024-08-02 06:31:50 -03:00
// set target_loc's alt minus position offset (if any)
target_loc . set_alt_cm ( currloc . alt - pos_control - > get_pos_offset_z_cm ( ) , currloc . get_alt_frame ( ) ) ;
2022-06-15 00:46:55 -03:00
return true ;
2018-03-22 10:25:18 -03:00
}
2024-08-02 06:31:50 -03:00
// subtract position controller offsets from target location
// should be used when the location will be used as a target for the position controller
void ModeAuto : : subtract_pos_offsets ( Location & target_loc ) const
{
// subtract position controller offsets from target location
const Vector3p & pos_ofs_neu_cm = pos_control - > get_pos_offset_cm ( ) ;
Vector3p pos_ofs_ned_m = Vector3p { pos_ofs_neu_cm . x * 0.01 , pos_ofs_neu_cm . y * 0.01 , - pos_ofs_neu_cm . z * 0.01 } ;
target_loc . offset ( - pos_ofs_ned_m ) ;
}
2018-03-22 10:25:18 -03:00
/********************************************************************************/
2020-04-23 01:14:18 -03:00
// Nav (Must) commands
2018-03-22 10:25:18 -03:00
/********************************************************************************/
// do_takeoff - initiate takeoff navigation command
2019-05-09 23:18:49 -03:00
void ModeAuto : : do_takeoff ( const AP_Mission : : Mission_Command & cmd )
2018-03-22 10:25:18 -03:00
{
// Set wp navigation target to safe altitude above current position
takeoff_start ( cmd . content . location ) ;
}
2024-10-03 21:33:06 -03:00
// return the Location portion of a command. If the command's lat and lon and/or alt are zero the default_loc's lat,lon and/or alt are returned instead
2021-01-19 22:50:48 -04:00
Location ModeAuto : : loc_from_cmd ( const AP_Mission : : Mission_Command & cmd , const Location & default_loc ) const
2018-03-22 10:25:18 -03:00
{
2019-01-01 22:54:31 -04:00
Location ret ( cmd . content . location ) ;
2018-03-22 10:25:18 -03:00
// use current lat, lon if zero
2018-10-03 00:33:03 -03:00
if ( ret . lat = = 0 & & ret . lng = = 0 ) {
2021-01-19 22:50:48 -04:00
ret . lat = default_loc . lat ;
ret . lng = default_loc . lng ;
2018-03-22 10:25:18 -03:00
}
2021-03-04 04:19:05 -04:00
// use default altitude if not provided in cmd
2018-10-03 00:33:03 -03:00
if ( ret . alt = = 0 ) {
2021-01-19 22:50:48 -04:00
// set to default_loc's altitude but in command's alt frame
// note that this may use the terrain database
int32_t default_alt ;
if ( default_loc . get_alt_cm ( ret . get_alt_frame ( ) , default_alt ) ) {
ret . set_alt_cm ( default_alt , ret . get_alt_frame ( ) ) ;
2018-03-22 10:25:18 -03:00
} else {
2021-01-19 22:50:48 -04:00
// default to default_loc's altitude and frame
ret . set_alt_cm ( default_loc . alt , default_loc . get_alt_frame ( ) ) ;
2018-03-22 10:25:18 -03:00
}
}
2018-10-03 00:33:03 -03:00
return ret ;
}
// do_nav_wp - initiate move to next waypoint
2019-05-09 23:18:49 -03:00
void ModeAuto : : do_nav_wp ( const AP_Mission : : Mission_Command & cmd )
2018-10-03 00:33:03 -03:00
{
2021-01-19 22:50:48 -04:00
// calculate default location used when lat, lon or alt is zero
Location default_loc = copter . current_loc ;
2024-08-02 06:31:50 -03:00
// subtract position offsets
subtract_pos_offsets ( default_loc ) ;
2021-01-19 22:50:48 -04:00
if ( wp_nav - > is_active ( ) & & wp_nav - > reached_wp_destination ( ) ) {
if ( ! wp_nav - > get_wp_destination_loc ( default_loc ) ) {
// this should never happen
INTERNAL_ERROR ( AP_InternalError : : error_t : : flow_of_control ) ;
}
}
// get waypoint's location from command and send to wp_nav
2022-12-19 09:17:48 -04:00
const Location target_loc = loc_from_cmd ( cmd , default_loc ) ;
2022-12-23 03:34:20 -04:00
if ( ! wp_start ( target_loc ) ) {
// failure to set next destination can only be because of missing terrain data
copter . failsafe_terrain_on_event ( ) ;
return ;
}
2021-01-19 22:50:48 -04:00
2018-03-22 10:25:18 -03:00
// this will be used to remember the time in millis after we reach or pass the WP.
loiter_time = 0 ;
// this is the delay, stored in seconds
loiter_time_max = cmd . p1 ;
2021-01-19 22:50:48 -04:00
// set next destination if necessary
2022-12-19 09:17:48 -04:00
if ( ! set_next_wp ( cmd , target_loc ) ) {
2021-01-19 22:50:48 -04:00
// failure to set next destination can only be because of missing terrain data
copter . failsafe_terrain_on_event ( ) ;
return ;
}
}
// checks the next mission command and adds it as a destination if necessary
// supports both straight line and spline waypoints
// cmd should be the current command
// default_loc should be the destination from the current_cmd but corrected for cases where user set lat, lon or alt to zero
// returns true on success, false on failure which should only happen due to a failure to retrieve terrain data
bool ModeAuto : : set_next_wp ( const AP_Mission : : Mission_Command & current_cmd , const Location & default_loc )
{
// do not add next wp if current command has a delay meaning the vehicle will stop at the destination
if ( current_cmd . p1 > 0 ) {
return true ;
}
// do not add next wp if there are no more navigation commands
AP_Mission : : Mission_Command next_cmd ;
if ( ! mission . get_next_nav_cmd ( current_cmd . index + 1 , next_cmd ) ) {
return true ;
}
// whether vehicle should stop at the target position depends upon the next command
switch ( next_cmd . id ) {
case MAV_CMD_NAV_WAYPOINT :
case MAV_CMD_NAV_LOITER_UNLIM :
2023-10-18 23:34:30 -03:00
# if AP_MISSION_NAV_PAYLOAD_PLACE_ENABLED
2023-12-02 04:54:58 -04:00
case MAV_CMD_NAV_PAYLOAD_PLACE :
# endif
case MAV_CMD_NAV_LOITER_TIME : {
2021-01-19 22:50:48 -04:00
const Location dest_loc = loc_from_cmd ( current_cmd , default_loc ) ;
const Location next_dest_loc = loc_from_cmd ( next_cmd , dest_loc ) ;
return wp_nav - > set_wp_destination_next_loc ( next_dest_loc ) ;
}
case MAV_CMD_NAV_SPLINE_WAYPOINT : {
// get spline's location and next location from command and send to wp_nav
Location next_dest_loc , next_next_dest_loc ;
bool next_next_dest_loc_is_spline ;
get_spline_from_cmd ( next_cmd , default_loc , next_dest_loc , next_next_dest_loc , next_next_dest_loc_is_spline ) ;
return wp_nav - > set_spline_destination_next_loc ( next_dest_loc , next_next_dest_loc , next_next_dest_loc_is_spline ) ;
}
2022-05-16 19:10:29 -03:00
case MAV_CMD_NAV_VTOL_LAND :
2021-01-19 22:50:48 -04:00
case MAV_CMD_NAV_LAND :
// stop because we may change between rel,abs and terrain alt types
2021-04-11 05:42:52 -03:00
case MAV_CMD_NAV_LOITER_TURNS :
2021-01-19 22:50:48 -04:00
case MAV_CMD_NAV_RETURN_TO_LAUNCH :
2022-05-16 19:10:29 -03:00
case MAV_CMD_NAV_VTOL_TAKEOFF :
2021-01-19 22:50:48 -04:00
case MAV_CMD_NAV_TAKEOFF :
// always stop for RTL and takeoff commands
default :
// for unsupported commands it is safer to stop
break ;
2018-03-22 10:25:18 -03:00
}
2021-01-19 22:50:48 -04:00
return true ;
2018-03-22 10:25:18 -03:00
}
// do_land - initiate landing procedure
2019-05-09 23:18:49 -03:00
void ModeAuto : : do_land ( const AP_Mission : : Mission_Command & cmd )
2018-03-22 10:25:18 -03:00
{
// To-Do: check if we have already landed
// if location provided we fly to that location at current altitude
if ( cmd . content . location . lat ! = 0 | | cmd . content . location . lng ! = 0 ) {
// set state to fly to location
2019-12-01 19:25:32 -04:00
state = State : : FlyToLocation ;
2018-03-22 10:25:18 -03:00
2022-06-15 00:46:55 -03:00
// convert cmd to location class
Location target_loc ( cmd . content . location ) ;
if ( ! shift_alt_to_current_alt ( target_loc ) ) {
// this can only fail due to missing terrain database alt or rangefinder alt
// use current alt-above-home and report error
target_loc . set_alt_cm ( copter . current_loc . alt , Location : : AltFrame : : ABOVE_HOME ) ;
2023-07-13 21:58:09 -03:00
LOGGER_WRITE_ERROR ( LogErrorSubsystem : : TERRAIN , LogErrorCode : : MISSING_TERRAIN_DATA ) ;
2022-06-15 00:46:55 -03:00
gcs ( ) . send_text ( MAV_SEVERITY_CRITICAL , " Land: no terrain data, using alt-above-home " ) ;
}
2018-03-22 10:25:18 -03:00
2022-12-23 03:34:20 -04:00
if ( ! wp_start ( target_loc ) ) {
// failure to set next destination can only be because of missing terrain data
copter . failsafe_terrain_on_event ( ) ;
return ;
}
2018-06-04 00:42:43 -03:00
} else {
2018-03-22 10:25:18 -03:00
// set landing state
2019-12-01 19:25:32 -04:00
state = State : : Descending ;
2018-03-22 10:25:18 -03:00
// initialise landing controller
land_start ( ) ;
}
}
// do_loiter_unlimited - start loitering with no end conditions
// note: caller should set yaw_mode
2019-05-09 23:18:49 -03:00
void ModeAuto : : do_loiter_unlimited ( const AP_Mission : : Mission_Command & cmd )
2018-03-22 10:25:18 -03:00
{
2024-08-02 06:31:50 -03:00
// calculate default location used when lat, lon or alt is zero
Location default_loc = copter . current_loc ;
2018-03-22 10:25:18 -03:00
2024-08-02 06:31:50 -03:00
// subtract position offsets
subtract_pos_offsets ( default_loc ) ;
// use previous waypoint destination as default if available
if ( wp_nav - > is_active ( ) & & wp_nav - > reached_wp_destination ( ) ) {
if ( ! wp_nav - > get_wp_destination_loc ( default_loc ) ) {
// this should never happen
INTERNAL_ERROR ( AP_InternalError : : error_t : : flow_of_control ) ;
2018-03-22 10:25:18 -03:00
}
}
2024-08-02 06:31:50 -03:00
// get waypoint's location from command and send to wp_nav
const Location target_loc = loc_from_cmd ( cmd , default_loc ) ;
2018-03-22 10:25:18 -03:00
// start way point navigator and provide it the desired location
2022-12-23 03:34:20 -04:00
if ( ! wp_start ( target_loc ) ) {
// failure to set next destination can only be because of missing terrain data
copter . failsafe_terrain_on_event ( ) ;
return ;
}
2018-03-22 10:25:18 -03:00
}
// do_circle - initiate moving in a circle
2019-05-09 23:18:49 -03:00
void ModeAuto : : do_circle ( const AP_Mission : : Mission_Command & cmd )
2018-03-22 10:25:18 -03:00
{
2024-08-02 06:31:50 -03:00
// calculate default location used when lat, lon or alt is zero
Location default_loc = copter . current_loc ;
// subtract position offsets
subtract_pos_offsets ( default_loc ) ;
const Location circle_center = loc_from_cmd ( cmd , default_loc ) ;
2018-03-22 10:25:18 -03:00
// calculate radius
2022-05-11 00:56:06 -03:00
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 ;
}
2018-03-22 10:25:18 -03:00
2023-02-14 18:17:31 -04:00
// true if circle should be ccw
const bool circle_direction_ccw = cmd . content . location . loiter_ccw ;
2018-03-22 10:25:18 -03:00
// move to edge of circle (verify_circle) will ensure we begin circling once we reach the edge
2023-02-14 18:17:31 -04:00
circle_movetoedge_start ( circle_center , circle_radius_m , circle_direction_ccw ) ;
2018-03-22 10:25:18 -03:00
}
// do_loiter_time - initiate loitering at a point for a given time period
// note: caller should set yaw_mode
2019-05-09 23:18:49 -03:00
void ModeAuto : : do_loiter_time ( const AP_Mission : : Mission_Command & cmd )
2018-03-22 10:25:18 -03:00
{
// re-use loiter unlimited
do_loiter_unlimited ( cmd ) ;
// setup loiter timer
loiter_time = 0 ;
loiter_time_max = cmd . p1 ; // units are (seconds)
}
2018-07-25 00:39:43 -03:00
// do_loiter_alt - initiate loitering at a point until a given altitude is reached
// note: caller should set yaw_mode
2019-05-09 23:18:49 -03:00
void ModeAuto : : do_loiter_to_alt ( const AP_Mission : : Mission_Command & cmd )
2018-07-25 00:39:43 -03:00
{
// re-use loiter unlimited
do_loiter_unlimited ( cmd ) ;
// if we aren't navigating to a location then we have to adjust
// altitude for current location
2019-01-01 22:54:31 -04:00
Location target_loc ( cmd . content . location ) ;
2018-07-25 00:39:43 -03:00
if ( target_loc . lat = = 0 & & target_loc . lng = = 0 ) {
2019-01-01 22:54:31 -04:00
target_loc . lat = copter . current_loc . lat ;
target_loc . lng = copter . current_loc . lng ;
2018-07-25 00:39:43 -03:00
}
2019-03-14 22:44:27 -03:00
if ( ! target_loc . get_alt_cm ( Location : : AltFrame : : ABOVE_HOME , loiter_to_alt . alt ) ) {
2018-07-25 00:39:43 -03:00
loiter_to_alt . reached_destination_xy = true ;
loiter_to_alt . reached_alt = true ;
gcs ( ) . send_text ( MAV_SEVERITY_INFO , " bad do_loiter_to_alt " ) ;
return ;
}
loiter_to_alt . reached_destination_xy = false ;
loiter_to_alt . loiter_start_done = false ;
loiter_to_alt . reached_alt = false ;
loiter_to_alt . alt_error_cm = 0 ;
2021-05-19 11:07:38 -03:00
// set vertical speed and acceleration limits
2021-05-11 01:42:02 -03:00
pos_control - > set_max_speed_accel_z ( wp_nav - > get_default_speed_down ( ) , wp_nav - > get_default_speed_up ( ) , wp_nav - > get_accel_z ( ) ) ;
2022-02-22 09:23:00 -04:00
pos_control - > set_correction_speed_accel_z ( wp_nav - > get_default_speed_down ( ) , wp_nav - > get_default_speed_up ( ) , wp_nav - > get_accel_z ( ) ) ;
2022-05-25 09:26:00 -03:00
// set submode
set_submode ( SubMode : : LOITER_TO_ALT ) ;
2018-07-25 00:39:43 -03:00
}
2021-03-04 04:19:05 -04:00
// do_spline_wp - initiate move to next waypoint
2019-05-09 23:18:49 -03:00
void ModeAuto : : do_spline_wp ( const AP_Mission : : Mission_Command & cmd )
2018-03-22 10:25:18 -03:00
{
2021-01-19 22:50:48 -04:00
// calculate default location used when lat, lon or alt is zero
Location default_loc = copter . current_loc ;
2024-08-02 06:31:50 -03:00
// subtract position offsets
subtract_pos_offsets ( default_loc ) ;
2021-01-19 22:50:48 -04:00
if ( wp_nav - > is_active ( ) & & wp_nav - > reached_wp_destination ( ) ) {
if ( ! wp_nav - > get_wp_destination_loc ( default_loc ) ) {
// this should never happen
INTERNAL_ERROR ( AP_InternalError : : error_t : : flow_of_control ) ;
}
}
// get spline's location and next location from command and send to wp_nav
Location dest_loc , next_dest_loc ;
bool next_dest_loc_is_spline ;
get_spline_from_cmd ( cmd , default_loc , dest_loc , next_dest_loc , next_dest_loc_is_spline ) ;
if ( ! wp_nav - > set_spline_destination_loc ( dest_loc , next_dest_loc , next_dest_loc_is_spline ) ) {
// failure to set destination can only be because of missing terrain data
copter . failsafe_terrain_on_event ( ) ;
return ;
}
2018-03-22 10:25:18 -03:00
// this will be used to remember the time in millis after we reach or pass the WP.
loiter_time = 0 ;
// this is the delay, stored in seconds
loiter_time_max = cmd . p1 ;
2021-01-19 22:50:48 -04:00
// set next destination if necessary
if ( ! set_next_wp ( cmd , dest_loc ) ) {
// failure to set next destination can only be because of missing terrain data
copter . failsafe_terrain_on_event ( ) ;
return ;
}
2018-03-22 10:25:18 -03:00
2021-01-19 22:50:48 -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
2024-09-26 02:24:53 -03:00
if ( auto_yaw . mode ( ) ! = AutoYaw : : Mode : : ROI & & ! ( auto_yaw . mode ( ) = = AutoYaw : : Mode : : FIXED & & copter . g . wp_yaw_behavior = = WP_YAW_BEHAVIOR_NONE ) ) {
2021-01-19 22:50:48 -04:00
auto_yaw . set_mode_to_default ( false ) ;
2018-03-22 10:25:18 -03:00
}
2022-05-25 09:26:00 -03:00
// set submode
set_submode ( SubMode : : WP ) ;
2021-01-19 22:50:48 -04:00
}
2021-03-04 04:19:05 -04:00
// calculate locations required to build a spline curve from a mission command
// dest_loc is populated from cmd's location using default_loc in cases where the lat and lon or altitude is zero
// next_dest_loc and nest_dest_loc_is_spline is filled in with the following navigation command's location if it exists. If it does not exist it is set to the dest_loc and false
2021-01-19 22:50:48 -04:00
void ModeAuto : : get_spline_from_cmd ( const AP_Mission : : Mission_Command & cmd , const Location & default_loc , Location & dest_loc , Location & next_dest_loc , bool & next_dest_loc_is_spline )
{
dest_loc = loc_from_cmd ( cmd , default_loc ) ;
2018-03-22 10:25:18 -03:00
// if there is no delay at the end of this segment get next nav command
2021-01-19 22:50:48 -04:00
AP_Mission : : Mission_Command temp_cmd ;
2018-04-24 20:31:01 -03:00
if ( cmd . p1 = = 0 & & mission . get_next_nav_cmd ( cmd . index + 1 , temp_cmd ) ) {
2021-01-19 22:50:48 -04:00
next_dest_loc = loc_from_cmd ( temp_cmd , dest_loc ) ;
next_dest_loc_is_spline = temp_cmd . id = = MAV_CMD_NAV_SPLINE_WAYPOINT ;
} else {
next_dest_loc = dest_loc ;
next_dest_loc_is_spline = false ;
2018-03-22 10:25:18 -03:00
}
}
2024-09-04 00:48:37 -03:00
# if AC_NAV_GUIDED
2018-03-22 10:25:18 -03:00
// do_nav_guided_enable - initiate accepting commands from external nav computer
2019-05-09 23:18:49 -03:00
void ModeAuto : : do_nav_guided_enable ( const AP_Mission : : Mission_Command & cmd )
2018-03-22 10:25:18 -03:00
{
if ( cmd . p1 > 0 ) {
2019-03-08 01:40:41 -04:00
// start guided within auto
2018-03-22 10:25:18 -03:00
nav_guided_start ( ) ;
}
}
// do_guided_limits - pass guided limits to guided controller
2019-05-09 23:18:49 -03:00
void ModeAuto : : do_guided_limits ( const AP_Mission : : Mission_Command & cmd )
2018-03-22 10:25:18 -03:00
{
copter . mode_guided . limit_set (
cmd . p1 * 1000 , // convert seconds to ms
cmd . content . guided_limits . alt_min * 100.0f , // convert meters to cm
cmd . content . guided_limits . alt_max * 100.0f , // convert meters to cm
cmd . content . guided_limits . horiz_max * 100.0f ) ; // convert meters to cm
}
2023-08-02 19:34:05 -03:00
# endif // AC_NAV_GUIDED
2018-03-22 10:25:18 -03:00
// do_nav_delay - Delay the next navigation command
2019-05-09 23:18:49 -03:00
void ModeAuto : : do_nav_delay ( const AP_Mission : : Mission_Command & cmd )
2018-03-22 10:25:18 -03:00
{
2019-08-08 11:10:20 -03:00
nav_delay_time_start_ms = millis ( ) ;
2018-03-22 10:25:18 -03:00
if ( cmd . content . nav_delay . seconds > 0 ) {
// relative delay
2019-08-08 11:10:20 -03:00
nav_delay_time_max_ms = cmd . content . nav_delay . seconds * 1000 ; // convert seconds to milliseconds
2018-03-22 10:25:18 -03:00
} else {
// absolute delay to utc time
2023-10-05 04:40:35 -03:00
# if AP_RTC_ENABLED
2019-08-08 11:10:20 -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
2018-03-22 10:25:18 -03:00
}
2019-08-21 05:03:18 -03:00
gcs ( ) . send_text ( MAV_SEVERITY_INFO , " Delaying %u sec " , ( unsigned ) ( nav_delay_time_max_ms / 1000 ) ) ;
2018-03-22 10:25:18 -03:00
}
2022-02-17 08:59:16 -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 ( copter . mode_guided . init ( true ) ) {
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-13 17:30:58 -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-05-25 09:26:00 -03:00
set_submode ( SubMode : : NAV_SCRIPT_TIME ) ;
2022-02-17 08:59:16 -04:00
} else {
// for safety we set nav_scripting to done to protect against the mission getting stuck
nav_scripting . done = true ;
}
}
# endif
2022-05-25 02:20:27 -03:00
// start maintaining an attitude for a specified time
void ModeAuto : : do_nav_attitude_time ( const AP_Mission : : Mission_Command & cmd )
{
// copy command arguments into local structure
nav_attitude_time . roll_deg = cmd . content . nav_attitude_time . roll_deg ;
nav_attitude_time . pitch_deg = cmd . content . nav_attitude_time . pitch_deg ;
nav_attitude_time . yaw_deg = cmd . content . nav_attitude_time . yaw_deg ;
nav_attitude_time . climb_rate = cmd . content . nav_attitude_time . climb_rate ;
nav_attitude_time . start_ms = AP_HAL : : millis ( ) ;
2022-05-25 09:26:00 -03:00
set_submode ( SubMode : : NAV_ATTITUDE_TIME ) ;
2022-05-25 02:20:27 -03:00
}
2022-02-17 08:59:16 -04:00
2018-03-22 10:25:18 -03:00
/********************************************************************************/
2020-04-23 01:14:18 -03:00
// Condition (May) commands
2018-03-22 10:25:18 -03:00
/********************************************************************************/
2019-05-09 23:18:49 -03:00
void ModeAuto : : do_wait_delay ( const AP_Mission : : Mission_Command & cmd )
2018-03-22 10:25:18 -03:00
{
condition_start = millis ( ) ;
condition_value = cmd . content . delay . seconds * 1000 ; // convert seconds to milliseconds
}
2019-05-09 23:18:49 -03:00
void ModeAuto : : do_within_distance ( const AP_Mission : : Mission_Command & cmd )
2018-03-22 10:25:18 -03:00
{
condition_value = cmd . content . distance . meters * 100 ;
}
2019-05-09 23:18:49 -03:00
void ModeAuto : : do_yaw ( const AP_Mission : : Mission_Command & cmd )
2018-03-22 10:25:18 -03:00
{
2020-04-23 01:14:18 -03:00
auto_yaw . set_fixed_yaw (
cmd . content . yaw . angle_deg ,
cmd . content . yaw . turn_rate_dps ,
cmd . content . yaw . direction ,
cmd . content . yaw . relative_angle > 0 ) ;
2018-03-22 10:25:18 -03:00
}
/********************************************************************************/
2020-04-23 01:14:18 -03:00
// Do (Now) commands
2018-03-22 10:25:18 -03:00
/********************************************************************************/
2019-05-09 23:18:49 -03:00
void ModeAuto : : do_change_speed ( const AP_Mission : : Mission_Command & cmd )
2018-03-22 10:25:18 -03:00
{
if ( cmd . content . speed . target_ms > 0 ) {
2024-08-06 06:07:07 -03:00
switch ( cmd . content . speed . speed_type ) {
case SPEED_TYPE_CLIMB_SPEED :
2019-01-24 01:02:31 -04:00
copter . wp_nav - > set_speed_up ( cmd . content . speed . target_ms * 100.0f ) ;
2023-11-28 07:36:08 -04:00
desired_speed_override . up = cmd . content . speed . target_ms ;
2024-08-06 06:07:07 -03:00
break ;
case SPEED_TYPE_DESCENT_SPEED :
2019-01-24 01:02:31 -04:00
copter . wp_nav - > set_speed_down ( cmd . content . speed . target_ms * 100.0f ) ;
2023-11-28 07:36:08 -04:00
desired_speed_override . down = cmd . content . speed . target_ms ;
2024-08-06 06:07:07 -03:00
break ;
case SPEED_TYPE_AIRSPEED :
case SPEED_TYPE_GROUNDSPEED :
2018-10-09 08:46:37 -03:00
copter . wp_nav - > set_speed_xy ( cmd . content . speed . target_ms * 100.0f ) ;
2023-11-28 07:36:08 -04:00
desired_speed_override . xy = cmd . content . speed . target_ms ;
2024-08-06 06:07:07 -03:00
break ;
2018-10-09 08:46:37 -03:00
}
2018-03-22 10:25:18 -03:00
}
}
2019-05-09 23:18:49 -03:00
void ModeAuto : : do_set_home ( const AP_Mission : : Mission_Command & cmd )
2018-03-22 10:25:18 -03:00
{
2018-06-04 00:42:43 -03:00
if ( cmd . p1 = = 1 | | ( cmd . content . location . lat = = 0 & & cmd . content . location . lng = = 0 & & cmd . content . location . alt = = 0 ) ) {
2018-05-29 21:47:08 -03:00
if ( ! copter . set_home_to_current_location ( false ) ) {
// ignore failure
}
2018-03-22 10:25:18 -03:00
} else {
2018-05-29 21:47:08 -03:00
if ( ! copter . set_home ( cmd . content . location , false ) ) {
// ignore failure
}
2018-03-22 10:25:18 -03:00
}
}
// do_roi - starts actions required by MAV_CMD_DO_SET_ROI
// this involves either moving the camera to point at the ROI (region of interest)
// and possibly rotating the copter to point at the ROI if our mount type does not support a yaw feature
2020-04-23 01:14:18 -03:00
// TO-DO: add support for other features of MAV_CMD_DO_SET_ROI including pointing at a given waypoint
2019-05-09 23:18:49 -03:00
void ModeAuto : : do_roi ( const AP_Mission : : Mission_Command & cmd )
2018-03-22 10:25:18 -03:00
{
2017-12-25 23:55:42 -04:00
auto_yaw . set_roi ( cmd . content . location ) ;
2018-03-22 10:25:18 -03:00
}
2024-09-21 06:47:10 -03:00
# if HAL_MOUNT_ENABLED
2018-03-22 10:25:18 -03:00
// point the camera to a specified angle
2019-05-09 23:18:49 -03:00
void ModeAuto : : do_mount_control ( const AP_Mission : : Mission_Command & cmd )
2018-03-22 10:25:18 -03:00
{
2021-03-09 23:28:29 -04:00
// if vehicle has a camera mount but it doesn't do pan control then yaw the entire vehicle instead
2023-05-24 04:07:42 -03:00
if ( ( copter . camera_mount . get_mount_type ( ) ! = AP_Mount : : Type : : None ) & &
2021-03-09 23:28:29 -04:00
! copter . camera_mount . has_pan_control ( ) ) {
2024-05-15 22:25:51 -03:00
// Per the handler in AP_Mount, DO_MOUNT_CONTROL yaw angle is in body frame, which is
// equivalent to an offset to the current yaw demand.
auto_yaw . set_yaw_angle_offset ( cmd . content . mount_control . yaw ) ;
2018-03-22 10:25:18 -03:00
}
2021-03-09 23:28:29 -04:00
// pass the target angles to the camera mount
2022-06-20 08:52:27 -03:00
copter . camera_mount . set_angle_target ( cmd . content . mount_control . roll , cmd . content . mount_control . pitch , cmd . content . mount_control . yaw , false ) ;
2018-03-22 10:25:18 -03:00
}
2024-09-21 06:47:10 -03:00
# endif // HAL_MOUNT_ENABLED
2018-03-22 10:25:18 -03:00
2023-03-03 00:13:14 -04:00
# if AP_WINCH_ENABLED
2018-03-22 10:25:18 -03:00
// control winch based on mission command
2019-05-09 23:18:49 -03:00
void ModeAuto : : do_winch ( const AP_Mission : : Mission_Command & cmd )
2018-03-22 10:25:18 -03:00
{
// Note: we ignore the gripper num parameter because we only support one gripper
switch ( cmd . content . winch . action ) {
case WINCH_RELAXED :
g2 . winch . relax ( ) ;
break ;
case WINCH_RELATIVE_LENGTH_CONTROL :
2020-07-24 05:38:12 -03:00
g2 . winch . release_length ( cmd . content . winch . release_length ) ;
2018-03-22 10:25:18 -03:00
break ;
case WINCH_RATE_CONTROL :
g2 . winch . set_desired_rate ( cmd . content . winch . release_rate ) ;
break ;
default :
// do nothing
break ;
}
}
# endif
2023-10-28 03:06:45 -03:00
# if AP_MISSION_NAV_PAYLOAD_PLACE_ENABLED && AC_PAYLOAD_PLACE_ENABLED
2018-03-22 10:25:18 -03:00
// do_payload_place - initiate placing procedure
2019-05-09 23:18:49 -03:00
void ModeAuto : : do_payload_place ( const AP_Mission : : Mission_Command & cmd )
2018-03-22 10:25:18 -03:00
{
// if location provided we fly to that location at current altitude
if ( cmd . content . location . lat ! = 0 | | cmd . content . location . lng ! = 0 ) {
// set state to fly to location
2023-09-27 22:24:36 -03:00
payload_place . state = PayloadPlace : : State : : FlyToLocation ;
2018-03-22 10:25:18 -03:00
2022-06-15 00:46:55 -03:00
// convert cmd to location class
Location target_loc ( cmd . content . location ) ;
if ( ! shift_alt_to_current_alt ( target_loc ) ) {
// this can only fail due to missing terrain database alt or rangefinder alt
// use current alt-above-home and report error
target_loc . set_alt_cm ( copter . current_loc . alt , Location : : AltFrame : : ABOVE_HOME ) ;
2023-07-13 21:58:09 -03:00
LOGGER_WRITE_ERROR ( LogErrorSubsystem : : TERRAIN , LogErrorCode : : MISSING_TERRAIN_DATA ) ;
2022-06-15 00:46:55 -03:00
gcs ( ) . send_text ( MAV_SEVERITY_CRITICAL , " PayloadPlace: no terrain data, using alt-above-home " ) ;
}
2022-12-23 03:34:20 -04:00
if ( ! wp_start ( target_loc ) ) {
// failure to set next destination can only be because of missing terrain data
copter . failsafe_terrain_on_event ( ) ;
return ;
}
2018-03-22 10:25:18 -03:00
} else {
// initialise placing controller
2023-09-27 22:24:36 -03:00
payload_place . start_descent ( ) ;
2018-03-22 10:25:18 -03:00
}
2023-09-27 22:24:36 -03:00
payload_place . descent_max_cm = cmd . p1 ;
// set submode
set_submode ( SubMode : : NAV_PAYLOAD_PLACE ) ;
2018-03-22 10:25:18 -03:00
}
2023-10-18 23:34:30 -03:00
# endif // AP_MISSION_NAV_PAYLOAD_PLACE_ENABLED
2018-03-22 10:25:18 -03:00
// do_RTL - start Return-to-Launch
2019-05-09 23:18:49 -03:00
void ModeAuto : : do_RTL ( void )
2018-03-22 10:25:18 -03:00
{
// start rtl in auto flight mode
rtl_start ( ) ;
}
/********************************************************************************/
2020-04-23 01:14:18 -03:00
// Verify Nav (Must) commands
2018-03-22 10:25:18 -03:00
/********************************************************************************/
// verify_takeoff - check if we have completed the takeoff
2019-05-09 23:18:49 -03:00
bool ModeAuto : : verify_takeoff ( )
2018-03-22 10:25:18 -03:00
{
2022-10-01 07:21:38 -03:00
# if AP_LANDINGGEAR_ENABLED
2021-01-10 22:56:52 -04:00
// if we have reached our destination
2023-09-28 02:05:51 -03:00
if ( auto_takeoff . complete ) {
2021-01-10 22:56:52 -04:00
// retract the landing gear
2020-02-20 23:08:26 -04:00
copter . landinggear . retract_after_takeoff ( ) ;
2019-04-07 12:31:20 -03:00
}
2021-02-06 23:29:33 -04:00
# endif
2019-04-07 12:31:20 -03:00
2023-09-28 02:05:51 -03:00
return auto_takeoff . complete ;
2018-03-22 10:25:18 -03:00
}
// verify_land - returns true if landing has been completed
2019-05-09 23:18:49 -03:00
bool ModeAuto : : verify_land ( )
2018-03-22 10:25:18 -03:00
{
bool retval = false ;
2019-12-01 19:25:32 -04:00
switch ( state ) {
case State : : FlyToLocation :
2018-03-22 10:25:18 -03:00
// check if we've reached the location
if ( copter . wp_nav - > reached_wp_destination ( ) ) {
// initialise landing controller
2022-02-22 09:23:00 -04:00
land_start ( ) ;
2018-03-22 10:25:18 -03:00
// advance to next state
2019-12-01 19:25:32 -04:00
state = State : : Descending ;
2018-03-22 10:25:18 -03:00
}
break ;
2019-12-01 19:25:32 -04:00
case State : : Descending :
2018-03-22 10:25:18 -03:00
// rely on THROTTLE_LAND mode to correctly update landing status
2019-05-09 23:18:49 -03:00
retval = copter . ap . land_complete & & ( motors - > get_spool_state ( ) = = AP_Motors : : SpoolState : : GROUND_IDLE ) ;
2021-09-06 21:55:47 -03:00
if ( retval & & ! mission . continue_after_land_check_for_takeoff ( ) & & copter . motors - > armed ( ) ) {
2020-03-03 23:29:14 -04:00
/*
we want to stop mission processing on land
completion . Disarm now , then return false . This
leaves mission state machine in the current NAV_LAND
mission item . After disarming the mission will reset
*/
copter . arming . disarm ( AP_Arming : : Method : : LANDED ) ;
retval = false ;
}
2018-03-22 10:25:18 -03:00
break ;
default :
// this should never happen
2021-01-03 22:10:14 -04:00
INTERNAL_ERROR ( AP_InternalError : : error_t : : flow_of_control ) ;
2018-03-22 10:25:18 -03:00
retval = true ;
break ;
}
// true is returned if we've successfully landed
return retval ;
}
2023-10-18 23:34:30 -03:00
# if AC_PAYLOAD_PLACE_ENABLED
2018-03-22 10:25:18 -03:00
// verify_payload_place - returns true if placing has been completed
2023-09-27 22:24:36 -03:00
bool PayloadPlace : : verify ( )
{
switch ( state ) {
case State : : FlyToLocation :
case State : : Descent_Start :
case State : : Descent :
case State : : Release :
case State : : Releasing :
case State : : Delay :
case State : : Ascent_Start :
case State : : Ascent :
2022-12-30 22:11:31 -04:00
return false ;
2023-09-27 22:24:36 -03:00
case State : : Done :
2018-03-22 10:25:18 -03:00
return true ;
}
// should never get here
return true ;
}
2023-10-18 23:34:30 -03:00
# endif
2018-03-22 10:25:18 -03:00
2019-05-09 23:18:49 -03:00
bool ModeAuto : : verify_loiter_unlimited ( )
2018-03-22 10:25:18 -03:00
{
return false ;
}
2014-01-27 10:43:48 -04:00
2018-03-22 10:25:18 -03:00
// verify_loiter_time - check if we have loitered long enough
2019-05-09 23:18:49 -03:00
bool ModeAuto : : verify_loiter_time ( const AP_Mission : : Mission_Command & cmd )
2018-03-22 10:25:18 -03:00
{
// return immediately if we haven't reached our destination
if ( ! copter . wp_nav - > reached_wp_destination ( ) ) {
return false ;
}
// start our loiter timer
2018-06-04 00:42:43 -03:00
if ( loiter_time = = 0 ) {
2018-03-22 10:25:18 -03:00
loiter_time = millis ( ) ;
}
// check if loiter timer has run out
2019-02-25 16:38:38 -04:00
if ( ( ( millis ( ) - loiter_time ) / 1000 ) > = loiter_time_max ) {
gcs ( ) . send_text ( MAV_SEVERITY_INFO , " Reached command #%i " , cmd . index ) ;
return true ;
}
return false ;
2014-01-27 10:43:48 -04:00
}
2018-07-25 00:39:43 -03:00
// verify_loiter_to_alt - check if we have reached both destination
// (roughly) and altitude (precisely)
2021-02-01 12:26:21 -04:00
bool ModeAuto : : verify_loiter_to_alt ( ) const
2018-07-25 00:39:43 -03:00
{
if ( loiter_to_alt . reached_destination_xy & &
loiter_to_alt . reached_alt ) {
return true ;
}
return false ;
}
2018-03-22 10:25:18 -03:00
// verify_RTL - handles any state changes required to implement RTL
// do_RTL should have been called once first to initialise all variables
// returns true with RTL has completed successfully
2019-05-09 23:18:49 -03:00
bool ModeAuto : : verify_RTL ( )
2014-05-23 02:29:08 -03:00
{
2019-03-14 20:45:00 -03:00
return ( copter . mode_rtl . state_complete ( ) & &
2021-04-13 12:22:04 -03:00
( copter . mode_rtl . state ( ) = = ModeRTL : : SubMode : : FINAL_DESCENT | | copter . mode_rtl . state ( ) = = ModeRTL : : SubMode : : LAND ) & &
2019-12-11 23:36:28 -04:00
( motors - > get_spool_state ( ) = = AP_Motors : : SpoolState : : GROUND_IDLE ) ) ;
2018-03-22 10:25:18 -03:00
}
2014-05-23 02:29:08 -03:00
2018-03-22 10:25:18 -03:00
/********************************************************************************/
// Verify Condition (May) commands
/********************************************************************************/
2014-10-13 05:41:48 -03:00
2019-05-09 23:18:49 -03:00
bool ModeAuto : : verify_wait_delay ( )
2018-03-22 10:25:18 -03:00
{
if ( millis ( ) - condition_start > ( uint32_t ) MAX ( condition_value , 0 ) ) {
condition_value = 0 ;
return true ;
}
return false ;
2014-05-23 02:29:08 -03:00
}
2019-05-09 23:18:49 -03:00
bool ModeAuto : : verify_within_distance ( )
2014-05-23 02:29:08 -03:00
{
2018-03-22 10:25:18 -03:00
if ( wp_distance ( ) < ( uint32_t ) MAX ( condition_value , 0 ) ) {
condition_value = 0 ;
return true ;
}
return false ;
2014-05-23 02:29:08 -03:00
}
2018-03-22 10:25:18 -03:00
// verify_yaw - return true if we have reached the desired heading
2019-05-09 23:18:49 -03:00
bool ModeAuto : : verify_yaw ( )
2014-10-12 05:06:51 -03:00
{
2022-02-15 13:40:51 -04:00
// make sure still in fixed yaw mode, the waypoint controller often retakes control of yaw as it executes a new waypoint command
2022-09-24 11:12:33 -03:00
auto_yaw . set_mode ( AutoYaw : : Mode : : FIXED ) ;
2018-03-22 10:25:18 -03:00
2022-09-24 11:12:33 -03:00
// check if we have reached the target heading
return auto_yaw . reached_fixed_yaw_target ( ) ;
2018-03-22 10:25:18 -03:00
}
2014-10-12 05:06:51 -03:00
2018-03-22 10:25:18 -03:00
// verify_nav_wp - check if we have reached the next way point
2019-05-09 23:18:49 -03:00
bool ModeAuto : : verify_nav_wp ( const AP_Mission : : Mission_Command & cmd )
2018-03-22 10:25:18 -03:00
{
// check if we have reached the waypoint
2018-06-04 00:42:43 -03:00
if ( ! copter . wp_nav - > reached_wp_destination ( ) ) {
2018-03-22 10:25:18 -03:00
return false ;
}
2014-10-12 05:06:51 -03:00
2018-03-22 10:25:18 -03:00
// start timer if necessary
2018-06-04 00:42:43 -03:00
if ( loiter_time = = 0 ) {
2018-03-22 10:25:18 -03:00
loiter_time = millis ( ) ;
2020-04-23 01:14:18 -03:00
if ( loiter_time_max > 0 ) {
// play a tone
AP_Notify : : events . waypoint_complete = 1 ;
}
2018-03-22 10:25:18 -03:00
}
2014-10-12 05:06:51 -03:00
2018-03-22 10:25:18 -03:00
// check if timer has run out
if ( ( ( millis ( ) - loiter_time ) / 1000 ) > = loiter_time_max ) {
2020-04-23 01:14:18 -03:00
if ( loiter_time_max = = 0 ) {
// play a tone
AP_Notify : : events . waypoint_complete = 1 ;
}
2018-03-22 10:25:18 -03:00
gcs ( ) . send_text ( MAV_SEVERITY_INFO , " Reached command #%i " , cmd . index ) ;
return true ;
}
2019-02-25 18:05:51 -04:00
return false ;
2014-10-12 05:06:51 -03:00
}
2018-03-22 10:25:18 -03:00
// verify_circle - check if we have circled the point enough
2019-05-09 23:18:49 -03:00
bool ModeAuto : : verify_circle ( const AP_Mission : : Mission_Command & cmd )
2014-10-19 22:54:57 -03:00
{
2018-03-22 10:25:18 -03:00
// check if we've reached the edge
2022-05-25 09:26:00 -03:00
if ( _mode = = SubMode : : CIRCLE_MOVE_TO_EDGE ) {
2018-03-22 10:25:18 -03:00
if ( copter . wp_nav - > reached_wp_destination ( ) ) {
// start circling
circle_start ( ) ;
}
return false ;
2014-10-12 05:06:51 -03:00
}
2024-01-12 00:14:19 -04:00
const float turns = cmd . get_loiter_turns ( ) ;
2018-03-22 10:25:18 -03:00
// check if we have completed circling
2024-01-12 00:14:19 -04:00
return fabsf ( copter . circle_nav - > get_angle_total ( ) / float ( M_2PI ) ) > = turns ;
2018-03-22 10:25:18 -03:00
}
// verify_spline_wp - check if we have reached the next way point using spline
2019-05-09 23:18:49 -03:00
bool ModeAuto : : verify_spline_wp ( const AP_Mission : : Mission_Command & cmd )
2018-03-22 10:25:18 -03:00
{
// check if we have reached the waypoint
2018-06-04 00:42:43 -03:00
if ( ! copter . wp_nav - > reached_wp_destination ( ) ) {
2018-03-22 10:25:18 -03:00
return false ;
2014-10-12 05:06:51 -03:00
}
2018-03-22 10:25:18 -03:00
// start timer if necessary
2018-06-04 00:42:43 -03:00
if ( loiter_time = = 0 ) {
2018-03-22 10:25:18 -03:00
loiter_time = millis ( ) ;
}
2016-01-13 03:09:03 -04:00
2018-03-22 10:25:18 -03:00
// check if timer has run out
if ( ( ( millis ( ) - loiter_time ) / 1000 ) > = loiter_time_max ) {
gcs ( ) . send_text ( MAV_SEVERITY_INFO , " Reached command #%i " , cmd . index ) ;
return true ;
}
2019-02-25 18:05:51 -04:00
return false ;
2018-03-22 10:25:18 -03:00
}
2016-04-22 08:45:28 -03:00
2024-09-04 00:48:37 -03:00
# if AC_NAV_GUIDED
2018-03-22 10:25:18 -03:00
// verify_nav_guided - check if we have breached any limits
2019-05-09 23:18:49 -03:00
bool ModeAuto : : verify_nav_guided_enable ( const AP_Mission : : Mission_Command & cmd )
2018-03-22 10:25:18 -03:00
{
// if disabling guided mode then immediately return true so we move to next command
if ( cmd . p1 = = 0 ) {
return true ;
}
// check time and position limits
return copter . mode_guided . limit_check ( ) ;
}
2023-08-02 19:34:05 -03:00
# endif // AC_NAV_GUIDED
2018-03-22 10:25:18 -03:00
// verify_nav_delay - check if we have waited long enough
2019-05-09 23:18:49 -03:00
bool ModeAuto : : verify_nav_delay ( const AP_Mission : : Mission_Command & cmd )
2018-03-22 10:25:18 -03:00
{
2019-08-08 11:10:20 -03:00
if ( millis ( ) - nav_delay_time_start_ms > nav_delay_time_max_ms ) {
nav_delay_time_max_ms = 0 ;
2018-03-22 10:25:18 -03:00
return true ;
}
return false ;
2014-10-12 05:06:51 -03:00
}
2022-02-17 08:59:16 -04:00
# if AP_SCRIPTING_ENABLED
// 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:20 -04:00
( ( nav_scripting . timeout_s > 0 ) & &
( AP_HAL : : millis ( ) - nav_scripting . start_ms ) > ( nav_scripting . timeout_s * 1000 ) ) ) {
2022-02-17 08:59:16 -04:00
return true ;
}
return false ;
}
# endif
2022-05-25 02:20:27 -03:00
// check if nav_attitude_time command has completed
bool ModeAuto : : verify_nav_attitude_time ( const AP_Mission : : Mission_Command & cmd )
{
return ( ( AP_HAL : : millis ( ) - nav_attitude_time . start_ms ) > ( cmd . content . nav_attitude_time . time_sec * 1000 ) ) ;
}
2022-01-27 14:36:21 -04:00
// pause - Prevent aircraft from progressing along the track
bool ModeAuto : : pause ( )
{
2023-03-01 19:23:06 -04:00
// do not pause if not in the WP sub mode or already reached to the destination
2023-03-08 14:24:25 -04:00
if ( _mode ! = SubMode : : WP | | wp_nav - > reached_wp_destination ( ) ) {
2022-01-27 14:36:21 -04:00
return false ;
}
2023-03-08 14:24:25 -04:00
wp_nav - > set_pause ( ) ;
2022-01-27 14:36:21 -04:00
return true ;
}
// resume - Allow aircraft to progress along the track
bool ModeAuto : : resume ( )
{
2023-03-08 14:24:25 -04:00
wp_nav - > set_resume ( ) ;
2022-01-27 14:36:21 -04:00
return true ;
}
2023-04-19 03:53:38 -03:00
bool ModeAuto : : paused ( ) const
{
2024-08-23 21:47:40 -03:00
return ( wp_nav ! = nullptr ) & & wp_nav - > paused ( ) ;
2023-04-19 03:53:38 -03:00
}
2018-02-21 22:06:07 -04:00
# endif