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
2017-12-10 23:51:13 -04:00
bool Copter : : ModeAuto : : init ( bool ignore_checks )
2014-01-23 01:14:58 -04:00
{
2018-02-07 22:21:09 -04:00
if ( ( copter . position_ok ( ) & & copter . mission . num_commands ( ) > 1 ) | | ignore_checks ) {
2016-03-21 00:45:50 -03:00
_mode = Auto_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)
2018-02-07 22:21:09 -04:00
if ( motors - > armed ( ) & & ap . land_complete & & ! copter . 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
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-05-15 04:20:02 -03:00
// start/resume the mission (based on MIS_RESTART parameter)
2018-02-07 22:21:09 -04:00
copter . mission . start_or_resume ( ) ;
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 ;
}
}
// auto_run - runs the auto controller
// should be called at 100hz or more
// relies on run_autopilot being called at 10hz which handles decision making and non-navigation related commands
2017-12-10 23:51:13 -04:00
void Copter : : ModeAuto : : run ( )
2014-01-23 01:14:58 -04:00
{
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
2014-01-25 04:25:17 -04:00
case Auto_TakeOff :
2016-03-21 00:45:50 -03:00
takeoff_run ( ) ;
2014-01-24 22:37:42 -04:00
break ;
2014-01-25 04:25:17 -04:00
case Auto_WP :
2014-04-16 04:23:24 -03:00
case Auto_CircleMoveToEdge :
2016-03-21 00:45:50 -03:00
wp_run ( ) ;
2014-01-24 22:37:42 -04:00
break ;
2014-01-25 04:25:17 -04:00
case Auto_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
2014-01-27 23:20:39 -04:00
case Auto_RTL :
2016-03-21 00:45:50 -03:00
rtl_run ( ) ;
2014-01-27 23:20:39 -04:00
break ;
2014-01-27 10:43:48 -04:00
case Auto_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
case Auto_Spline :
2016-03-21 00:45:50 -03:00
spline_run ( ) ;
2014-03-22 00:48:54 -03:00
break ;
2014-05-23 02:29:08 -03:00
case Auto_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
case Auto_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
case Auto_NavPayloadPlace :
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
}
}
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
bool Copter : : ModeAuto : : loiter_start ( )
{
// return failure if GPS is bad
if ( ! copter . position_ok ( ) ) {
return false ;
}
_mode = Auto_Loiter ;
// 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
void Copter : : ModeAuto : : rtl_start ( )
{
_mode = Auto_RTL ;
// 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
2017-12-10 23:51:13 -04:00
void Copter : : ModeAuto : : takeoff_start ( const Location & dest_loc )
2014-01-24 22:37:42 -04:00
{
2016-03-21 00:45:50 -03:00
_mode = Auto_TakeOff ;
2014-01-24 22:37:42 -04:00
2015-10-05 05:23:58 -03:00
// convert location to class
Location_Class dest ( dest_loc ) ;
// 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 ;
if ( ! dest . get_alt_cm ( Location_Class : : ALT_FRAME_ABOVE_HOME , alt_target ) ) {
// this failure could only happen if take-off alt was specified as an alt-above terrain and we have no terrain data
2018-02-07 22:21:09 -04:00
copter . Log_Write_Error ( ERROR_SUBSYSTEM_TERRAIN , ERROR_CODE_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 ) {
dest . set_alt_cm ( copter . current_loc . alt , Location_Class : : ALT_FRAME_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 ) {
2016-04-28 07:53:45 -03:00
dest . set_alt_cm ( 100 , Location_Class : : ALT_FRAME_ABOVE_HOME ) ;
2015-10-05 05:23:58 -03:00
}
// set waypoint controller target
2017-01-09 03:31:26 -04:00
if ( ! wp_nav - > set_wp_destination ( 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-02-07 22:21:09 -04:00
copter . auto_takeoff_set_start_alt ( ) ;
2014-01-24 22:37:42 -04:00
}
// auto_wp_start - initialises waypoint controller to implement flying to a particular destination
2017-12-10 23:51:13 -04:00
void Copter : : ModeAuto : : wp_start ( const Vector3f & destination )
2014-01-24 22:37:42 -04:00
{
2016-03-21 00:45:50 -03:00
_mode = Auto_WP ;
2014-01-24 22:37:42 -04:00
2016-04-22 08:45:28 -03:00
// initialise wpnav (no need to check return status because terrain data is not used)
2017-01-09 03:31:26 -04:00
wp_nav - > set_wp_destination ( destination , false ) ;
2014-01-24 22:37:42 -04:00
// initialise yaw
2014-02-18 08:35:29 -04:00
// 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 ) ;
2014-02-18 08:35:29 -04:00
}
2014-01-24 22:37:42 -04:00
}
2014-01-23 01:14:58 -04:00
2015-08-16 16:10:23 -03:00
// auto_wp_start - initialises waypoint controller to implement flying to a particular destination
2017-12-10 23:51:13 -04:00
void Copter : : ModeAuto : : wp_start ( const Location_Class & dest_loc )
2015-08-16 16:10:23 -03:00
{
2016-03-21 00:45:50 -03:00
_mode = Auto_WP ;
2015-08-16 16:10:23 -03:00
// send target to waypoint controller
2017-01-09 03:31:26 -04:00
if ( ! wp_nav - > set_wp_destination ( 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
}
// 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
2017-12-10 23:51:13 -04:00
void Copter : : ModeAuto : : land_start ( )
2014-01-24 22:37:42 -04:00
{
2014-01-25 00:40:32 -04:00
// set target to stopping point
Vector3f 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
2017-12-10 23:51:13 -04:00
void Copter : : ModeAuto : : land_start ( const Vector3f & destination )
2014-01-24 22:37:42 -04:00
{
2016-03-21 00:45:50 -03:00
_mode = Auto_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
2016-07-07 21:41:38 -03:00
// initialise position and desired velocity
2017-01-09 03:31:26 -04:00
if ( ! pos_control - > is_active_z ( ) ) {
pos_control - > set_alt_target ( inertial_nav . get_altitude ( ) ) ;
pos_control - > set_desired_velocity_z ( inertial_nav . get_velocity_z ( ) ) ;
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 ) ;
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
2017-12-10 23:51:13 -04:00
void Copter : : ModeAuto : : circle_movetoedge_start ( const Location_Class & circle_center , float radius_m )
2014-04-16 04:23:24 -03:00
{
2016-03-09 07:21:08 -04:00
// convert location to vector from ekf origin
Vector3f circle_center_neu ;
if ( ! circle_center . get_vector_from_origin_NEU ( circle_center_neu ) ) {
// default to current position and log error
circle_center_neu = inertial_nav . get_position ( ) ;
2018-02-07 22:21:09 -04:00
copter . Log_Write_Error ( ERROR_SUBSYSTEM_NAVIGATION , ERROR_CODE_FAILED_CIRCLE_INIT ) ;
2016-03-09 07:21:08 -04:00
}
2018-02-07 22:21:09 -04:00
copter . circle_nav - > set_center ( circle_center_neu ) ;
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
2016-03-21 00:45:50 -03:00
_mode = Auto_CircleMoveToEdge ;
2016-03-09 07:21:08 -04:00
// convert circle_edge_neu to Location_Class
Location_Class circle_edge ( circle_edge_neu ) ;
// 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
2017-01-09 03:31:26 -04:00
if ( ! wp_nav - > set_wp_destination ( 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
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 ) ;
2018-02-07 22:21:09 -04:00
if ( dist_to_center > copter . circle_nav - > get_radius ( ) & & dist_to_center > 500 ) {
2017-12-25 23:55:42 -04:00
auto_yaw . set_mode_to_default ( false ) ;
2016-03-09 07:21:08 -04:00
} else {
// vehicle is within circle so hold yaw to avoid spinning as we move to edge of circle
2017-12-25 23:55:42 -04:00
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
2017-12-10 23:51:13 -04:00
void Copter : : ModeAuto : : circle_start ( )
2014-01-27 10:43:48 -04:00
{
2016-03-21 00:45:50 -03:00
_mode = Auto_Circle ;
2014-01-27 23:20:39 -04:00
2014-04-16 04:23:24 -03:00
// initialise circle controller
2018-02-07 22:21:09 -04:00
copter . circle_nav - > init ( copter . circle_nav - > get_center ( ) ) ;
2014-01-27 10:43:48 -04:00
}
2018-03-22 10:25:18 -03:00
// auto_spline_start - initialises waypoint controller to implement flying to a particular destination using the spline controller
// seg_end_type can be SEGMENT_END_STOP, SEGMENT_END_STRAIGHT or SEGMENT_END_SPLINE. If Straight or Spline the next_destination should be provided
void Copter : : ModeAuto : : spline_start ( const Location_Class & destination , bool stopped_at_start ,
AC_WPNav : : spline_segment_end_type seg_end_type ,
const Location_Class & next_destination )
{
_mode = Auto_Spline ;
// initialise wpnav
if ( ! wp_nav - > set_spline_destination ( destination , stopped_at_start , seg_end_type , next_destination ) ) {
// failure to set destination can only be because of missing terrain data
copter . failsafe_terrain_on_event ( ) ;
return ;
}
// 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 ) ;
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
void Copter : : ModeAuto : : nav_guided_start ( )
{
_mode = Auto_NavGuided ;
// 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
bool Copter : : ModeAuto : : landing_gear_should_be_deployed ( ) const
{
switch ( _mode ) {
case Auto_Land :
return true ;
case Auto_RTL :
return copter . mode_rtl . landing_gear_should_be_deployed ( ) ;
default :
return false ;
}
return false ;
}
// auto_payload_place_start - initialises controller to implement a placing
void Copter : : ModeAuto : : payload_place_start ( )
{
// set target to stopping point
Vector3f 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 ) ;
}
// start_command - this function will be called when the ap_mission lib wishes to start a new command
bool Copter : : ModeAuto : : start_command ( const AP_Mission : : Mission_Command & cmd )
{
// To-Do: logging when new commands start/end
if ( copter . should_log ( MASK_LOG_CMD ) ) {
copter . DataFlash . Log_Write_Mission_Cmd ( copter . mission , cmd ) ;
}
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_PAYLOAD_PLACE : // 94 place at Waypoint
do_payload_place ( 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 ;
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
case MAV_CMD_NAV_DELAY : // 94 Delay the next navigation command
do_nav_delay ( cmd ) ;
break ;
//
// 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_SERVO :
copter . ServoRelayEvents . do_set_servo ( cmd . content . servo . channel , cmd . content . servo . pwm ) ;
break ;
case MAV_CMD_DO_SET_RELAY :
copter . ServoRelayEvents . do_set_relay ( cmd . content . relay . num , cmd . content . relay . state ) ;
break ;
case MAV_CMD_DO_REPEAT_SERVO :
copter . ServoRelayEvents . do_repeat_servo ( cmd . content . repeat_servo . channel , cmd . content . repeat_servo . pwm ,
cmd . content . repeat_servo . repeat_count , cmd . content . repeat_servo . cycle_time * 1000.0f ) ;
break ;
case MAV_CMD_DO_REPEAT_RELAY :
copter . ServoRelayEvents . do_repeat_relay ( cmd . content . repeat_relay . num , cmd . content . repeat_relay . repeat_count ,
cmd . content . repeat_relay . cycle_time * 1000.0f ) ;
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 CAMERA == ENABLED
case MAV_CMD_DO_CONTROL_VIDEO : // Control on-board camera capturing. |Camera ID (-1 for all)| Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw| Transmission mode: 0: video stream, >0: single images every n seconds (decimal)| Recording: 0: disabled, 1: enabled compressed, 2: enabled raw| Empty| Empty| Empty|
break ;
case MAV_CMD_DO_DIGICAM_CONFIGURE : // Mission command to configure an on-board camera controller system. |Modes: P, TV, AV, M, Etc| Shutter speed: Divisor number for one second| Aperture: F stop number| ISO number e.g. 80, 100, 200, Etc| Exposure type enumerator| Command Identity| Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off)|
do_digicam_configure ( cmd ) ;
break ;
case MAV_CMD_DO_DIGICAM_CONTROL : // Mission command to control an on-board camera controller system. |Session control e.g. show/hide lens| Zoom's absolute position| Zooming step value to offset zoom from the current position| Focus Locking, Unlocking or Re-locking| Shooting Command| Command Identity| Empty|
do_digicam_control ( cmd ) ;
break ;
case MAV_CMD_DO_SET_CAM_TRIGG_DIST :
copter . camera . set_trigger_distance ( cmd . content . cam_trigg_dist . meters ) ;
break ;
# endif
# if PARACHUTE == ENABLED
case MAV_CMD_DO_PARACHUTE : // Mission command to configure or release parachute
do_parachute ( cmd ) ;
break ;
# endif
# if GRIPPER_ENABLED == ENABLED
case MAV_CMD_DO_GRIPPER : // Mission command to control gripper
do_gripper ( cmd ) ;
break ;
# endif
# 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
default :
// do nothing with unrecognized MAVLink messages
break ;
}
// always return success
return true ;
}
// verify_command_callback - callback function called from ap-mission at 10hz or higher when a command is being run
// we double check that the flight mode is AUTO to avoid the possibility of ap-mission triggering actions while we're not in AUTO mode
bool Copter : : ModeAuto : : verify_command_callback ( const AP_Mission : : Mission_Command & cmd )
{
if ( copter . flightmode = = & copter . mode_auto ) {
bool cmd_complete = verify_command ( cmd ) ;
// send message to GCS
if ( cmd_complete ) {
gcs ( ) . send_mission_item_reached_message ( cmd . index ) ;
}
return cmd_complete ;
}
return false ;
}
// exit_mission - function that is called once the mission completes
void Copter : : ModeAuto : : exit_mission ( )
{
// play a tone
AP_Notify : : events . mission_complete = 1 ;
// if we are not on the ground switch to loiter or land
if ( ! ap . land_complete ) {
// try to enter loiter but if that fails land
if ( ! loiter_start ( ) ) {
set_mode ( LAND , MODE_REASON_MISSION_END ) ;
}
} else {
// if we've landed it's safe to disarm
copter . init_disarm_motors ( ) ;
}
}
// do_guided - start guided mode
bool Copter : : ModeAuto : : do_guided ( const AP_Mission : : Mission_Command & cmd )
{
// only process guided waypoint if we are in guided mode
if ( copter . control_mode ! = GUIDED & & ! ( copter . control_mode = = AUTO & & mode ( ) = = Auto_NavGuided ) ) {
return false ;
}
// switch to handle different commands
switch ( cmd . id ) {
case MAV_CMD_NAV_WAYPOINT :
{
// set wp_nav's destination
Location_Class dest ( cmd . content . location ) ;
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 ;
}
uint32_t Copter : : ModeAuto : : wp_distance ( ) const
{
return wp_nav - > get_wp_distance_to_destination ( ) ;
}
int32_t Copter : : ModeAuto : : wp_bearing ( ) const
{
return wp_nav - > get_wp_bearing_to_destination ( ) ;
}
2018-05-11 08:59:05 -03:00
bool Copter : : ModeAuto : : get_wp ( Location_Class & destination )
{
switch ( _mode ) {
case Auto_NavGuided :
return copter . mode_guided . get_wp ( destination ) ;
case Auto_WP :
return wp_nav - > get_wp_destination ( destination ) ;
default :
return false ;
}
}
2018-03-22 10:25:18 -03:00
// update mission
void Copter : : ModeAuto : : run_autopilot ( )
{
copter . mission . update ( ) ;
}
/*******************************************************************************
Verify command Handlers
Each type of mission element has a " verify " operation . The verify
operation returns true when the mission element has completed and we
should move onto the next mission element .
Return true if we do not recognize the command so that we move on to the next command
* * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * */
bool Copter : : ModeAuto : : verify_command ( const AP_Mission : : Mission_Command & cmd )
{
switch ( cmd . id ) {
//
// navigation commands
//
case MAV_CMD_NAV_TAKEOFF :
return verify_takeoff ( ) ;
case MAV_CMD_NAV_WAYPOINT :
return verify_nav_wp ( cmd ) ;
case MAV_CMD_NAV_LAND :
return verify_land ( ) ;
case MAV_CMD_NAV_PAYLOAD_PLACE :
return verify_payload_place ( ) ;
case MAV_CMD_NAV_LOITER_UNLIM :
return verify_loiter_unlimited ( ) ;
case MAV_CMD_NAV_LOITER_TURNS :
return verify_circle ( cmd ) ;
case MAV_CMD_NAV_LOITER_TIME :
return verify_loiter_time ( ) ;
case MAV_CMD_NAV_RETURN_TO_LAUNCH :
return verify_RTL ( ) ;
case MAV_CMD_NAV_SPLINE_WAYPOINT :
return verify_spline_wp ( cmd ) ;
# if NAV_GUIDED == ENABLED
case MAV_CMD_NAV_GUIDED_ENABLE :
return verify_nav_guided_enable ( cmd ) ;
# endif
case MAV_CMD_NAV_DELAY :
return verify_nav_delay ( cmd ) ;
///
/// conditional commands
///
case MAV_CMD_CONDITION_DELAY :
return verify_wait_delay ( ) ;
case MAV_CMD_CONDITION_DISTANCE :
return verify_within_distance ( ) ;
case MAV_CMD_CONDITION_YAW :
return verify_yaw ( ) ;
// do commands (always return true)
case MAV_CMD_DO_CHANGE_SPEED :
case MAV_CMD_DO_SET_HOME :
case MAV_CMD_DO_SET_SERVO :
case MAV_CMD_DO_SET_RELAY :
case MAV_CMD_DO_REPEAT_SERVO :
case MAV_CMD_DO_REPEAT_RELAY :
case MAV_CMD_DO_SET_ROI :
case MAV_CMD_DO_MOUNT_CONTROL :
case MAV_CMD_DO_CONTROL_VIDEO :
case MAV_CMD_DO_DIGICAM_CONFIGURE :
case MAV_CMD_DO_DIGICAM_CONTROL :
case MAV_CMD_DO_SET_CAM_TRIGG_DIST :
case MAV_CMD_DO_PARACHUTE : // assume parachute was released successfully
case MAV_CMD_DO_GRIPPER :
case MAV_CMD_DO_GUIDED_LIMITS :
case MAV_CMD_DO_FENCE_ENABLE :
case MAV_CMD_DO_WINCH :
return true ;
default :
// error message
gcs ( ) . send_text ( MAV_SEVERITY_WARNING , " Skipping invalid cmd #%i " , cmd . id ) ;
// return true if we do not recognize the command so that we move on to the next command
return true ;
}
}
// auto_takeoff_run - takeoff in auto mode
// called by auto_run at 100hz or more
void Copter : : ModeAuto : : takeoff_run ( )
{
// if not auto armed or motor interlock not enabled set throttle to zero and exit immediately
if ( ! motors - > armed ( ) | | ! ap . auto_armed | | ! motors - > get_interlock ( ) ) {
// initialise wpnav targets
wp_nav - > shift_wp_origin_to_current_pos ( ) ;
zero_throttle_and_relax_ac ( ) ;
// clear i term when we're taking off
set_throttle_takeoff ( ) ;
return ;
}
// process pilot's yaw input
float target_yaw_rate = 0 ;
if ( ! copter . failsafe . radio ) {
// get pilot's desired yaw rate
target_yaw_rate = get_pilot_desired_yaw_rate ( channel_yaw - > get_control_in ( ) ) ;
}
# if FRAME_CONFIG == HELI_FRAME
// helicopters stay in landed state until rotor speed runup has finished
if ( motors - > rotor_runup_complete ( ) ) {
set_land_complete ( false ) ;
} else {
// initialise wpnav targets
wp_nav - > shift_wp_origin_to_current_pos ( ) ;
}
# else
set_land_complete ( false ) ;
# endif
// set motors to full range
motors - > set_desired_spool_state ( AP_Motors : : DESIRED_THROTTLE_UNLIMITED ) ;
// run waypoint controller
copter . failsafe_terrain_set_status ( wp_nav - > update_wpnav ( ) ) ;
// call z-axis position controller (wpnav should have already updated it's alt target)
pos_control - > update_z_controller ( ) ;
// call attitude controller
copter . auto_takeoff_attitude_run ( target_yaw_rate ) ;
}
// auto_wp_run - runs the auto waypoint controller
// called by auto_run at 100hz or more
void Copter : : ModeAuto : : wp_run ( )
{
// if not auto armed or motor interlock not enabled set throttle to zero and exit immediately
if ( ! motors - > armed ( ) | | ! ap . auto_armed | | ! motors - > get_interlock ( ) ) {
// To-Do: reset waypoint origin to current location because copter is probably on the ground so we don't want it lurching left or right on take-off
// (of course it would be better if people just used take-off)
zero_throttle_and_relax_ac ( ) ;
// clear i term when we're taking off
set_throttle_takeoff ( ) ;
return ;
}
// process pilot's yaw input
float target_yaw_rate = 0 ;
if ( ! copter . failsafe . radio ) {
// 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
}
}
// set motors to full range
motors - > set_desired_spool_state ( AP_Motors : : DESIRED_THROTTLE_UNLIMITED ) ;
// run waypoint controller
copter . failsafe_terrain_set_status ( wp_nav - > update_wpnav ( ) ) ;
// call z-axis position controller (wpnav should have already updated it's alt target)
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
attitude_control - > input_euler_angle_roll_pitch_euler_rate_yaw ( wp_nav - > get_roll ( ) , wp_nav - > get_pitch ( ) , target_yaw_rate ) ;
} else {
// roll, pitch from waypoint controller, yaw heading from auto_heading()
2017-12-25 23:55:42 -04:00
attitude_control - > input_euler_angle_roll_pitch_yaw ( wp_nav - > get_roll ( ) , wp_nav - > get_pitch ( ) , auto_yaw . yaw ( ) , true ) ;
2018-03-22 10:25:18 -03:00
}
}
// auto_spline_run - runs the auto spline controller
// called by auto_run at 100hz or more
void Copter : : ModeAuto : : spline_run ( )
{
// if not auto armed or motor interlock not enabled set throttle to zero and exit immediately
if ( ! motors - > armed ( ) | | ! ap . auto_armed | | ! motors - > get_interlock ( ) ) {
// To-Do: reset waypoint origin to current location because copter is probably on the ground so we don't want it lurching left or right on take-off
// (of course it would be better if people just used take-off)
zero_throttle_and_relax_ac ( ) ;
// clear i term when we're taking off
set_throttle_takeoff ( ) ;
return ;
}
// process pilot's yaw input
float target_yaw_rate = 0 ;
if ( ! copter . failsafe . radio ) {
// get pilot's desired yaw rat
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
}
}
// set motors to full range
motors - > set_desired_spool_state ( AP_Motors : : DESIRED_THROTTLE_UNLIMITED ) ;
// run waypoint controller
wp_nav - > update_spline ( ) ;
// call z-axis position controller (wpnav should have already updated it's alt target)
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
attitude_control - > input_euler_angle_roll_pitch_euler_rate_yaw ( wp_nav - > get_roll ( ) , wp_nav - > get_pitch ( ) , target_yaw_rate ) ;
} else {
// roll, pitch from waypoint controller, yaw heading from auto_heading()
2017-12-25 23:55:42 -04:00
attitude_control - > input_euler_angle_roll_pitch_yaw ( wp_nav - > get_roll ( ) , wp_nav - > get_pitch ( ) , auto_yaw . yaw ( ) , true ) ;
2018-03-22 10:25:18 -03:00
}
}
// auto_land_run - lands in auto mode
// called by auto_run at 100hz or more
void Copter : : ModeAuto : : land_run ( )
{
// if not auto armed or landed or motor interlock not enabled set throttle to zero and exit immediately
if ( ! motors - > armed ( ) | | ! ap . auto_armed | | ap . land_complete | | ! motors - > get_interlock ( ) ) {
zero_throttle_and_relax_ac ( ) ;
// set target to current position
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
motors - > set_desired_spool_state ( AP_Motors : : DESIRED_THROTTLE_UNLIMITED ) ;
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
void Copter : : ModeAuto : : rtl_run ( )
{
// 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
void Copter : : ModeAuto : : circle_run ( )
{
2014-01-27 10:43:48 -04:00
// call circle controller
2018-02-07 22:21:09 -04:00
copter . circle_nav - > update ( ) ;
2014-01-27 10:43:48 -04:00
2018-03-22 10:25:18 -03:00
// call z-axis position controller
pos_control - > update_z_controller ( ) ;
// roll & pitch from waypoint controller, yaw rate from pilot
attitude_control - > input_euler_angle_roll_pitch_yaw ( copter . circle_nav - > get_roll ( ) , copter . circle_nav - > get_pitch ( ) , copter . circle_nav - > get_yaw ( ) , true ) ;
}
# if NAV_GUIDED == ENABLED
// auto_nav_guided_run - allows control by external navigation controller
// called by auto_run at 100hz or more
void Copter : : ModeAuto : : nav_guided_run ( )
{
// 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
void Copter : : ModeAuto : : loiter_run ( )
{
// if not auto armed or motor interlock not enabled set throttle to zero and exit immediately
if ( ! motors - > armed ( ) | | ! ap . auto_armed | | ap . land_complete | | ! motors - > get_interlock ( ) ) {
zero_throttle_and_relax_ac ( ) ;
return ;
}
// accept pilot input of yaw
float target_yaw_rate = 0 ;
if ( ! copter . failsafe . radio ) {
target_yaw_rate = get_pilot_desired_yaw_rate ( channel_yaw - > get_control_in ( ) ) ;
}
// set motors to full range
motors - > set_desired_spool_state ( AP_Motors : : DESIRED_THROTTLE_UNLIMITED ) ;
// run waypoint and z-axis position controller
copter . failsafe_terrain_set_status ( wp_nav - > update_wpnav ( ) ) ;
pos_control - > update_z_controller ( ) ;
attitude_control - > input_euler_angle_roll_pitch_euler_rate_yaw ( wp_nav - > get_roll ( ) , wp_nav - > get_pitch ( ) , target_yaw_rate ) ;
}
// auto_payload_place_start - initialises controller to implement placement of a load
void Copter : : ModeAuto : : payload_place_start ( const Vector3f & destination )
{
_mode = Auto_NavPayloadPlace ;
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
// initialise position and desired velocity
if ( ! pos_control - > is_active_z ( ) ) {
pos_control - > set_alt_target ( inertial_nav . get_altitude ( ) ) ;
pos_control - > set_desired_velocity_z ( inertial_nav . get_velocity_z ( ) ) ;
}
// 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
void Copter : : ModeAuto : : payload_place_run ( )
{
if ( ! payload_place_run_should_run ( ) ) {
zero_throttle_and_relax_ac ( ) ;
// set target to current position
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
motors - > set_desired_spool_state ( AP_Motors : : DESIRED_THROTTLE_UNLIMITED ) ;
switch ( nav_payload_place . state ) {
case PayloadPlaceStateType_FlyToLocation :
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 :
case PayloadPlaceStateType_Ascending :
case PayloadPlaceStateType_Done :
return payload_place_run_loiter ( ) ;
}
}
bool Copter : : ModeAuto : : payload_place_run_should_run ( )
{
// muts be armed
if ( ! motors - > armed ( ) ) {
return false ;
}
// muts be auto-armed
if ( ! ap . auto_armed ) {
return false ;
}
// must not be landed
if ( ap . land_complete ) {
return false ;
}
// interlock must be enabled (i.e. unsafe)
if ( ! motors - > get_interlock ( ) ) {
return false ;
}
return true ;
}
void Copter : : ModeAuto : : payload_place_run_loiter ( )
{
// loiter...
2018-03-19 14:26:35 -03:00
land_run_horizontal_control ( ) ;
2018-03-22 10:25:18 -03:00
// run loiter controller
2018-03-27 23:13:37 -03:00
loiter_nav - > update ( ekfGndSpdLimit , ekfNavVelGainScaler ) ;
2018-03-22 10:25:18 -03:00
// call attitude controller
const float target_yaw_rate = 0 ;
attitude_control - > input_euler_angle_roll_pitch_euler_rate_yaw ( wp_nav - > get_roll ( ) , wp_nav - > get_pitch ( ) , target_yaw_rate ) ;
// call position controller
pos_control - > update_z_controller ( ) ;
}
void Copter : : ModeAuto : : payload_place_run_descend ( )
{
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
Location_Class Copter : : ModeAuto : : terrain_adjusted_location ( const AP_Mission : : Mission_Command & cmd ) const
{
// convert to location class
Location_Class target_loc ( cmd . content . location ) ;
const Location_Class & current_loc = copter . current_loc ;
// decide if we will use terrain following
int32_t curr_terr_alt_cm , target_terr_alt_cm ;
if ( current_loc . get_alt_cm ( Location_Class : : ALT_FRAME_ABOVE_TERRAIN , curr_terr_alt_cm ) & &
target_loc . get_alt_cm ( Location_Class : : ALT_FRAME_ABOVE_TERRAIN , target_terr_alt_cm ) ) {
curr_terr_alt_cm = MAX ( curr_terr_alt_cm , 200 ) ;
// if using terrain, set target altitude to current altitude above terrain
target_loc . set_alt_cm ( curr_terr_alt_cm , Location_Class : : ALT_FRAME_ABOVE_TERRAIN ) ;
} else {
// set target altitude to current altitude above home
target_loc . set_alt_cm ( current_loc . alt , Location_Class : : ALT_FRAME_ABOVE_HOME ) ;
}
return target_loc ;
}
/********************************************************************************/
// Nav (Must) commands
/********************************************************************************/
// do_takeoff - initiate takeoff navigation command
void Copter : : ModeAuto : : do_takeoff ( const AP_Mission : : Mission_Command & cmd )
{
// Set wp navigation target to safe altitude above current position
takeoff_start ( cmd . content . location ) ;
}
// do_nav_wp - initiate move to next waypoint
void Copter : : ModeAuto : : do_nav_wp ( const AP_Mission : : Mission_Command & cmd )
{
Location_Class target_loc ( cmd . content . location ) ;
const Location_Class & current_loc = copter . current_loc ;
// use current lat, lon if zero
if ( target_loc . lat = = 0 & & target_loc . lng = = 0 ) {
target_loc . lat = current_loc . lat ;
target_loc . lng = current_loc . lng ;
}
// use current altitude if not provided
if ( target_loc . alt = = 0 ) {
// set to current altitude but in command's alt frame
int32_t curr_alt ;
if ( current_loc . get_alt_cm ( target_loc . get_alt_frame ( ) , curr_alt ) ) {
target_loc . set_alt_cm ( curr_alt , target_loc . get_alt_frame ( ) ) ;
} else {
// default to current altitude as alt-above-home
target_loc . set_alt_cm ( current_loc . alt , current_loc . get_alt_frame ( ) ) ;
}
}
// 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 ;
// Set wp navigation target
wp_start ( target_loc ) ;
// if no delay as well as not final waypoint set the waypoint as "fast"
AP_Mission : : Mission_Command temp_cmd ;
if ( loiter_time_max = = 0 & & copter . mission . get_next_nav_cmd ( cmd . index + 1 , temp_cmd ) ) {
copter . wp_nav - > set_fast_waypoint ( true ) ;
}
}
// do_land - initiate landing procedure
void Copter : : ModeAuto : : do_land ( const AP_Mission : : Mission_Command & cmd )
{
// 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
land_state = LandStateType_FlyToLocation ;
Location_Class target_loc = terrain_adjusted_location ( cmd ) ;
wp_start ( target_loc ) ;
} else {
// set landing state
land_state = LandStateType_Descending ;
// initialise landing controller
land_start ( ) ;
}
}
// do_loiter_unlimited - start loitering with no end conditions
// note: caller should set yaw_mode
void Copter : : ModeAuto : : do_loiter_unlimited ( const AP_Mission : : Mission_Command & cmd )
{
// convert back to location
Location_Class target_loc ( cmd . content . location ) ;
const Location_Class & current_loc = copter . current_loc ;
// use current location if not provided
if ( target_loc . lat = = 0 & & target_loc . lng = = 0 ) {
// To-Do: make this simpler
Vector3f temp_pos ;
copter . wp_nav - > get_wp_stopping_point_xy ( temp_pos ) ;
Location_Class temp_loc ( temp_pos ) ;
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 ;
if ( current_loc . get_alt_cm ( target_loc . get_alt_frame ( ) , curr_alt ) ) {
target_loc . set_alt_cm ( curr_alt , target_loc . get_alt_frame ( ) ) ;
} else {
// default to current altitude as alt-above-home
target_loc . set_alt_cm ( current_loc . alt , current_loc . get_alt_frame ( ) ) ;
}
}
// start way point navigator and provide it the desired location
wp_start ( target_loc ) ;
}
// do_circle - initiate moving in a circle
void Copter : : ModeAuto : : do_circle ( const AP_Mission : : Mission_Command & cmd )
{
Location_Class circle_center ( cmd . content . location ) ;
const Location_Class & current_loc = copter . current_loc ;
// default lat/lon to current position if not provided
// To-Do: use stopping point or position_controller's target instead of current location to avoid jerk?
if ( circle_center . lat = = 0 & & circle_center . lng = = 0 ) {
circle_center . lat = current_loc . lat ;
circle_center . lng = current_loc . lng ;
}
// default target altitude to current altitude if not provided
if ( circle_center . alt = = 0 ) {
int32_t curr_alt ;
if ( current_loc . get_alt_cm ( circle_center . get_alt_frame ( ) , curr_alt ) ) {
// circle altitude uses frame from command
circle_center . set_alt_cm ( curr_alt , circle_center . get_alt_frame ( ) ) ;
} else {
// default to current altitude above origin
circle_center . set_alt_cm ( current_loc . alt , current_loc . get_alt_frame ( ) ) ;
copter . Log_Write_Error ( ERROR_SUBSYSTEM_TERRAIN , ERROR_CODE_MISSING_TERRAIN_DATA ) ;
}
}
// 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
void Copter : : ModeAuto : : do_loiter_time ( const AP_Mission : : Mission_Command & cmd )
{
// re-use loiter unlimited
do_loiter_unlimited ( cmd ) ;
// setup loiter timer
loiter_time = 0 ;
loiter_time_max = cmd . p1 ; // units are (seconds)
}
// do_spline_wp - initiate move to next waypoint
void Copter : : ModeAuto : : do_spline_wp ( const AP_Mission : : Mission_Command & cmd )
{
Location_Class target_loc ( cmd . content . location ) ;
const Location_Class & current_loc = copter . current_loc ;
// use current lat, lon if zero
if ( target_loc . lat = = 0 & & target_loc . lng = = 0 ) {
target_loc . lat = current_loc . lat ;
target_loc . lng = current_loc . lng ;
}
// use current altitude if not provided
if ( target_loc . alt = = 0 ) {
// set to current altitude but in command's alt frame
int32_t curr_alt ;
if ( current_loc . get_alt_cm ( target_loc . get_alt_frame ( ) , curr_alt ) ) {
target_loc . set_alt_cm ( curr_alt , target_loc . get_alt_frame ( ) ) ;
} else {
// default to current altitude as alt-above-home
target_loc . set_alt_cm ( current_loc . alt , current_loc . get_alt_frame ( ) ) ;
}
}
// 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 ;
// determine segment start and end type
bool stopped_at_start = true ;
AC_WPNav : : spline_segment_end_type seg_end_type = AC_WPNav : : SEGMENT_END_STOP ;
AP_Mission : : Mission_Command temp_cmd ;
// if previous command was a wp_nav command with no delay set stopped_at_start to false
// To-Do: move processing of delay into wp-nav controller to allow it to determine the stopped_at_start value itself?
uint16_t prev_cmd_idx = copter . mission . get_prev_nav_cmd_index ( ) ;
if ( prev_cmd_idx ! = AP_MISSION_CMD_INDEX_NONE ) {
if ( copter . mission . read_cmd_from_storage ( prev_cmd_idx , temp_cmd ) ) {
if ( ( temp_cmd . id = = MAV_CMD_NAV_WAYPOINT | | temp_cmd . id = = MAV_CMD_NAV_SPLINE_WAYPOINT ) & & temp_cmd . p1 = = 0 ) {
stopped_at_start = false ;
}
}
}
// if there is no delay at the end of this segment get next nav command
Location_Class next_loc ;
if ( cmd . p1 = = 0 & & copter . mission . get_next_nav_cmd ( cmd . index + 1 , temp_cmd ) ) {
next_loc = temp_cmd . content . location ;
// default lat, lon to first waypoint's lat, lon
if ( next_loc . lat = = 0 & & next_loc . lng = = 0 ) {
next_loc . lat = target_loc . lat ;
next_loc . lng = target_loc . lng ;
}
// default alt to first waypoint's alt but in next waypoint's alt frame
if ( next_loc . alt = = 0 ) {
int32_t next_alt ;
if ( target_loc . get_alt_cm ( next_loc . get_alt_frame ( ) , next_alt ) ) {
next_loc . set_alt_cm ( next_alt , next_loc . get_alt_frame ( ) ) ;
} else {
// default to first waypoints altitude
next_loc . set_alt_cm ( target_loc . alt , target_loc . get_alt_frame ( ) ) ;
}
}
// if the next nav command is a waypoint set end type to spline or straight
if ( temp_cmd . id = = MAV_CMD_NAV_WAYPOINT ) {
seg_end_type = AC_WPNav : : SEGMENT_END_STRAIGHT ;
} else if ( temp_cmd . id = = MAV_CMD_NAV_SPLINE_WAYPOINT ) {
seg_end_type = AC_WPNav : : SEGMENT_END_SPLINE ;
}
}
// set spline navigation target
spline_start ( target_loc , stopped_at_start , seg_end_type , next_loc ) ;
}
# if NAV_GUIDED == ENABLED
// do_nav_guided_enable - initiate accepting commands from external nav computer
void Copter : : ModeAuto : : do_nav_guided_enable ( const AP_Mission : : Mission_Command & cmd )
{
if ( cmd . p1 > 0 ) {
// initialise guided limits
copter . mode_guided . limit_init_time_and_pos ( ) ;
// set spline navigation target
nav_guided_start ( ) ;
}
}
// do_guided_limits - pass guided limits to guided controller
void Copter : : ModeAuto : : do_guided_limits ( const AP_Mission : : Mission_Command & cmd )
{
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
void Copter : : ModeAuto : : do_nav_delay ( const AP_Mission : : Mission_Command & cmd )
{
nav_delay_time_start = millis ( ) ;
if ( cmd . content . nav_delay . seconds > 0 ) {
// relative delay
nav_delay_time_max = cmd . content . nav_delay . seconds * 1000 ; // convert seconds to milliseconds
} else {
// absolute delay to utc time
nav_delay_time_max = hal . util - > get_time_utc ( cmd . content . nav_delay . hour_utc , cmd . content . nav_delay . min_utc , cmd . content . nav_delay . sec_utc , 0 ) ;
}
gcs ( ) . send_text ( MAV_SEVERITY_INFO , " Delaying %u sec " , ( unsigned int ) ( nav_delay_time_max / 1000 ) ) ;
}
/********************************************************************************/
// Condition (May) commands
/********************************************************************************/
void Copter : : ModeAuto : : do_wait_delay ( const AP_Mission : : Mission_Command & cmd )
{
condition_start = millis ( ) ;
condition_value = cmd . content . delay . seconds * 1000 ; // convert seconds to milliseconds
}
void Copter : : ModeAuto : : do_within_distance ( const AP_Mission : : Mission_Command & cmd )
{
condition_value = cmd . content . distance . meters * 100 ;
}
void Copter : : ModeAuto : : do_yaw ( const AP_Mission : : Mission_Command & cmd )
{
2017-12-25 23:55:42 -04:00
auto_yaw . set_fixed_yaw (
2018-03-22 10:25:18 -03:00
cmd . content . yaw . angle_deg ,
cmd . content . yaw . turn_rate_dps ,
cmd . content . yaw . direction ,
cmd . content . yaw . relative_angle > 0 ) ;
}
/********************************************************************************/
// Do (Now) commands
/********************************************************************************/
void Copter : : ModeAuto : : do_change_speed ( const AP_Mission : : Mission_Command & cmd )
{
if ( cmd . content . speed . target_ms > 0 ) {
copter . wp_nav - > set_speed_xy ( cmd . content . speed . target_ms * 100.0f ) ;
}
}
void Copter : : ModeAuto : : do_set_home ( const AP_Mission : : Mission_Command & cmd )
{
if ( cmd . p1 = = 1 | | ( cmd . content . location . lat = = 0 & & cmd . content . location . lng = = 0 & & cmd . content . location . alt = = 0 ) ) {
copter . set_home_to_current_location ( false ) ;
} else {
copter . set_home ( cmd . content . location , false ) ;
}
}
// 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
// TO-DO: add support for other features of MAV_CMD_DO_SET_ROI including pointing at a given waypoint
void Copter : : ModeAuto : : do_roi ( const AP_Mission : : Mission_Command & cmd )
{
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
void Copter : : ModeAuto : : do_mount_control ( const AP_Mission : : Mission_Command & cmd )
{
# if MOUNT == ENABLED
if ( ! copter . camera_mount . has_pan_control ( ) ) {
2017-12-25 23:55:42 -04:00
auto_yaw . set_fixed_yaw ( cmd . content . mount_control . yaw , 0.0f , 0 , 0 ) ;
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 CAMERA == ENABLED
// do_digicam_configure Send Digicam Configure message with the camera library
void Copter : : ModeAuto : : do_digicam_configure ( const AP_Mission : : Mission_Command & cmd )
{
copter . camera . configure (
cmd . content . digicam_configure . shooting_mode ,
cmd . content . digicam_configure . shutter_speed ,
cmd . content . digicam_configure . aperture ,
cmd . content . digicam_configure . ISO ,
cmd . content . digicam_configure . exposure_type ,
cmd . content . digicam_configure . cmd_id ,
cmd . content . digicam_configure . engine_cutoff_time ) ;
}
// do_digicam_control Send Digicam Control message with the camera library
void Copter : : ModeAuto : : do_digicam_control ( const AP_Mission : : Mission_Command & cmd )
{
copter . camera . control ( cmd . content . digicam_control . session ,
cmd . content . digicam_control . zoom_pos ,
cmd . content . digicam_control . zoom_step ,
cmd . content . digicam_control . focus_lock ,
cmd . content . digicam_control . shooting_cmd ,
cmd . content . digicam_control . cmd_id ) ;
}
# endif
# if PARACHUTE == ENABLED
// do_parachute - configure or release parachute
void Copter : : ModeAuto : : do_parachute ( const AP_Mission : : Mission_Command & cmd )
{
switch ( cmd . p1 ) {
case PARACHUTE_DISABLE :
copter . parachute . enabled ( false ) ;
Log_Write_Event ( DATA_PARACHUTE_DISABLED ) ;
break ;
case PARACHUTE_ENABLE :
copter . parachute . enabled ( true ) ;
Log_Write_Event ( DATA_PARACHUTE_ENABLED ) ;
break ;
case PARACHUTE_RELEASE :
copter . parachute_release ( ) ;
break ;
default :
// do nothing
break ;
}
}
# endif
# if GRIPPER_ENABLED == ENABLED
// do_gripper - control gripper
void Copter : : ModeAuto : : do_gripper ( const AP_Mission : : Mission_Command & cmd )
{
// Note: we ignore the gripper num parameter because we only support one gripper
switch ( cmd . content . gripper . action ) {
case GRIPPER_ACTION_RELEASE :
g2 . gripper . release ( ) ;
Log_Write_Event ( DATA_GRIPPER_RELEASE ) ;
break ;
case GRIPPER_ACTION_GRAB :
g2 . gripper . grab ( ) ;
Log_Write_Event ( DATA_GRIPPER_GRAB ) ;
break ;
default :
// do nothing
break ;
}
}
# endif
# if WINCH_ENABLED == ENABLED
// control winch based on mission command
void Copter : : ModeAuto : : do_winch ( const AP_Mission : : Mission_Command & cmd )
{
// Note: we ignore the gripper num parameter because we only support one gripper
switch ( cmd . content . winch . action ) {
case WINCH_RELAXED :
g2 . winch . relax ( ) ;
Log_Write_Event ( DATA_WINCH_RELAXED ) ;
break ;
case WINCH_RELATIVE_LENGTH_CONTROL :
g2 . winch . release_length ( cmd . content . winch . release_length , cmd . content . winch . release_rate ) ;
Log_Write_Event ( DATA_WINCH_LENGTH_CONTROL ) ;
break ;
case WINCH_RATE_CONTROL :
g2 . winch . set_desired_rate ( cmd . content . winch . release_rate ) ;
Log_Write_Event ( DATA_WINCH_RATE_CONTROL ) ;
break ;
default :
// do nothing
break ;
}
}
# endif
// do_payload_place - initiate placing procedure
void Copter : : ModeAuto : : do_payload_place ( const AP_Mission : : Mission_Command & cmd )
{
// 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 ;
Location_Class target_loc = terrain_adjusted_location ( cmd ) ;
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
void Copter : : ModeAuto : : do_RTL ( void )
{
// start rtl in auto flight mode
rtl_start ( ) ;
}
/********************************************************************************/
// Verify Nav (Must) commands
/********************************************************************************/
// verify_takeoff - check if we have completed the takeoff
bool Copter : : ModeAuto : : verify_takeoff ( )
{
// have we reached our target altitude?
return copter . wp_nav - > reached_wp_destination ( ) ;
}
// verify_land - returns true if landing has been completed
bool Copter : : ModeAuto : : verify_land ( )
{
bool retval = false ;
switch ( land_state ) {
case LandStateType_FlyToLocation :
// check if we've reached the location
if ( copter . wp_nav - > reached_wp_destination ( ) ) {
// get destination so we can use it for loiter target
Vector3f dest = copter . wp_nav - > get_wp_destination ( ) ;
// initialise landing controller
land_start ( dest ) ;
// advance to next state
land_state = LandStateType_Descending ;
}
break ;
case LandStateType_Descending :
// rely on THROTTLE_LAND mode to correctly update landing status
retval = ap . land_complete ;
break ;
default :
// this should never happen
// TO-DO: log an error
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
bool Copter : : ModeAuto : : verify_payload_place ( )
{
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 ( ) ;
const uint32_t now = AP_HAL : : millis ( ) ;
// if we discover we've landed then immediately release the load:
if ( ap . land_complete ) {
switch ( nav_payload_place . state ) {
case PayloadPlaceStateType_FlyToLocation :
case PayloadPlaceStateType_Calibrating_Hover_Start :
case PayloadPlaceStateType_Calibrating_Hover :
case PayloadPlaceStateType_Descending_Start :
case PayloadPlaceStateType_Descending :
gcs ( ) . send_text ( MAV_SEVERITY_INFO , " NAV_PLACE: landed " ) ;
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 ;
}
// we're there; set loiter target
nav_payload_place . state = PayloadPlaceStateType_Calibrating_Hover_Start ;
FALLTHROUGH ;
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 : {
Location_Class target_loc = inertial_nav . get_position ( ) ;
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
// TO-DO: log an error
return true ;
}
// should never get here
return true ;
}
# undef debug
bool Copter : : ModeAuto : : verify_loiter_unlimited ( )
{
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
bool Copter : : ModeAuto : : verify_loiter_time ( )
{
// return immediately if we haven't reached our destination
if ( ! copter . wp_nav - > reached_wp_destination ( ) ) {
return false ;
}
// start our loiter timer
if ( loiter_time = = 0 ) {
loiter_time = millis ( ) ;
}
// check if loiter timer has run out
return ( ( ( millis ( ) - loiter_time ) / 1000 ) > = loiter_time_max ) ;
2014-01-27 10:43:48 -04:00
}
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
bool Copter : : ModeAuto : : verify_RTL ( )
2014-05-23 02:29:08 -03:00
{
2018-03-22 10:25:18 -03:00
return ( copter . mode_rtl . state_complete ( ) & & ( copter . mode_rtl . state ( ) = = RTL_FinalDescent | | copter . mode_rtl . state ( ) = = RTL_Land ) ) ;
}
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
2018-03-22 10:25:18 -03:00
bool Copter : : ModeAuto : : verify_wait_delay ( )
{
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
}
2018-03-22 10:25:18 -03:00
bool Copter : : 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
bool Copter : : 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
2017-12-25 23:55:42 -04:00
return ( labs ( 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
bool Copter : : ModeAuto : : verify_nav_wp ( const AP_Mission : : Mission_Command & cmd )
{
// check if we have reached the waypoint
if ( ! copter . wp_nav - > reached_wp_destination ( ) ) {
return false ;
}
2014-10-12 05:06:51 -03:00
2018-03-22 10:25:18 -03:00
// start timer if necessary
if ( loiter_time = = 0 ) {
loiter_time = millis ( ) ;
}
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 ) {
2018-05-24 13:31:01 -03:00
// 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 ;
} else {
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
bool Copter : : 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
if ( mode ( ) = = Auto_CircleMoveToEdge ) {
if ( copter . wp_nav - > reached_wp_destination ( ) ) {
const Vector3f curr_pos = copter . inertial_nav . get_position ( ) ;
Vector3f circle_center = copter . pv_location_to_vector ( cmd . content . location ) ;
// set target altitude if not provided
if ( is_zero ( circle_center . z ) ) {
circle_center . z = curr_pos . z ;
}
// set lat/lon position if not provided
if ( cmd . content . location . lat = = 0 & & cmd . content . location . lng = = 0 ) {
circle_center . x = curr_pos . x ;
circle_center . y = curr_pos . y ;
}
// 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
bool Copter : : ModeAuto : : verify_spline_wp ( const AP_Mission : : Mission_Command & cmd )
{
// check if we have reached the waypoint
if ( ! copter . wp_nav - > reached_wp_destination ( ) ) {
return false ;
2014-10-12 05:06:51 -03:00
}
2018-03-22 10:25:18 -03:00
// start timer if necessary
if ( loiter_time = = 0 ) {
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 ;
} else {
return false ;
}
}
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
bool Copter : : ModeAuto : : verify_nav_guided_enable ( const AP_Mission : : Mission_Command & cmd )
{
// 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
bool Copter : : ModeAuto : : verify_nav_delay ( const AP_Mission : : Mission_Command & cmd )
{
if ( millis ( ) - nav_delay_time_start > ( uint32_t ) MAX ( nav_delay_time_max , 0 ) ) {
nav_delay_time_max = 0 ;
return true ;
}
return false ;
2014-10-12 05:06:51 -03:00
}
2018-02-21 22:06:07 -04:00
# endif