2015-05-29 23:12:49 -03:00
# include "Copter.h"
2018-02-21 22:06:07 -04:00
# if MODE_AUTO_ENABLED == ENABLED
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 ) {
2021-04-13 12:06:43 -03:00
_mode = SubMode : : LOITER ;
2014-10-12 05:06:51 -03:00
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 ;
}
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
2017-12-25 23:55:42 -04:00
if ( auto_yaw . mode ( ) = = AUTO_YAW_ROI ) {
auto_yaw . set_mode ( AUTO_YAW_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
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)
check_for_mission_change ( ) ;
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
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)
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
if ( check_for_mission_change ( ) ) {
// if mission is running restart the current command if it is a waypoint or spline command
2021-04-13 12:06:43 -03:00
if ( ( copter . mode_auto . 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 :
2014-10-16 09:30:07 -03:00
# if NAV_GUIDED == 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 ;
2021-04-13 12:06:43 -03:00
case SubMode : : NAV_PAYLOAD_PLACE :
2016-03-21 00:45:50 -03:00
payload_place_run ( ) ;
2016-11-17 01:19:22 -04:00
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
if ( ! ( mission . get_in_landing_sequence_flag ( ) | | mission . state ( ) = = AP_Mission : : mission_state : : MISSION_COMPLETE ) ) {
auto_RTL = false ;
}
2014-01-24 22:37:42 -04:00
}
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
{
2021-07-24 20:25:18 -03:00
return ( ( copter . g2 . auto_options & ( uint32_t ) Options : : AllowArming ) ! = 0 ) & & ! auto_RTL ;
2020-10-14 02:27:10 -03:00
} ;
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 )
{
if ( mission . jump_to_landing_sequence ( ) ) {
mission . set_force_resume ( true ) ;
if ( set_mode ( Mode : : Number : : AUTO , reason ) ) {
auto_RTL = true ;
return true ;
}
// mode change failed, revert force resume flag
mission . set_force_resume ( false ) ;
return false ;
}
gcs ( ) . send_text ( MAV_SEVERITY_INFO , " No landing sequence found " ) ;
return false ;
}
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
2017-12-25 23:55:42 -04:00
auto_yaw . set_mode ( AUTO_YAW_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
{
2021-04-13 12:06:43 -03:00
_mode = SubMode : : RTL ;
2018-03-22 10:25:18 -03:00
// call regular rtl flight mode initialisation and ask it to ignore checks
copter . mode_rtl . init ( true ) ;
}
2014-01-24 22:37:42 -04:00
// auto_takeoff_start - initialises 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
{
2021-04-13 12:06:43 -03:00
_mode = SubMode : : TAKEOFF ;
2014-01-24 22:37:42 -04:00
2019-01-01 22:54:31 -04:00
Location dest ( dest_loc ) ;
2015-10-05 05:23:58 -03:00
2019-06-12 23:11:12 -03:00
if ( ! copter . current_loc . initialised ( ) ) {
// vehicle doesn't know where it is ATM. We should not
// initialise our takeoff destination without knowing this!
return ;
}
2015-10-05 05:23:58 -03:00
// set horizontal target
2018-02-07 22:21:09 -04:00
dest . lat = copter . current_loc . lat ;
dest . lng = copter . current_loc . lng ;
2015-10-05 05:23:58 -03:00
// get altitude target
int32_t alt_target ;
2019-03-14 22:44:27 -03:00
if ( ! dest . get_alt_cm ( Location : : AltFrame : : ABOVE_HOME , alt_target ) ) {
2015-10-05 05:23:58 -03:00
// this failure could only happen if take-off alt was specified as an alt-above terrain and we have no terrain data
2019-03-24 22:31:46 -03:00
AP : : logger ( ) . Write_Error ( LogErrorSubsystem : : TERRAIN , LogErrorCode : : MISSING_TERRAIN_DATA ) ;
2015-10-05 05:23:58 -03:00
// fall back to altitude above current altitude
2018-02-07 22:21:09 -04:00
alt_target = copter . current_loc . alt + dest . alt ;
2015-10-05 05:23:58 -03:00
}
// sanity check target
2018-02-07 22:21:09 -04:00
if ( alt_target < copter . current_loc . alt ) {
2019-03-14 22:44:27 -03:00
dest . set_alt_cm ( copter . current_loc . alt , Location : : AltFrame : : ABOVE_HOME ) ;
2015-10-05 05:23:58 -03:00
}
// Note: if taking off from below home this could cause a climb to an unexpectedly high altitude
if ( alt_target < 100 ) {
2019-03-14 22:44:27 -03:00
dest . set_alt_cm ( 100 , Location : : AltFrame : : ABOVE_HOME ) ;
2015-10-05 05:23:58 -03:00
}
// set waypoint controller target
2021-01-19 22:50:48 -04:00
if ( ! wp_nav - > set_wp_destination_loc ( dest ) ) {
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 ( ) ;
2015-10-05 05:23:58 -03:00
return ;
}
2014-01-24 22:37:42 -04:00
// initialise yaw
2017-12-25 23:55:42 -04:00
auto_yaw . set_mode ( AUTO_YAW_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
set_throttle_takeoff ( ) ;
2016-06-04 23:37:55 -03:00
2016-08-15 00:57:38 -03:00
// get initial alt for WP_NAVALT_MIN
2018-06-26 00:24:54 -03:00
auto_takeoff_set_start_alt ( ) ;
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
2019-05-09 23:18:49 -03:00
void ModeAuto : : wp_start ( const Location & dest_loc )
2015-08-16 16:10:23 -03:00
{
// send target to waypoint controller
2021-01-19 22:50:48 -04:00
if ( ! wp_nav - > set_wp_destination_loc ( dest_loc ) ) {
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-05-07 04:26:49 -03:00
return ;
2015-08-16 16:10:23 -03:00
}
2021-04-13 12:06:43 -03:00
_mode = SubMode : : WP ;
2021-01-29 03:25:29 -04:00
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
2017-12-25 23:55:42 -04:00
if ( auto_yaw . mode ( ) ! = AUTO_YAW_ROI ) {
auto_yaw . set_mode_to_default ( false ) ;
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
{
2014-01-25 00:40:32 -04:00
// set target to stopping point
2021-06-21 04:22:48 -03:00
Vector2f stopping_point ;
2018-03-27 23:13:37 -03:00
loiter_nav - > get_stopping_point_xy ( stopping_point ) ;
2014-01-24 22:37:42 -04:00
// call location specific land start function
2016-03-21 00:45:50 -03:00
land_start ( stopping_point ) ;
2014-01-24 22:37:42 -04:00
}
// auto_land_start - initialises controller to implement a landing
2021-06-21 04:22:48 -03:00
void ModeAuto : : land_start ( const Vector2f & destination )
2014-01-24 22:37:42 -04:00
{
2021-04-13 12:06:43 -03:00
_mode = SubMode : : LAND ;
2014-01-24 22:37:42 -04:00
2014-01-25 00:40:32 -04:00
// initialise loiter target destination
2018-03-27 23:13:37 -03:00
loiter_nav - > init_target ( destination ) ;
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
2017-12-25 23:55:42 -04:00
auto_yaw . set_mode ( AUTO_YAW_HOLD ) ;
2020-02-20 23:08:26 -04:00
2021-02-06 23:29:33 -04:00
# if LANDING_GEAR_ENABLED == ENABLED
2020-02-20 23:08:26 -04:00
// optionally deploy landing gear
copter . landinggear . deploy_for_landing ( ) ;
2021-02-06 23:29:33 -04:00
# endif
2021-01-06 11:19:23 -04:00
# if AC_FENCE == ENABLED
2021-02-19 08:47:28 -04:00
// disable the fence on landing
2021-01-13 19:37:25 -04:00
copter . fence . auto_disable_fence_for_landing ( ) ;
2021-01-06 11:19:23 -04:00
# endif
2014-01-24 22:37:42 -04:00
}
2014-04-16 04:23:24 -03:00
// auto_circle_movetoedge_start - initialise waypoint controller to move to edge of a circle with it's center at the specified location
// we assume the caller has performed all required GPS_ok checks
2019-05-09 23:18:49 -03:00
void ModeAuto : : circle_movetoedge_start ( const Location & circle_center , float radius_m )
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 ) ) {
2018-02-07 22:21:09 -04:00
copter . circle_nav - > set_radius ( radius_m * 100.0f ) ;
2016-03-09 07:21:08 -04:00
}
2014-04-16 04:23:24 -03:00
2016-03-09 07:21:08 -04:00
// check our distance from edge of circle
Vector3f circle_edge_neu ;
2018-02-07 22:21:09 -04:00
copter . circle_nav - > get_closest_point_on_circle ( circle_edge_neu ) ;
2016-03-09 07:21:08 -04:00
float dist_to_edge = ( inertial_nav . get_position ( ) - circle_edge_neu ) . length ( ) ;
// if more than 3m then fly to edge
if ( dist_to_edge > 300.0f ) {
// set the state to move to the edge of the circle
2021-04-13 12:06:43 -03:00
_mode = SubMode : : CIRCLE_MOVE_TO_EDGE ;
2016-03-09 07:21:08 -04:00
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-06-17 22:20:26 -03:00
const Vector3p & circle_center_neu = copter . circle_nav - > get_center ( ) ;
2016-03-09 07:21:08 -04:00
const Vector3f & curr_pos = inertial_nav . get_position ( ) ;
2016-04-16 06:58:46 -03:00
float dist_to_center = norm ( circle_center_neu . x - curr_pos . x , circle_center_neu . y - curr_pos . y ) ;
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
if ( auto_yaw . mode ( ) ! = AUTO_YAW_ROI ) {
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
auto_yaw . set_mode ( AUTO_YAW_HOLD ) ;
}
2016-03-09 07:21:08 -04:00
}
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
{
2021-04-13 12:06:43 -03:00
_mode = SubMode : : CIRCLE ;
2014-01-27 23:20:39 -04:00
2014-04-16 04:23:24 -03:00
// initialise circle controller
2020-04-08 03:21:13 -03:00
copter . circle_nav - > init ( copter . circle_nav - > get_center ( ) , copter . circle_nav - > center_is_terrain_alt ( ) ) ;
2020-04-09 07:41:06 -03:00
if ( auto_yaw . mode ( ) ! = AUTO_YAW_ROI ) {
2020-04-21 08:50:25 -03:00
auto_yaw . set_mode ( AUTO_YAW_CIRCLE ) ;
2020-04-09 07:41:06 -03:00
}
2014-01-27 10:43:48 -04:00
}
2018-03-22 10:25:18 -03:00
# if NAV_GUIDED == ENABLED
// 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
{
2021-04-13 12:06:43 -03:00
_mode = SubMode : : NAVGUIDED ;
2018-03-22 10:25:18 -03:00
// call regular guided flight mode initialisation
copter . mode_guided . init ( true ) ;
// initialise guided start time and position as reference for limit checking
copter . mode_guided . limit_init_time_and_pos ( ) ;
}
# endif //NAV_GUIDED
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
{
2021-04-13 12:06:43 -03:00
return ( ( _mode = = SubMode : : TAKEOFF ) & & ! wp_nav - > reached_wp_destination ( ) ) ;
2018-04-30 06:50:04 -03:00
}
2018-03-22 10:25:18 -03:00
// auto_payload_place_start - initialises controller to implement a placing
2019-05-09 23:18:49 -03:00
void ModeAuto : : payload_place_start ( )
2018-03-22 10:25:18 -03:00
{
// set target to stopping point
2021-06-21 04:22:48 -03:00
Vector2f stopping_point ;
2018-03-27 23:13:37 -03:00
loiter_nav - > get_stopping_point_xy ( stopping_point ) ;
2018-03-22 10:25:18 -03:00
// call location specific place start function
payload_place_start ( stopping_point ) ;
}
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
{
return ( copter . g2 . auto_options . get ( ) & uint32_t ( Options : : IgnorePilotYaw ) ) = = 0 ;
}
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
{
// To-Do: logging when new commands start/end
if ( copter . should_log ( MASK_LOG_CMD ) ) {
2019-01-18 00:24:08 -04:00
copter . logger . Write_Mission_Cmd ( mission , cmd ) ;
2018-03-22 10:25:18 -03:00
}
switch ( cmd . id ) {
///
/// navigation commands
///
case MAV_CMD_NAV_TAKEOFF : // 22
do_takeoff ( cmd ) ;
break ;
case MAV_CMD_NAV_WAYPOINT : // 16 Navigate to Waypoint
do_nav_wp ( cmd ) ;
break ;
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 ;
# if NAV_GUIDED == ENABLED
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 ;
2019-03-08 01:40:41 -04:00
case MAV_CMD_NAV_PAYLOAD_PLACE : // 94 place at Waypoint
do_payload_place ( 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 ;
case MAV_CMD_DO_MOUNT_CONTROL : // 205
// point the camera to a specified angle
do_mount_control ( cmd ) ;
break ;
case MAV_CMD_DO_FENCE_ENABLE :
# if AC_FENCE == ENABLED
if ( cmd . p1 = = 0 ) { //disable
copter . fence . enable ( false ) ;
gcs ( ) . send_text ( MAV_SEVERITY_INFO , " Fence Disabled " ) ;
} else { //enable fence
copter . fence . enable ( true ) ;
gcs ( ) . send_text ( MAV_SEVERITY_INFO , " Fence Enabled " ) ;
}
# endif //AC_FENCE == ENABLED
break ;
# if NAV_GUIDED == ENABLED
case MAV_CMD_DO_GUIDED_LIMITS : // 220 accept guided mode limits
do_guided_limits ( cmd ) ;
break ;
# endif
# if WINCH_ENABLED == ENABLED
case MAV_CMD_DO_WINCH : // Mission command to control winch
do_winch ( cmd ) ;
break ;
# endif
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
}
}
2021-03-04 04:19:05 -04:00
// detect external changes to mission
bool ModeAuto : : check_for_mission_change ( )
{
// check if mission has been updated
const uint32_t change_time_ms = mission . last_change_time_ms ( ) ;
const bool update_time_changed = ( change_time_ms ! = mis_change_detect . last_change_time_ms ) ; ;
// check if active command index has changed
const uint16_t curr_cmd_idx = mission . get_current_nav_index ( ) ;
const bool curr_cmd_idx_changed = ( curr_cmd_idx ! = mis_change_detect . curr_cmd_index ) ;
// no changes if neither mission update time nor active command index has changed
if ( ! update_time_changed & & ! curr_cmd_idx_changed ) {
return false ;
}
// the mission has been updated (but maybe not changed) and/or the current command index has changed
// check the contents of the next three commands to ensure they have not changed
// and update storage so we can detect future changes
bool cmds_changed = false ; // true if upcoming command contents have changed
// retrieve cmds from mission and compare with mis_change_detect
uint8_t num_cmds = 0 ;
uint16_t cmd_idx = curr_cmd_idx ;
AP_Mission : : Mission_Command cmd [ mis_change_detect_cmd_max ] ;
while ( ( num_cmds < ARRAY_SIZE ( cmd ) ) & & mission . get_next_nav_cmd ( cmd_idx , cmd [ num_cmds ] ) ) {
num_cmds + + ;
if ( ( num_cmds > mis_change_detect . cmd_count ) | | ( cmd [ num_cmds - 1 ] ! = mis_change_detect . cmd [ num_cmds - 1 ] ) ) {
cmds_changed = true ;
mis_change_detect . cmd [ num_cmds - 1 ] = cmd [ num_cmds - 1 ] ;
}
cmd_idx = cmd [ num_cmds - 1 ] . index + 1 ;
}
// mission has changed if number of upcoming commands does not match mis_change_detect
if ( num_cmds ! = mis_change_detect . cmd_count ) {
cmds_changed = true ;
}
// update mis_change_detect with last change time, command index and number of commands
mis_change_detect . last_change_time_ms = change_time_ms ;
mis_change_detect . curr_cmd_index = curr_cmd_idx ;
mis_change_detect . cmd_count = num_cmds ;
// mission has changed if upcoming command contents have changed without the current command index changing
return cmds_changed & & ! curr_cmd_idx_changed ;
}
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
2021-04-13 12:06:43 -03:00
if ( copter . flightmode - > mode_number ( ) ! = Mode : : Number : : GUIDED & & ! ( copter . flightmode - > mode_number ( ) = = Mode : : Number : : AUTO & & mode ( ) = = SubMode : : NAVGUIDED ) ) {
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
//
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
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
case MAV_CMD_NAV_PAYLOAD_PLACE :
2018-04-24 20:31:01 -03:00
cmd_complete = verify_payload_place ( ) ;
break ;
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
# if NAV_GUIDED == ENABLED
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
///
/// 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 :
case MAV_CMD_DO_MOUNT_CONTROL :
case MAV_CMD_DO_GUIDED_LIMITS :
case MAV_CMD_DO_FENCE_ENABLE :
case MAV_CMD_DO_WINCH :
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
2020-09-30 04:16:16 -03:00
if ( ( copter . g2 . auto_options & ( int32_t ) Options : : AllowTakeOffWithoutRaisingThrottle ) ! = 0 ) {
2020-09-24 20:42:34 -03:00
copter . set_auto_armed ( true ) ;
}
2018-06-26 00:16:31 -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
{
// process pilot's yaw input
float target_yaw_rate = 0 ;
2020-11-12 20:15:53 -04:00
if ( ! copter . failsafe . radio & & use_pilot_yaw ( ) ) {
2018-03-22 10:25:18 -03:00
// get pilot's desired yaw rate
target_yaw_rate = get_pilot_desired_yaw_rate ( channel_yaw - > get_control_in ( ) ) ;
if ( ! is_zero ( target_yaw_rate ) ) {
2017-12-25 23:55:42 -04:00
auto_yaw . set_mode ( AUTO_YAW_HOLD ) ;
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 ( ) ) {
2019-03-14 20:45:00 -03:00
make_safe_spool_down ( ) ;
2019-02-28 02:16:19 -04:00
wp_nav - > wp_and_spline_init ( ) ;
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 ( ) ;
// call attitude controller
2017-12-25 23:55:42 -04:00
if ( auto_yaw . mode ( ) = = AUTO_YAW_HOLD ) {
2018-03-22 10:25:18 -03:00
// roll & pitch from waypoint controller, yaw rate from pilot
2021-04-13 02:39:53 -03:00
attitude_control - > input_thrust_vector_rate_heading ( wp_nav - > get_thrust_vector ( ) , target_yaw_rate ) ;
2018-03-22 10:25:18 -03:00
} else {
// roll, pitch from waypoint controller, yaw heading from auto_heading()
2021-04-13 02:39:53 -03:00
attitude_control - > input_thrust_vector_heading ( wp_nav - > get_thrust_vector ( ) , auto_yaw . yaw ( ) , auto_yaw . rate_cds ( ) ) ;
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 ( ) ) {
2019-03-14 20:45:00 -03:00
make_safe_spool_down ( ) ;
2019-07-18 08:06:09 -03:00
loiter_nav - > clear_pilot_desired_acceleration ( ) ;
2019-02-28 02:16:19 -04:00
loiter_nav - > init_target ( ) ;
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
2018-03-19 14:26:35 -03:00
land_run_horizontal_control ( ) ;
land_run_vertical_control ( ) ;
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
{
2020-04-21 08:50:25 -03:00
// process pilot's yaw input
float target_yaw_rate = 0 ;
2020-11-12 20:15:53 -04:00
if ( ! copter . failsafe . radio & & use_pilot_yaw ( ) ) {
2020-04-21 08:50:25 -03:00
// get pilot's desired yaw rate
target_yaw_rate = get_pilot_desired_yaw_rate ( channel_yaw - > get_control_in ( ) ) ;
if ( ! is_zero ( target_yaw_rate ) ) {
auto_yaw . set_mode ( AUTO_YAW_HOLD ) ;
}
}
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 ( ) ;
2017-01-24 14:37:00 -04:00
if ( auto_yaw . mode ( ) = = AUTO_YAW_HOLD ) {
// roll & pitch from waypoint controller, yaw rate from pilot
2021-04-13 02:39:53 -03:00
attitude_control - > input_thrust_vector_rate_heading ( copter . circle_nav - > get_thrust_vector ( ) , target_yaw_rate ) ;
2017-01-24 14:37:00 -04:00
} else {
// roll, pitch from waypoint controller, yaw heading from auto_heading()
2021-04-13 02:39:53 -03:00
attitude_control - > input_thrust_vector_heading ( copter . circle_nav - > get_thrust_vector ( ) , auto_yaw . yaw ( ) ) ;
2017-01-24 14:37:00 -04:00
}
2018-03-22 10:25:18 -03:00
}
# if NAV_GUIDED == ENABLED
// 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 ( ) ;
}
# endif // NAV_GUIDED
// 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 ( ) ) {
2019-03-14 20:45:00 -03:00
make_safe_spool_down ( ) ;
2019-02-28 02:16:19 -04:00
wp_nav - > wp_and_spline_init ( ) ;
2018-03-22 10:25:18 -03:00
return ;
}
// accept pilot input of yaw
float target_yaw_rate = 0 ;
2020-11-12 20:15:53 -04:00
if ( ! copter . failsafe . radio & & use_pilot_yaw ( ) ) {
2018-03-22 10:25:18 -03:00
target_yaw_rate = get_pilot_desired_yaw_rate ( channel_yaw - > get_control_in ( ) ) ;
}
// 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 ( ) ;
2021-04-13 02:39:53 -03:00
attitude_control - > input_thrust_vector_rate_heading ( wp_nav - > get_thrust_vector ( ) , target_yaw_rate ) ;
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 ( ) ) {
2018-07-25 00:39:43 -03:00
zero_throttle_and_relax_ac ( ) ;
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 ) {
2019-07-18 08:06:09 -03:00
loiter_nav - > clear_pilot_desired_acceleration ( ) ;
2018-07-25 00:39:43 -03:00
loiter_nav - > init_target ( ) ;
2021-04-13 12:06:43 -03:00
_mode = SubMode : : LOITER_TO_ALT ;
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 ) ;
// get avoidance adjusted climb rate
target_climb_rate = get_avoidance_adjusted_climbrate ( target_climb_rate ) ;
2021-05-11 01:42:02 -03:00
pos_control - > set_pos_target_z_from_climb_rate_cm ( target_climb_rate , false ) ;
2018-07-25 00:39:43 -03:00
pos_control - > update_z_controller ( ) ;
}
2018-03-22 10:25:18 -03:00
// auto_payload_place_start - initialises controller to implement placement of a load
2021-06-21 04:22:48 -03:00
void ModeAuto : : payload_place_start ( const Vector2f & destination )
2018-03-22 10:25:18 -03:00
{
2021-04-13 12:06:43 -03:00
_mode = SubMode : : NAV_PAYLOAD_PLACE ;
2018-03-22 10:25:18 -03:00
nav_payload_place . state = PayloadPlaceStateType_Calibrating_Hover_Start ;
// initialise loiter target destination
2018-03-27 23:13:37 -03:00
loiter_nav - > init_target ( destination ) ;
2018-03-22 10:25:18 -03:00
2021-05-19 11:07:38 -03:00
// initialise the vertical position controller
2021-05-11 01:42:02 -03:00
pos_control - > init_z_controller ( ) ;
2018-03-22 10:25:18 -03:00
// initialise yaw
2017-12-25 23:55:42 -04:00
auto_yaw . set_mode ( AUTO_YAW_HOLD ) ;
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
2019-05-09 23:18:49 -03:00
void ModeAuto : : payload_place_run ( )
2018-03-22 10:25:18 -03:00
{
if ( ! payload_place_run_should_run ( ) ) {
zero_throttle_and_relax_ac ( ) ;
// set target to current position
2018-09-18 23:50:37 -03:00
loiter_nav - > clear_pilot_desired_acceleration ( ) ;
2018-03-27 23:13:37 -03:00
loiter_nav - > init_target ( ) ;
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
switch ( nav_payload_place . state ) {
case PayloadPlaceStateType_FlyToLocation :
2018-08-09 09:55:54 -03:00
return wp_run ( ) ;
2018-03-22 10:25:18 -03:00
case PayloadPlaceStateType_Calibrating_Hover_Start :
case PayloadPlaceStateType_Calibrating_Hover :
return payload_place_run_loiter ( ) ;
case PayloadPlaceStateType_Descending_Start :
case PayloadPlaceStateType_Descending :
return payload_place_run_descend ( ) ;
case PayloadPlaceStateType_Releasing_Start :
case PayloadPlaceStateType_Releasing :
case PayloadPlaceStateType_Released :
case PayloadPlaceStateType_Ascending_Start :
2020-10-07 08:41:27 -03:00
return payload_place_run_loiter ( ) ;
2018-03-22 10:25:18 -03:00
case PayloadPlaceStateType_Ascending :
case PayloadPlaceStateType_Done :
2020-10-07 08:41:27 -03:00
return wp_run ( ) ;
2018-03-22 10:25:18 -03:00
}
}
2019-05-09 23:18:49 -03:00
bool ModeAuto : : payload_place_run_should_run ( )
2018-03-22 10:25:18 -03:00
{
2018-12-28 06:32:57 -04:00
// must be armed
2018-03-22 10:25:18 -03:00
if ( ! motors - > armed ( ) ) {
return false ;
}
2018-12-28 06:32:57 -04:00
// must be auto-armed
2019-05-09 23:18:49 -03:00
if ( ! copter . ap . auto_armed ) {
2018-03-22 10:25:18 -03:00
return false ;
}
// must not be landed
2019-05-09 23:18:49 -03:00
if ( copter . ap . land_complete ) {
2018-03-22 10:25:18 -03:00
return false ;
}
// interlock must be enabled (i.e. unsafe)
if ( ! motors - > get_interlock ( ) ) {
return false ;
}
return true ;
}
2019-05-09 23:18:49 -03:00
void ModeAuto : : payload_place_run_loiter ( )
2018-03-22 10:25:18 -03:00
{
// loiter...
2018-03-19 14:26:35 -03:00
land_run_horizontal_control ( ) ;
2018-03-22 10:25:18 -03:00
// call position controller
pos_control - > update_z_controller ( ) ;
}
2019-05-09 23:18:49 -03:00
void ModeAuto : : payload_place_run_descend ( )
2018-03-22 10:25:18 -03:00
{
2018-03-19 14:26:35 -03:00
land_run_horizontal_control ( ) ;
land_run_vertical_control ( ) ;
2018-03-22 10:25:18 -03:00
}
// terrain_adjusted_location: returns a Location with lat/lon from cmd
// and altitude from our current altitude adjusted for location
2019-05-09 23:18:49 -03:00
Location ModeAuto : : terrain_adjusted_location ( const AP_Mission : : Mission_Command & cmd ) const
2018-03-22 10:25:18 -03:00
{
// convert to location class
2019-01-01 22:54:31 -04:00
Location target_loc ( cmd . content . location ) ;
2018-03-22 10:25:18 -03:00
// decide if we will use terrain following
int32_t curr_terr_alt_cm , target_terr_alt_cm ;
2019-03-14 22:44:27 -03:00
if ( copter . current_loc . get_alt_cm ( Location : : AltFrame : : ABOVE_TERRAIN , curr_terr_alt_cm ) & &
target_loc . get_alt_cm ( Location : : AltFrame : : ABOVE_TERRAIN , target_terr_alt_cm ) ) {
2018-03-22 10:25:18 -03:00
curr_terr_alt_cm = MAX ( curr_terr_alt_cm , 200 ) ;
// if using terrain, set target altitude to current altitude above terrain
2019-03-14 22:44:27 -03:00
target_loc . set_alt_cm ( curr_terr_alt_cm , Location : : AltFrame : : ABOVE_TERRAIN ) ;
2018-03-22 10:25:18 -03:00
} else {
// set target altitude to current altitude above home
2019-03-14 22:44:27 -03:00
target_loc . set_alt_cm ( copter . current_loc . alt , Location : : AltFrame : : ABOVE_HOME ) ;
2018-03-22 10:25:18 -03:00
}
return target_loc ;
}
/********************************************************************************/
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 ) ;
}
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 ;
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
const Location dest_loc = loc_from_cmd ( cmd , default_loc ) ;
if ( ! wp_nav - > set_wp_destination_loc ( dest_loc ) ) {
// failure to set destination can only be because of missing terrain data
copter . failsafe_terrain_on_event ( ) ;
return ;
}
2021-04-13 12:06:43 -03:00
_mode = SubMode : : WP ;
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
if ( auto_yaw . mode ( ) ! = AUTO_YAW_ROI ) {
auto_yaw . set_mode_to_default ( false ) ;
}
}
// 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 :
case MAV_CMD_NAV_LOITER_TIME : {
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 ) ;
}
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 :
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
2019-01-01 22:54:31 -04:00
const Location target_loc = terrain_adjusted_location ( cmd ) ;
2018-03-22 10:25:18 -03:00
wp_start ( target_loc ) ;
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
{
// convert back to location
2019-01-01 22:54:31 -04:00
Location target_loc ( cmd . content . location ) ;
2018-03-22 10:25:18 -03:00
// use current location if not provided
if ( target_loc . lat = = 0 & & target_loc . lng = = 0 ) {
// To-Do: make this simpler
Vector3f temp_pos ;
2021-06-21 04:22:48 -03:00
copter . wp_nav - > get_wp_stopping_point_xy ( temp_pos . xy ( ) ) ;
2021-03-17 18:17:14 -03:00
const Location temp_loc ( temp_pos , Location : : AltFrame : : ABOVE_ORIGIN ) ;
2018-03-22 10:25:18 -03:00
target_loc . lat = temp_loc . lat ;
target_loc . lng = temp_loc . lng ;
}
// use current altitude if not provided
// To-Do: use z-axis stopping point instead of current alt
if ( target_loc . alt = = 0 ) {
// set to current altitude but in command's alt frame
int32_t curr_alt ;
2018-10-03 00:14:44 -03:00
if ( copter . current_loc . get_alt_cm ( target_loc . get_alt_frame ( ) , curr_alt ) ) {
2018-03-22 10:25:18 -03:00
target_loc . set_alt_cm ( curr_alt , target_loc . get_alt_frame ( ) ) ;
} else {
// default to current altitude as alt-above-home
2018-10-03 00:14:44 -03:00
target_loc . set_alt_cm ( copter . current_loc . alt ,
copter . current_loc . get_alt_frame ( ) ) ;
2018-03-22 10:25:18 -03:00
}
}
// start way point navigator and provide it the desired location
wp_start ( target_loc ) ;
}
// 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
{
2021-01-19 22:50:48 -04:00
const Location circle_center = loc_from_cmd ( cmd , copter . current_loc ) ;
2018-03-22 10:25:18 -03:00
// calculate radius
uint8_t circle_radius_m = HIGHBYTE ( cmd . p1 ) ; // circle radius held in high byte of p1
// move to edge of circle (verify_circle) will ensure we begin circling once we reach the edge
circle_movetoedge_start ( circle_center , circle_radius_m ) ;
}
// 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 ) ;
2021-04-13 12:06:43 -03:00
_mode = SubMode : : LOITER_TO_ALT ;
2018-07-25 00:39:43 -03:00
// 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 ( ) ) ;
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 ;
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 ;
}
2021-04-13 12:06:43 -03:00
_mode = SubMode : : WP ;
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
if ( auto_yaw . mode ( ) ! = AUTO_YAW_ROI ) {
auto_yaw . set_mode_to_default ( false ) ;
2018-03-22 10:25:18 -03:00
}
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
}
}
# if NAV_GUIDED == ENABLED
// 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
}
# endif // NAV_GUIDED
// 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
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 ) ;
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
}
/********************************************************************************/
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 ) {
2018-10-09 08:46:37 -03:00
if ( cmd . content . speed . speed_type = = 2 ) {
2019-01-24 01:02:31 -04:00
copter . wp_nav - > set_speed_up ( cmd . content . speed . target_ms * 100.0f ) ;
2018-10-09 08:46:37 -03:00
} else if ( cmd . content . speed . speed_type = = 3 ) {
2019-01-24 01:02:31 -04:00
copter . wp_nav - > set_speed_down ( cmd . content . speed . target_ms * 100.0f ) ;
2018-10-09 08:46:37 -03:00
} else {
copter . wp_nav - > set_speed_xy ( cmd . content . speed . target_ms * 100.0f ) ;
}
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
}
// 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
{
2020-07-24 14:02:40 -03:00
# if HAL_MOUNT_ENABLED
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
if ( ( copter . camera_mount . get_mount_type ( ) ! = copter . camera_mount . MountType : : Mount_Type_None ) & &
! copter . camera_mount . has_pan_control ( ) ) {
2021-07-09 05:44:07 -03:00
auto_yaw . set_yaw_angle_rate ( cmd . content . mount_control . yaw , 0.0f ) ;
2018-03-22 10:25:18 -03:00
}
2021-03-09 23:28:29 -04:00
// pass the target angles to the camera mount
2018-03-22 10:25:18 -03:00
copter . camera_mount . set_angle_targets ( cmd . content . mount_control . roll , cmd . content . mount_control . pitch , cmd . content . mount_control . yaw ) ;
# endif
}
# if WINCH_ENABLED == ENABLED
// 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
// 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
nav_payload_place . state = PayloadPlaceStateType_FlyToLocation ;
2019-01-01 22:54:31 -04:00
const Location target_loc = terrain_adjusted_location ( cmd ) ;
2018-03-22 10:25:18 -03:00
wp_start ( target_loc ) ;
} else {
nav_payload_place . state = PayloadPlaceStateType_Calibrating_Hover_Start ;
// initialise placing controller
payload_place_start ( ) ;
}
nav_payload_place . descend_max = cmd . p1 ;
}
// 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
{
// have we reached our target altitude?
2019-04-07 12:31:20 -03:00
const bool reached_wp_dest = copter . wp_nav - > reached_wp_destination ( ) ;
2021-02-06 23:29:33 -04:00
# if LANDING_GEAR_ENABLED == ENABLED
2021-01-10 22:56:52 -04:00
// if we have reached our destination
2019-04-07 12:31:20 -03:00
if ( reached_wp_dest ) {
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
return reached_wp_dest ;
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 ( ) ) {
// get destination so we can use it for loiter target
2021-06-21 04:22:48 -03:00
const Vector2f & dest = copter . wp_nav - > get_wp_destination ( ) . xy ( ) ;
2018-03-22 10:25:18 -03:00
// initialise landing controller
land_start ( dest ) ;
// 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 ) ;
2020-03-03 23:29:14 -04:00
if ( retval & & ! mission . continue_after_land ( ) & & copter . motors - > armed ( ) ) {
/*
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 ;
}
# define NAV_PAYLOAD_PLACE_DEBUGGING 0
# if NAV_PAYLOAD_PLACE_DEBUGGING
# include <stdio.h>
# define debug(fmt, args ...) do {::fprintf(stderr,"%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); } while(0)
# else
# define debug(fmt, args ...)
# endif
// verify_payload_place - returns true if placing has been completed
2019-05-09 23:18:49 -03:00
bool ModeAuto : : verify_payload_place ( )
2018-03-22 10:25:18 -03:00
{
const uint16_t hover_throttle_calibrate_time = 2000 ; // milliseconds
const uint16_t descend_throttle_calibrate_time = 2000 ; // milliseconds
const float hover_throttle_placed_fraction = 0.7 ; // i.e. if throttle is less than 70% of hover we have placed
const float descent_throttle_placed_fraction = 0.9 ; // i.e. if throttle is less than 90% of descent throttle we have placed
const uint16_t placed_time = 500 ; // how long we have to be below a throttle threshold before considering placed
const float current_throttle_level = motors - > get_throttle ( ) ;
2020-10-07 08:41:27 -03:00
const uint32_t now = AP_HAL : : millis ( ) ;
2018-03-22 10:25:18 -03:00
// if we discover we've landed then immediately release the load:
2019-05-09 23:18:49 -03:00
if ( copter . ap . land_complete ) {
2018-03-22 10:25:18 -03:00
switch ( nav_payload_place . state ) {
case PayloadPlaceStateType_FlyToLocation :
case PayloadPlaceStateType_Calibrating_Hover_Start :
case PayloadPlaceStateType_Calibrating_Hover :
case PayloadPlaceStateType_Descending_Start :
case PayloadPlaceStateType_Descending :
2020-10-07 08:41:27 -03:00
gcs ( ) . send_text ( MAV_SEVERITY_INFO , " PayloadPlace: landed " ) ;
2018-03-22 10:25:18 -03:00
nav_payload_place . state = PayloadPlaceStateType_Releasing_Start ;
break ;
case PayloadPlaceStateType_Releasing_Start :
case PayloadPlaceStateType_Releasing :
case PayloadPlaceStateType_Released :
case PayloadPlaceStateType_Ascending_Start :
case PayloadPlaceStateType_Ascending :
case PayloadPlaceStateType_Done :
break ;
}
}
switch ( nav_payload_place . state ) {
case PayloadPlaceStateType_FlyToLocation :
if ( ! copter . wp_nav - > reached_wp_destination ( ) ) {
return false ;
}
2018-08-09 09:55:54 -03:00
payload_place_start ( ) ;
return false ;
2018-03-22 10:25:18 -03:00
case PayloadPlaceStateType_Calibrating_Hover_Start :
// hover for 1 second to get an idea of what our hover
// throttle looks like
debug ( " Calibrate start " ) ;
nav_payload_place . hover_start_timestamp = now ;
nav_payload_place . state = PayloadPlaceStateType_Calibrating_Hover ;
FALLTHROUGH ;
case PayloadPlaceStateType_Calibrating_Hover : {
if ( now - nav_payload_place . hover_start_timestamp < hover_throttle_calibrate_time ) {
// still calibrating...
debug ( " Calibrate Timer: %d " , now - nav_payload_place . hover_start_timestamp ) ;
return false ;
}
// we have a valid calibration. Hopefully.
nav_payload_place . hover_throttle_level = current_throttle_level ;
const float hover_throttle_delta = fabsf ( nav_payload_place . hover_throttle_level - motors - > get_throttle_hover ( ) ) ;
gcs ( ) . send_text ( MAV_SEVERITY_INFO , " hover throttle delta: %f " , static_cast < double > ( hover_throttle_delta ) ) ;
nav_payload_place . state = PayloadPlaceStateType_Descending_Start ;
}
FALLTHROUGH ;
case PayloadPlaceStateType_Descending_Start :
nav_payload_place . descend_start_timestamp = now ;
nav_payload_place . descend_start_altitude = inertial_nav . get_altitude ( ) ;
nav_payload_place . descend_throttle_level = 0 ;
nav_payload_place . state = PayloadPlaceStateType_Descending ;
FALLTHROUGH ;
case PayloadPlaceStateType_Descending :
// make sure we don't descend too far:
debug ( " descended: %f cm (%f cm max) " , ( nav_payload_place . descend_start_altitude - inertial_nav . get_altitude ( ) ) , nav_payload_place . descend_max ) ;
if ( ! is_zero ( nav_payload_place . descend_max ) & &
nav_payload_place . descend_start_altitude - inertial_nav . get_altitude ( ) > nav_payload_place . descend_max ) {
nav_payload_place . state = PayloadPlaceStateType_Ascending ;
gcs ( ) . send_text ( MAV_SEVERITY_WARNING , " Reached maximum descent " ) ;
return false ; // we'll do any cleanups required next time through the loop
}
// see if we've been descending long enough to calibrate a descend-throttle-level:
if ( is_zero ( nav_payload_place . descend_throttle_level ) & &
now - nav_payload_place . descend_start_timestamp > descend_throttle_calibrate_time ) {
nav_payload_place . descend_throttle_level = current_throttle_level ;
}
// watch the throttle to determine whether the load has been placed
// debug("hover ratio: %f descend ratio: %f\n", current_throttle_level/nav_payload_place.hover_throttle_level, ((nav_payload_place.descend_throttle_level == 0) ? -1.0f : current_throttle_level/nav_payload_place.descend_throttle_level));
if ( current_throttle_level / nav_payload_place . hover_throttle_level > hover_throttle_placed_fraction & &
( is_zero ( nav_payload_place . descend_throttle_level ) | |
current_throttle_level / nav_payload_place . descend_throttle_level > descent_throttle_placed_fraction ) ) {
// throttle is above both threshold ratios (or above hover threshold ration and descent threshold ratio not yet valid)
nav_payload_place . place_start_timestamp = 0 ;
return false ;
}
if ( nav_payload_place . place_start_timestamp = = 0 ) {
// we've only just now hit the correct throttle level
nav_payload_place . place_start_timestamp = now ;
return false ;
} else if ( now - nav_payload_place . place_start_timestamp < placed_time ) {
// keep going down....
debug ( " Place Timer: %d " , now - nav_payload_place . place_start_timestamp ) ;
return false ;
}
nav_payload_place . state = PayloadPlaceStateType_Releasing_Start ;
FALLTHROUGH ;
case PayloadPlaceStateType_Releasing_Start :
# if GRIPPER_ENABLED == ENABLED
if ( g2 . gripper . valid ( ) ) {
gcs ( ) . send_text ( MAV_SEVERITY_INFO , " Releasing the gripper " ) ;
g2 . gripper . release ( ) ;
} else {
gcs ( ) . send_text ( MAV_SEVERITY_INFO , " Gripper not valid " ) ;
nav_payload_place . state = PayloadPlaceStateType_Ascending_Start ;
break ;
}
# else
gcs ( ) . send_text ( MAV_SEVERITY_INFO , " Gripper code disabled " ) ;
# endif
nav_payload_place . state = PayloadPlaceStateType_Releasing ;
FALLTHROUGH ;
case PayloadPlaceStateType_Releasing :
# if GRIPPER_ENABLED == ENABLED
if ( g2 . gripper . valid ( ) & & ! g2 . gripper . released ( ) ) {
return false ;
}
# endif
nav_payload_place . state = PayloadPlaceStateType_Released ;
FALLTHROUGH ;
case PayloadPlaceStateType_Released : {
nav_payload_place . state = PayloadPlaceStateType_Ascending_Start ;
}
FALLTHROUGH ;
case PayloadPlaceStateType_Ascending_Start : {
2021-03-17 18:17:14 -03:00
Location target_loc ( inertial_nav . get_position ( ) , Location : : AltFrame : : ABOVE_ORIGIN ) ;
2018-03-22 10:25:18 -03:00
target_loc . alt = nav_payload_place . descend_start_altitude ;
wp_start ( target_loc ) ;
nav_payload_place . state = PayloadPlaceStateType_Ascending ;
}
FALLTHROUGH ;
case PayloadPlaceStateType_Ascending :
if ( ! copter . wp_nav - > reached_wp_destination ( ) ) {
return false ;
}
nav_payload_place . state = PayloadPlaceStateType_Done ;
FALLTHROUGH ;
case PayloadPlaceStateType_Done :
return true ;
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
return true ;
}
// should never get here
return true ;
}
# undef debug
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
{
2018-03-22 10:25:18 -03:00
// set yaw mode if it has been changed (the waypoint controller often retakes control of yaw as it executes a new waypoint command)
2017-12-25 23:55:42 -04:00
if ( auto_yaw . mode ( ) ! = AUTO_YAW_FIXED ) {
auto_yaw . set_mode ( AUTO_YAW_FIXED ) ;
2018-03-22 10:25:18 -03:00
}
// check if we are within 2 degrees of the target heading
2018-10-02 22:47:58 -03:00
return ( fabsf ( wrap_180_cd ( ahrs . yaw_sensor - auto_yaw . yaw ( ) ) ) < = 200 ) ;
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
2021-04-13 12:06:43 -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
}
2018-03-22 10:25:18 -03:00
// check if we have completed circling
return fabsf ( copter . circle_nav - > get_angle_total ( ) / M_2PI ) > = LOWBYTE ( cmd . p1 ) ;
}
// 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
2018-03-22 10:25:18 -03:00
# if NAV_GUIDED == ENABLED
// 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 ( ) ;
}
# endif // NAV_GUIDED
// 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
}
2018-02-21 22:06:07 -04:00
# endif