2015-05-13 03:09:36 -03:00
# include "Plane.h"
2014-03-13 23:48:58 -03:00
2011-09-08 22:29:39 -03:00
/********************************************************************************/
// Command Event Handlers
/********************************************************************************/
2015-05-13 03:09:36 -03:00
bool Plane : : start_command ( const AP_Mission : : Mission_Command & cmd )
2011-09-08 22:29:39 -03:00
{
2016-05-11 02:57:41 -03:00
// default to non-VTOL loiter
auto_state . vtol_loiter = false ;
// log when new commands start
2014-03-18 23:42:15 -03:00
if ( should_log ( MASK_LOG_CMD ) ) {
2019-01-18 00:24:08 -04:00
logger . Write_Mission_Cmd ( mission , cmd ) ;
2014-03-03 09:50:45 -04:00
}
// special handling for nav vs non-nav commands
if ( AP_Mission : : is_nav_cmd ( cmd ) ) {
2016-03-28 18:21:24 -03:00
// set takeoff_complete to true so we don't add extra elevator
2014-03-03 09:50:45 -04:00
// except in a takeoff
2014-04-23 08:57:51 -03:00
auto_state . takeoff_complete = true ;
2014-10-21 12:26:33 -03:00
2015-06-13 06:12:54 -03:00
// start non-idle
auto_state . idle_mode = false ;
2014-04-23 08:57:51 -03:00
2016-04-18 13:37:30 -03:00
nav_controller - > set_data_is_stale ( ) ;
2015-09-16 06:03:28 -03:00
// reset loiter start time. New command is a new loiter
loiter . start_time_ms = 0 ;
2016-07-21 02:29:31 -03:00
AP_Mission : : Mission_Command next_nav_cmd ;
const uint16_t next_index = mission . get_current_nav_index ( ) + 1 ;
2021-12-01 02:35:26 -04:00
const bool have_next_cmd = mission . get_next_nav_cmd ( next_index , next_nav_cmd ) ;
auto_state . wp_is_land_approach = have_next_cmd & & ( next_nav_cmd . id = = MAV_CMD_NAV_LAND ) ;
2021-09-10 03:28:21 -03:00
# if HAL_QUADPLANE_ENABLED
2021-12-01 02:35:26 -04:00
if ( have_next_cmd & & quadplane . is_vtol_land ( next_nav_cmd . id ) ) {
2021-09-10 03:28:21 -03:00
auto_state . wp_is_land_approach = false ;
}
# endif
2014-03-03 09:50:45 -04:00
}
switch ( cmd . id ) {
2011-09-08 22:29:39 -03:00
2012-08-16 21:50:15 -03:00
case MAV_CMD_NAV_TAKEOFF :
2015-08-20 17:44:32 -03:00
crash_state . is_crashed = false ;
2021-09-10 03:28:21 -03:00
# if HAL_QUADPLANE_ENABLED
2017-10-29 03:31:09 -03:00
if ( quadplane . is_vtol_takeoff ( cmd . id ) ) {
return quadplane . do_vtol_takeoff ( cmd ) ;
}
2021-09-10 03:28:21 -03:00
# endif
2014-03-03 09:50:45 -04:00
do_takeoff ( cmd ) ;
2012-08-16 21:50:15 -03:00
break ;
2011-09-08 22:29:39 -03:00
2012-08-16 21:50:15 -03:00
case MAV_CMD_NAV_WAYPOINT : // Navigate to Waypoint
2014-03-03 09:50:45 -04:00
do_nav_wp ( cmd ) ;
2012-08-16 21:50:15 -03:00
break ;
2011-09-08 22:29:39 -03:00
2012-08-16 21:50:15 -03:00
case MAV_CMD_NAV_LAND : // LAND to Waypoint
2021-09-10 03:28:21 -03:00
# if HAL_QUADPLANE_ENABLED
2017-10-29 03:31:09 -03:00
if ( quadplane . is_vtol_land ( cmd . id ) ) {
crash_state . is_crashed = false ;
return quadplane . do_vtol_land ( cmd ) ;
}
2021-09-10 03:28:21 -03:00
# endif
2014-03-03 09:50:45 -04:00
do_land ( cmd ) ;
2012-08-16 21:50:15 -03:00
break ;
2011-09-08 22:29:39 -03:00
2012-08-16 21:50:15 -03:00
case MAV_CMD_NAV_LOITER_UNLIM : // Loiter indefinitely
2014-03-03 09:50:45 -04:00
do_loiter_unlimited ( cmd ) ;
2012-08-16 21:50:15 -03:00
break ;
2011-09-08 22:29:39 -03:00
2012-08-16 21:50:15 -03:00
case MAV_CMD_NAV_LOITER_TURNS : // Loiter N Times
2014-03-03 09:50:45 -04:00
do_loiter_turns ( cmd ) ;
2012-08-16 21:50:15 -03:00
break ;
2011-09-08 22:29:39 -03:00
2012-08-16 21:50:15 -03:00
case MAV_CMD_NAV_LOITER_TIME :
2014-03-03 09:50:45 -04:00
do_loiter_time ( cmd ) ;
2012-08-16 21:50:15 -03:00
break ;
2011-09-08 22:29:39 -03:00
2015-03-13 18:48:21 -03:00
case MAV_CMD_NAV_LOITER_TO_ALT :
do_loiter_to_alt ( cmd ) ;
break ;
2012-08-16 21:50:15 -03:00
case MAV_CMD_NAV_RETURN_TO_LAUNCH :
2020-07-24 14:52:07 -03:00
set_mode ( mode_rtl , ModeReason : : MISSION_CMD ) ;
2012-08-16 21:50:15 -03:00
break ;
2011-09-08 22:29:39 -03:00
2014-10-21 17:46:01 -03:00
case MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT :
do_continue_and_change_alt ( cmd ) ;
2014-11-24 22:15:25 -04:00
break ;
2014-10-21 17:46:01 -03:00
2015-06-13 06:12:54 -03:00
case MAV_CMD_NAV_ALTITUDE_WAIT :
do_altitude_wait ( cmd ) ;
break ;
2021-09-10 03:28:21 -03:00
# if HAL_QUADPLANE_ENABLED
2016-01-01 05:42:10 -04:00
case MAV_CMD_NAV_VTOL_TAKEOFF :
crash_state . is_crashed = false ;
return quadplane . do_vtol_takeoff ( cmd ) ;
case MAV_CMD_NAV_VTOL_LAND :
2023-01-17 02:47:03 -04:00
case MAV_CMD_NAV_PAYLOAD_PLACE :
2022-06-30 18:43:06 -03:00
if ( quadplane . landing_with_fixed_wing_spiral_approach ( ) ) {
2018-09-25 01:11:26 -03:00
// the user wants to approach the landing in a fixed wing flight mode
// the waypoint will be used as a loiter_to_alt
// after which point the plane will compute the optimal into the wind direction
// and fly in on that direction towards the landing waypoint
// it will then transition to VTOL and do a normal quadplane landing
do_landing_vtol_approach ( cmd ) ;
break ;
} else {
return quadplane . do_vtol_land ( cmd ) ;
}
2021-09-10 03:28:21 -03:00
# endif
2014-03-03 09:50:45 -04:00
// Conditional commands
2011-09-08 22:29:39 -03:00
2012-08-16 21:50:15 -03:00
case MAV_CMD_CONDITION_DELAY :
2014-03-03 09:50:45 -04:00
do_wait_delay ( cmd ) ;
2012-08-16 21:50:15 -03:00
break ;
2011-09-08 22:29:39 -03:00
2012-08-16 21:50:15 -03:00
case MAV_CMD_CONDITION_DISTANCE :
2014-03-03 09:50:45 -04:00
do_within_distance ( cmd ) ;
2012-08-16 21:50:15 -03:00
break ;
2011-09-08 22:29:39 -03:00
2014-03-03 09:50:45 -04:00
// Do commands
2011-09-08 22:29:39 -03:00
2012-08-16 21:50:15 -03:00
case MAV_CMD_DO_CHANGE_SPEED :
2014-03-03 09:50:45 -04:00
do_change_speed ( cmd ) ;
2012-08-16 21:50:15 -03:00
break ;
2011-09-08 22:29:39 -03:00
2012-08-16 21:50:15 -03:00
case MAV_CMD_DO_SET_HOME :
2014-03-03 09:50:45 -04:00
do_set_home ( cmd ) ;
2012-08-16 21:50:15 -03:00
break ;
2011-09-08 22:29:39 -03:00
2014-06-05 03:12:10 -03:00
case MAV_CMD_DO_INVERTED_FLIGHT :
if ( cmd . p1 = = 0 | | cmd . p1 = = 1 ) {
auto_state . inverted_flight = ( bool ) cmd . p1 ;
2017-07-08 22:15:58 -03:00
gcs ( ) . send_text ( MAV_SEVERITY_INFO , " Set inverted %u " , cmd . p1 ) ;
2014-06-05 03:12:10 -03:00
}
break ;
2014-10-17 22:40:31 -03:00
case MAV_CMD_DO_LAND_START :
break ;
2014-10-25 18:20:04 -03:00
case MAV_CMD_DO_FENCE_ENABLE :
2022-07-19 08:33:13 -03:00
# if AP_FENCE_ENABLED
2020-09-10 03:31:18 -03:00
if ( cmd . p1 = = 0 ) { // disable fence
plane . fence . enable ( false ) ;
gcs ( ) . send_text ( MAV_SEVERITY_INFO , " Fence disabled " ) ;
} else if ( cmd . p1 = = 1 ) { // enable fence
plane . fence . enable ( true ) ;
gcs ( ) . send_text ( MAV_SEVERITY_INFO , " Fence enabled " ) ;
} else if ( cmd . p1 = = 2 ) { // disable fence floor only
plane . fence . disable_floor ( ) ;
gcs ( ) . send_text ( MAV_SEVERITY_INFO , " Fence floor disabled " ) ;
}
2014-10-25 18:20:04 -03:00
# endif
2015-06-19 23:35:07 -03:00
break ;
2015-06-13 06:16:02 -03:00
case MAV_CMD_DO_AUTOTUNE_ENABLE :
autotune_enable ( cmd . p1 ) ;
2014-10-25 18:20:04 -03:00
break ;
2020-07-24 14:23:23 -03:00
# if HAL_MOUNT_ENABLED
2012-08-16 21:50:15 -03:00
// Sets the region of interest (ROI) for a sensor set or the
// vehicle itself. This can then be used by the vehicles control
// system to control the vehicle attitude and the attitude of various
// devices such as cameras.
// |Region of interest mode. (see MAV_ROI enum)| Waypoint index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple cameras etc.)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z|
2014-07-04 03:42:51 -03:00
case MAV_CMD_DO_SET_ROI :
if ( cmd . content . location . alt = = 0 & & cmd . content . location . lat = = 0 & & cmd . content . location . lng = = 0 ) {
// switch off the camera tracking if enabled
if ( camera_mount . get_mode ( ) = = MAV_MOUNT_MODE_GPS_POINT ) {
camera_mount . set_mode_to_default ( ) ;
}
} else {
2015-01-08 16:12:08 -04:00
// set mount's target location
camera_mount . set_roi_target ( cmd . content . location ) ;
2014-07-04 03:42:51 -03:00
}
2012-08-16 21:50:15 -03:00
break ;
2015-05-25 19:30:30 -03:00
case MAV_CMD_DO_MOUNT_CONTROL : // 205
// point the camera to a specified angle
2022-06-21 02:59:11 -03:00
camera_mount . set_angle_target ( cmd . content . mount_control . roll , cmd . content . mount_control . pitch , cmd . content . mount_control . yaw , false ) ;
2015-05-25 19:30:30 -03:00
break ;
2011-10-31 18:55:58 -03:00
# endif
2016-04-22 05:22:31 -03:00
2021-09-10 03:28:21 -03:00
# if HAL_QUADPLANE_ENABLED
2016-04-22 05:22:31 -03:00
case MAV_CMD_DO_VTOL_TRANSITION :
plane . quadplane . handle_do_vtol_transition ( ( enum MAV_VTOL_STATE ) cmd . content . do_vtol_transition . target_state ) ;
break ;
2021-09-10 03:28:21 -03:00
# endif
2016-07-23 04:37:42 -03:00
2022-07-15 08:50:12 -03:00
# if AP_ICENGINE_ENABLED
2016-07-23 04:37:42 -03:00
case MAV_CMD_DO_ENGINE_CONTROL :
2016-07-23 06:02:48 -03:00
plane . g2 . ice_control . engine_control ( cmd . content . do_engine_control . start_control ,
cmd . content . do_engine_control . cold_start ,
cmd . content . do_engine_control . height_delay_cm * 0.01f ) ;
2016-07-23 04:37:42 -03:00
break ;
2022-07-15 08:50:12 -03:00
# endif
2018-08-13 17:16:45 -03:00
2021-11-15 01:08:34 -04:00
# if AP_SCRIPTING_ENABLED
2021-10-25 00:59:23 -03:00
case MAV_CMD_NAV_SCRIPT_TIME :
do_nav_script_time ( cmd ) ;
break ;
# endif
2022-06-09 20:16:47 -03:00
case MAV_CMD_NAV_DELAY :
do_nav_delay ( cmd ) ;
break ;
2021-10-25 00:59:23 -03:00
2018-08-13 17:16:45 -03:00
default :
// unable to use the command, allow the vehicle to try the next command
return false ;
2012-08-16 21:50:15 -03:00
}
2014-03-03 09:50:45 -04:00
return true ;
2011-09-08 22:29:39 -03:00
}
2013-04-15 01:41:15 -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 .
2016-08-22 06:05:05 -03:00
Return true if we do not recognize the command so that we move on to the next command
2013-04-15 01:41:15 -03:00
* * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * */
2011-09-08 22:29:39 -03:00
2015-05-13 03:09:36 -03:00
bool Plane : : verify_command ( const AP_Mission : : Mission_Command & cmd ) // Returns true if command complete
2011-09-08 22:29:39 -03:00
{
2014-03-03 09:50:45 -04:00
switch ( cmd . id ) {
2011-09-08 22:29:39 -03:00
2012-08-16 21:50:15 -03:00
case MAV_CMD_NAV_TAKEOFF :
2021-09-10 03:28:21 -03:00
# if HAL_QUADPLANE_ENABLED
2017-10-29 03:31:09 -03:00
if ( quadplane . is_vtol_takeoff ( cmd . id ) ) {
return quadplane . verify_vtol_takeoff ( cmd ) ;
}
2021-09-10 03:28:21 -03:00
# endif
2012-08-16 21:50:15 -03:00
return verify_takeoff ( ) ;
2011-09-08 22:29:39 -03:00
2012-08-16 21:50:15 -03:00
case MAV_CMD_NAV_WAYPOINT :
2014-09-02 22:23:29 -03:00
return verify_nav_wp ( cmd ) ;
2011-09-08 22:29:39 -03:00
2016-08-22 06:05:05 -03:00
case MAV_CMD_NAV_LAND :
2021-09-10 03:28:21 -03:00
# if HAL_QUADPLANE_ENABLED
2017-10-29 03:31:09 -03:00
if ( quadplane . is_vtol_land ( cmd . id ) ) {
2023-01-17 02:47:03 -04:00
return quadplane . verify_vtol_land ( ) ;
2017-10-29 03:31:09 -03:00
}
2021-09-10 03:28:21 -03:00
# endif
2022-09-29 20:10:41 -03:00
if ( flight_stage = = AP_FixedWing : : FlightStage : : ABORT_LANDING ) {
2017-01-10 03:44:25 -04:00
return landing . verify_abort_landing ( prev_WP_loc , next_WP_loc , current_loc , auto_state . takeoff_altitude_rel_cm , throttle_suppressed ) ;
2016-11-23 07:12:34 -04:00
2017-01-10 03:44:25 -04:00
} else {
// use rangefinder to correct if possible
2019-09-14 19:32:12 -03:00
float height = height_above_target ( ) - rangefinder_correction ( ) ;
// for flare calculations we don't want to use the terrain
// correction as otherwise we will flare early on rising
// ground
height - = auto_state . terrain_correction ;
2017-01-10 03:44:25 -04:00
return landing . verify_land ( prev_WP_loc , next_WP_loc , current_loc ,
2020-11-02 16:59:29 -04:00
height , auto_state . sink_rate , auto_state . wp_proportion , auto_state . last_flying_ms , arming . is_armed ( ) , is_flying ( ) ,
g . rangefinder_landing & & rangefinder_state . in_range ) ;
2016-11-23 07:12:34 -04:00
}
2016-08-22 06:05:05 -03:00
2012-08-16 21:50:15 -03:00
case MAV_CMD_NAV_LOITER_UNLIM :
2018-11-16 17:52:48 -04:00
return verify_loiter_unlim ( cmd ) ;
2011-09-08 22:29:39 -03:00
2012-08-16 21:50:15 -03:00
case MAV_CMD_NAV_LOITER_TURNS :
2018-11-16 17:52:48 -04:00
return verify_loiter_turns ( cmd ) ;
2011-09-08 22:29:39 -03:00
2012-08-16 21:50:15 -03:00
case MAV_CMD_NAV_LOITER_TIME :
return verify_loiter_time ( ) ;
2011-09-08 22:29:39 -03:00
2015-03-13 18:48:21 -03:00
case MAV_CMD_NAV_LOITER_TO_ALT :
2018-11-16 17:52:48 -04:00
return verify_loiter_to_alt ( cmd ) ;
2015-03-13 18:48:21 -03:00
2012-08-16 21:50:15 -03:00
case MAV_CMD_NAV_RETURN_TO_LAUNCH :
return verify_RTL ( ) ;
2011-09-08 22:29:39 -03:00
2014-10-21 17:46:01 -03:00
case MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT :
return verify_continue_and_change_alt ( ) ;
2015-06-13 06:12:54 -03:00
case MAV_CMD_NAV_ALTITUDE_WAIT :
return verify_altitude_wait ( cmd ) ;
2021-09-10 03:28:21 -03:00
# if HAL_QUADPLANE_ENABLED
2016-08-22 06:05:05 -03:00
case MAV_CMD_NAV_VTOL_TAKEOFF :
return quadplane . verify_vtol_takeoff ( cmd ) ;
case MAV_CMD_NAV_VTOL_LAND :
2023-01-17 02:47:03 -04:00
case MAV_CMD_NAV_PAYLOAD_PLACE :
2022-06-30 18:43:06 -03:00
if ( quadplane . landing_with_fixed_wing_spiral_approach ( ) & & ! verify_landing_vtol_approach ( cmd ) ) {
2018-09-25 01:11:26 -03:00
// verify_landing_vtol_approach will return true once we have completed the approach,
// in which case we fall over to normal vtol landing code
return false ;
} else {
return quadplane . verify_vtol_land ( ) ;
}
2021-09-10 03:28:21 -03:00
# endif // HAL_QUADPLANE_ENABLED
2016-08-22 06:05:05 -03:00
2014-03-03 09:50:45 -04:00
// Conditional commands
2011-09-08 22:29:39 -03:00
case MAV_CMD_CONDITION_DELAY :
return verify_wait_delay ( ) ;
case MAV_CMD_CONDITION_DISTANCE :
return verify_within_distance ( ) ;
2021-11-15 01:08:34 -04:00
# if AP_SCRIPTING_ENABLED
2021-10-25 00:59:23 -03:00
case MAV_CMD_NAV_SCRIPT_TIME :
return verify_nav_script_time ( cmd ) ;
# endif
2022-06-09 20:16:47 -03:00
case MAV_CMD_NAV_DELAY :
return verify_nav_delay ( cmd ) ;
2014-03-03 09:50:45 -04:00
// do commands (always return true)
case MAV_CMD_DO_CHANGE_SPEED :
case MAV_CMD_DO_SET_HOME :
2014-06-05 03:12:10 -03:00
case MAV_CMD_DO_INVERTED_FLIGHT :
2014-10-17 14:35:05 -03:00
case MAV_CMD_DO_LAND_START :
2014-10-25 18:20:04 -03:00
case MAV_CMD_DO_FENCE_ENABLE :
2015-06-13 06:16:02 -03:00
case MAV_CMD_DO_AUTOTUNE_ENABLE :
2016-08-22 06:05:05 -03:00
case MAV_CMD_DO_SET_CAM_TRIGG_DIST :
case MAV_CMD_DO_SET_ROI :
case MAV_CMD_DO_MOUNT_CONTROL :
2016-07-23 06:02:48 -03:00
case MAV_CMD_DO_VTOL_TRANSITION :
case MAV_CMD_DO_ENGINE_CONTROL :
2014-03-03 09:50:45 -04:00
return true ;
2011-09-08 22:29:39 -03:00
default :
2014-03-03 09:50:45 -04:00
// error message
2017-07-08 22:15:58 -03:00
gcs ( ) . send_text ( MAV_SEVERITY_WARNING , " Skipping invalid cmd #%i " , cmd . id ) ;
2016-08-22 06:05:05 -03:00
// return true if we do not recognize the command so that we move on to the next command
2014-03-03 09:50:45 -04:00
return true ;
}
2011-09-08 22:29:39 -03:00
}
/********************************************************************************/
// Nav (Must) commands
/********************************************************************************/
2021-06-01 03:03:52 -03:00
void Plane : : do_RTL ( int32_t rtl_altitude_AMSL_cm )
2011-09-08 22:29:39 -03:00
{
2017-11-21 15:41:45 -04:00
auto_state . next_wp_crosstrack = false ;
auto_state . crosstrack = false ;
2014-03-16 01:53:10 -03:00
prev_WP_loc = current_loc ;
2023-04-07 05:25:34 -03:00
next_WP_loc = calc_best_rally_or_home_location ( current_loc , rtl_altitude_AMSL_cm ) ;
2014-07-24 04:54:58 -03:00
setup_terrain_target_alt ( next_WP_loc ) ;
2014-08-04 03:55:15 -03:00
set_target_altitude_location ( next_WP_loc ) ;
2013-04-14 09:04:25 -03:00
2017-01-30 13:44:35 -04:00
if ( aparm . loiter_radius < 0 ) {
2013-04-15 08:31:11 -03:00
loiter . direction = - 1 ;
2013-04-14 09:04:25 -03:00
} else {
2013-04-15 08:31:11 -03:00
loiter . direction = 1 ;
2013-04-14 09:04:25 -03:00
}
2011-09-08 22:29:39 -03:00
2013-07-05 01:56:58 -03:00
setup_glide_slope ( ) ;
2014-07-24 03:21:30 -03:00
setup_turn_angle ( ) ;
2013-07-05 01:56:58 -03:00
2019-01-15 13:46:13 -04:00
logger . Write_Mode ( control_mode - > mode_number ( ) , control_mode_reason ) ;
2011-09-08 22:29:39 -03:00
}
2023-04-07 05:25:34 -03:00
Location Plane : : calc_best_rally_or_home_location ( const Location & _current_loc , float rtl_home_alt_amsl_cm ) const
{
# if HAL_RALLY_ENABLED
return plane . rally . calc_best_rally_or_home_location ( _current_loc , rtl_home_alt_amsl_cm ) ;
# else
Location destination = plane . home ;
destination . set_alt_cm ( rtl_home_alt_amsl_cm , Location : : AltFrame : : ABSOLUTE ) ;
return destination ;
# endif
}
2017-10-29 03:31:09 -03:00
/*
start a NAV_TAKEOFF command
*/
2015-05-13 03:09:36 -03:00
void Plane : : do_takeoff ( const AP_Mission : : Mission_Command & cmd )
2011-09-08 22:29:39 -03:00
{
2015-01-02 19:36:14 -04:00
prev_WP_loc = current_loc ;
2014-03-17 04:45:45 -03:00
set_next_WP ( cmd . content . location ) ;
2012-08-16 21:50:15 -03:00
// pitch in deg, airspeed m/s, throttle %, track WP 1 or 0
2014-08-04 06:59:46 -03:00
auto_state . takeoff_pitch_cd = ( int16_t ) cmd . p1 * 100 ;
2015-09-08 20:13:12 -03:00
if ( auto_state . takeoff_pitch_cd < = 0 ) {
// if the mission doesn't specify a pitch use 4 degrees
2022-12-23 22:26:31 -04:00
auto_state . takeoff_pitch_cd = 400 ;
2015-09-08 20:13:12 -03:00
}
2015-02-25 07:54:52 -04:00
auto_state . takeoff_altitude_rel_cm = next_WP_loc . alt - home . alt ;
2014-03-16 01:53:10 -03:00
next_WP_loc . lat = home . lat + 10 ;
next_WP_loc . lng = home . lng + 10 ;
2014-10-06 17:17:33 -03:00
auto_state . takeoff_speed_time_ms = 0 ;
2014-04-23 08:57:51 -03:00
auto_state . takeoff_complete = false ; // set flag to use gps ground course during TO. IMU will be doing yaw drift correction
2016-03-09 18:22:53 -04:00
auto_state . height_below_takeoff_to_level_off_cm = 0 ;
2012-08-16 21:50:15 -03:00
// Flag also used to override "on the ground" throttle disable
2014-10-06 17:17:33 -03:00
// zero locked course
steer_state . locked_course_err = 0 ;
2015-09-08 05:06:19 -03:00
steer_state . hold_course_cd = - 1 ;
2015-09-17 02:35:37 -03:00
auto_state . baro_takeoff_alt = barometer . get_altitude ( ) ;
2011-09-08 22:29:39 -03:00
}
2015-05-13 03:09:36 -03:00
void Plane : : do_nav_wp ( const AP_Mission : : Mission_Command & cmd )
2011-09-08 22:29:39 -03:00
{
2014-03-17 04:45:45 -03:00
set_next_WP ( cmd . content . location ) ;
2011-09-08 22:29:39 -03:00
}
2015-05-13 03:09:36 -03:00
void Plane : : do_land ( const AP_Mission : : Mission_Command & cmd )
2011-09-08 22:29:39 -03:00
{
2014-03-17 04:45:45 -03:00
set_next_WP ( cmd . content . location ) ;
2015-05-09 13:36:40 -03:00
// configure abort altitude and pitch
// if NAV_LAND has an abort altitude then use it, else use last takeoff, else use 50m
if ( cmd . p1 > 0 ) {
auto_state . takeoff_altitude_rel_cm = ( int16_t ) cmd . p1 * 100 ;
} else if ( auto_state . takeoff_altitude_rel_cm < = 0 ) {
auto_state . takeoff_altitude_rel_cm = 3000 ;
}
if ( auto_state . takeoff_pitch_cd < = 0 ) {
// If no takeoff command has ever been used, default to a conservative 10deg
auto_state . takeoff_pitch_cd = 1000 ;
}
2015-09-15 22:14:26 -03:00
// zero rangefinder state, start to accumulate good samples now
memset ( & rangefinder_state , 0 , sizeof ( rangefinder_state ) ) ;
2017-01-10 15:47:31 -04:00
2017-01-30 15:48:22 -04:00
landing . do_land ( cmd , relative_altitude ) ;
2017-01-10 15:47:31 -04:00
2022-09-29 20:10:41 -03:00
if ( flight_stage = = AP_FixedWing : : FlightStage : : ABORT_LANDING ) {
2017-06-15 23:00:54 -03:00
// if we were in an abort we need to explicitly move out of the abort state, as it's sticky
2022-09-29 20:10:41 -03:00
set_flight_stage ( AP_FixedWing : : FlightStage : : LAND ) ;
2017-06-15 23:00:54 -03:00
}
2022-07-19 08:33:13 -03:00
# if AP_FENCE_ENABLED
2021-01-13 19:36:42 -04:00
plane . fence . auto_disable_fence_for_landing ( ) ;
2020-09-10 03:31:18 -03:00
# endif
2011-09-08 22:29:39 -03:00
}
2021-09-10 03:28:21 -03:00
# if HAL_QUADPLANE_ENABLED
2018-09-25 01:11:26 -03:00
void Plane : : do_landing_vtol_approach ( const AP_Mission : : Mission_Command & cmd )
{
2018-11-16 17:53:43 -04:00
//set target alt
Location loc = cmd . content . location ;
2019-03-26 21:34:40 -03:00
loc . sanitize ( current_loc ) ;
2018-11-16 17:53:43 -04:00
set_next_WP ( loc ) ;
2018-09-25 01:11:26 -03:00
vtol_approach_s . approach_stage = LOITER_TO_ALT ;
}
2021-09-10 03:28:21 -03:00
# endif
2018-09-25 01:11:26 -03:00
2015-05-13 03:09:36 -03:00
void Plane : : loiter_set_direction_wp ( const AP_Mission : : Mission_Command & cmd )
2013-01-13 09:29:53 -04:00
{
2019-01-02 00:46:09 -04:00
if ( cmd . content . location . loiter_ccw ) {
2013-04-15 08:31:11 -03:00
loiter . direction = - 1 ;
2013-01-13 09:29:53 -04:00
} else {
2013-04-15 08:31:11 -03:00
loiter . direction = 1 ;
2013-01-13 09:29:53 -04:00
}
}
2015-05-13 03:09:36 -03:00
void Plane : : do_loiter_unlimited ( const AP_Mission : : Mission_Command & cmd )
2011-09-08 22:29:39 -03:00
{
2016-03-02 12:44:09 -04:00
Location cmdloc = cmd . content . location ;
2019-03-26 21:34:40 -03:00
cmdloc . sanitize ( current_loc ) ;
2016-03-02 12:44:09 -04:00
set_next_WP ( cmdloc ) ;
2014-03-03 09:50:45 -04:00
loiter_set_direction_wp ( cmd ) ;
2011-09-08 22:29:39 -03:00
}
2015-05-13 03:09:36 -03:00
void Plane : : do_loiter_turns ( const AP_Mission : : Mission_Command & cmd )
2011-09-08 22:29:39 -03:00
{
2016-03-02 12:44:09 -04:00
Location cmdloc = cmd . content . location ;
2019-03-26 21:34:40 -03:00
cmdloc . sanitize ( current_loc ) ;
2016-03-02 12:44:09 -04:00
set_next_WP ( cmdloc ) ;
2014-03-03 09:50:45 -04:00
loiter_set_direction_wp ( cmd ) ;
2016-03-02 12:44:09 -04:00
loiter . total_cd = ( uint32_t ) ( LOWBYTE ( cmd . p1 ) ) * 36000UL ;
2016-03-02 12:42:27 -04:00
condition_value = 1 ; // used to signify primary turns goal not yet met
2011-09-08 22:29:39 -03:00
}
2015-05-13 03:09:36 -03:00
void Plane : : do_loiter_time ( const AP_Mission : : Mission_Command & cmd )
2011-09-08 22:29:39 -03:00
{
2016-03-02 12:44:09 -04:00
Location cmdloc = cmd . content . location ;
2019-03-26 21:34:40 -03:00
cmdloc . sanitize ( current_loc ) ;
2016-03-02 12:44:09 -04:00
set_next_WP ( cmdloc ) ;
loiter_set_direction_wp ( cmd ) ;
2013-04-15 08:39:14 -03:00
// we set start_time_ms when we reach the waypoint
2016-03-02 12:42:27 -04:00
loiter . time_max_ms = cmd . p1 * ( uint32_t ) 1000 ; // convert sec to ms
condition_value = 1 ; // used to signify primary time goal not yet met
2011-09-08 22:29:39 -03:00
}
2015-05-13 03:09:36 -03:00
void Plane : : do_continue_and_change_alt ( const AP_Mission : : Mission_Command & cmd )
2014-10-21 17:46:01 -03:00
{
2015-08-24 07:06:24 -03:00
// select heading method. Either mission, gps bearing projection or yaw based
// If prev_WP_loc and next_WP_loc are different then an accurate wp based bearing can
// be computed. However, if we had just changed modes before this, such as an aborted landing
// via mode change, the prev and next wps are the same.
float bearing ;
2019-04-08 08:45:29 -03:00
if ( ! prev_WP_loc . same_latlon_as ( next_WP_loc ) ) {
2015-08-24 07:06:24 -03:00
// use waypoint based bearing, this is the usual case
steer_state . hold_course_cd = - 1 ;
2017-12-01 19:44:00 -04:00
} else if ( AP : : gps ( ) . status ( ) > = AP_GPS : : GPS_OK_FIX_2D ) {
2015-08-24 07:06:24 -03:00
// use gps ground course based bearing hold
steer_state . hold_course_cd = - 1 ;
2021-01-21 18:19:38 -04:00
bearing = AP : : gps ( ) . ground_course ( ) ;
2019-04-05 03:11:27 -03:00
next_WP_loc . offset_bearing ( bearing , 1000 ) ; // push it out 1km
2015-08-24 07:06:24 -03:00
} else {
// use yaw based bearing hold
steer_state . hold_course_cd = wrap_360_cd ( ahrs . yaw_sensor ) ;
bearing = ahrs . yaw_sensor * 0.01f ;
2019-04-05 03:11:27 -03:00
next_WP_loc . offset_bearing ( bearing , 1000 ) ; // push it out 1km
2015-08-24 07:06:24 -03:00
}
2014-10-21 17:46:01 -03:00
next_WP_loc . alt = cmd . content . location . alt + home . alt ;
2015-08-18 23:48:13 -03:00
condition_value = cmd . p1 ;
2014-12-03 03:31:23 -04:00
reset_offset_altitude ( ) ;
2014-10-21 17:46:01 -03:00
}
2015-06-13 06:12:54 -03:00
void Plane : : do_altitude_wait ( const AP_Mission : : Mission_Command & cmd )
{
// set all servos to trim until we reach altitude or descent speed
auto_state . idle_mode = true ;
}
2018-11-16 17:52:48 -04:00
void Plane : : do_loiter_to_alt ( const AP_Mission : : Mission_Command & cmd )
2015-03-13 18:48:21 -03:00
{
//set target alt
2016-03-02 12:44:09 -04:00
Location loc = cmd . content . location ;
2019-03-26 21:34:40 -03:00
loc . sanitize ( current_loc ) ;
2016-03-02 12:44:09 -04:00
set_next_WP ( loc ) ;
loiter_set_direction_wp ( cmd ) ;
2015-03-13 18:48:21 -03:00
2017-02-21 07:56:32 -04:00
// init to 0, set to 1 when altitude is reached
condition_value = 0 ;
2015-03-13 18:48:21 -03:00
}
2022-06-09 20:16:47 -03:00
// do_nav_delay - Delay the next navigation command
void Plane : : do_nav_delay ( const AP_Mission : : Mission_Command & cmd )
{
nav_delay . time_start_ms = millis ( ) ;
if ( cmd . content . nav_delay . seconds > 0 ) {
// relative delay
nav_delay . time_max_ms = cmd . content . nav_delay . seconds * 1000 ; // convert seconds to milliseconds
} else {
// absolute delay to utc time
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 ) ;
}
gcs ( ) . send_text ( MAV_SEVERITY_INFO , " Delaying %u sec " , ( unsigned ) ( nav_delay . time_max_ms / 1000 ) ) ;
}
2011-09-08 22:29:39 -03:00
/********************************************************************************/
// Verify Nav (Must) commands
/********************************************************************************/
2015-05-13 03:09:36 -03:00
bool Plane : : verify_takeoff ( )
2011-09-08 22:29:39 -03:00
{
2021-08-11 21:16:27 -03:00
if ( ahrs . dcm_yaw_initialised ( ) & & steer_state . hold_course_cd = = - 1 ) {
2014-10-06 17:17:33 -03:00
const float min_gps_speed = 5 ;
if ( auto_state . takeoff_speed_time_ms = = 0 & &
gps . status ( ) > = AP_GPS : : GPS_OK_FIX_3D & &
2017-03-20 20:54:16 -03:00
gps . ground_speed ( ) > min_gps_speed & &
hal . util - > safety_switch_state ( ) ! = AP_HAL : : Util : : SAFETY_DISARMED ) {
2015-05-13 19:05:32 -03:00
auto_state . takeoff_speed_time_ms = millis ( ) ;
2014-10-06 17:17:33 -03:00
}
if ( auto_state . takeoff_speed_time_ms ! = 0 & &
2015-05-13 19:05:32 -03:00
millis ( ) - auto_state . takeoff_speed_time_ms > = 2000 ) {
2014-10-06 17:17:33 -03:00
// once we reach sufficient speed for good GPS course
// estimation we save our current GPS ground course
// corrected for summed yaw to set the take off
// course. This keeps wings level until we are ready to
2016-05-12 14:10:49 -03:00
// rotate, and also allows us to cope with arbitrary
2014-10-06 17:17:33 -03:00
// compass errors for auto takeoff
2021-01-21 18:19:38 -04:00
float takeoff_course = wrap_PI ( radians ( gps . ground_course ( ) ) ) - steer_state . locked_course_err ;
2014-10-06 17:17:33 -03:00
takeoff_course = wrap_PI ( takeoff_course ) ;
steer_state . hold_course_cd = wrap_360_cd ( degrees ( takeoff_course ) * 100 ) ;
2019-08-30 06:57:30 -03:00
gcs ( ) . send_text ( MAV_SEVERITY_INFO , " Holding course %d at %.1fm/s (%.1f) " ,
( int ) steer_state . hold_course_cd ,
2015-05-03 03:00:05 -03:00
( double ) gps . ground_speed ( ) ,
( double ) degrees ( steer_state . locked_course_err ) ) ;
2012-08-16 21:50:15 -03:00
}
}
2011-09-08 22:29:39 -03:00
2013-10-03 09:01:43 -03:00
if ( steer_state . hold_course_cd ! = - 1 ) {
2013-04-11 21:25:46 -03:00
// call navigation controller for heading hold
2013-10-03 09:01:43 -03:00
nav_controller - > update_heading_hold ( steer_state . hold_course_cd ) ;
2013-04-11 21:25:46 -03:00
} else {
nav_controller - > update_level_flight ( ) ;
2012-08-16 21:50:15 -03:00
}
2011-09-08 22:29:39 -03:00
2019-01-31 19:17:00 -04:00
// check for optional takeoff timeout
if ( takeoff_state . start_time_ms ! = 0 & & g2 . takeoff_timeout > 0 ) {
const float ground_speed = gps . ground_speed ( ) ;
const float takeoff_min_ground_speed = 4 ;
2023-02-10 22:36:33 -04:00
if ( ! arming . is_armed_and_safety_off ( ) ) {
2019-01-31 19:17:00 -04:00
return false ;
}
if ( ground_speed > = takeoff_min_ground_speed ) {
takeoff_state . start_time_ms = 0 ;
} else {
uint32_t now = AP_HAL : : millis ( ) ;
if ( now - takeoff_state . start_time_ms > ( uint32_t ) ( 1000U * g2 . takeoff_timeout ) ) {
gcs ( ) . send_text ( MAV_SEVERITY_INFO , " Takeoff timeout at %.1f m/s " , ground_speed ) ;
2020-02-21 09:09:58 -04:00
plane . arming . disarm ( AP_Arming : : Method : : TAKEOFFTIMEOUT ) ;
2019-01-31 19:17:00 -04:00
mission . reset ( ) ;
}
}
}
2013-06-26 05:36:53 -03:00
// see if we have reached takeoff altitude
2015-02-25 07:54:52 -04:00
int32_t relative_alt_cm = adjusted_relative_altitude_cm ( ) ;
if ( relative_alt_cm > auto_state . takeoff_altitude_rel_cm ) {
2017-07-08 22:15:58 -03:00
gcs ( ) . send_text ( MAV_SEVERITY_INFO , " Takeoff complete at %.2fm " ,
2015-05-03 03:00:05 -03:00
( double ) ( relative_alt_cm * 0.01f ) ) ;
2013-10-03 09:01:43 -03:00
steer_state . hold_course_cd = - 1 ;
2014-04-23 08:57:51 -03:00
auto_state . takeoff_complete = true ;
2014-03-16 01:53:10 -03:00
next_WP_loc = prev_WP_loc = current_loc ;
2014-02-13 18:49:42 -04:00
2022-07-19 08:33:13 -03:00
# if AP_FENCE_ENABLED
2021-03-03 07:49:04 -04:00
plane . fence . auto_enable_fence_after_takeoff ( ) ;
# endif
2014-02-13 18:49:42 -04:00
2014-08-04 07:39:15 -03:00
// don't cross-track on completion of takeoff, as otherwise we
// can end up doing too sharp a turn
2017-11-21 15:41:45 -04:00
auto_state . next_wp_crosstrack = false ;
2012-08-16 21:50:15 -03:00
return true ;
} else {
return false ;
}
2011-09-08 22:29:39 -03:00
}
2014-08-04 07:39:15 -03:00
/*
update navigation for normal mission waypoints . Return true when the
waypoint is complete
*/
2015-05-13 03:09:36 -03:00
bool Plane : : verify_nav_wp ( const AP_Mission : : Mission_Command & cmd )
2011-09-08 22:29:39 -03:00
{
2013-10-03 09:01:43 -03:00
steer_state . hold_course_cd = - 1 ;
2013-04-11 21:25:46 -03:00
2016-12-18 10:39:08 -04:00
// depending on the pass by flag either go to waypoint in regular manner or
// fly past it for set distance along the line of waypoints
Location flex_next_WP_loc = next_WP_loc ;
2017-01-06 21:32:28 -04:00
uint8_t cmd_passby = HIGHBYTE ( cmd . p1 ) ; // distance in meters to pass beyond the wp
uint8_t cmd_acceptance_distance = LOWBYTE ( cmd . p1 ) ; // radius in meters to accept reaching the wp
if ( cmd_passby > 0 ) {
2022-07-03 02:52:16 -03:00
const float dist = prev_WP_loc . get_distance ( flex_next_WP_loc ) ;
const float bearing_deg = degrees ( prev_WP_loc . get_bearing ( flex_next_WP_loc ) ) ;
2016-12-18 10:39:08 -04:00
2022-07-03 02:52:16 -03:00
if ( is_positive ( dist ) ) {
flex_next_WP_loc . offset_bearing ( bearing_deg , cmd_passby ) ;
2017-01-06 21:32:28 -04:00
}
2016-12-18 10:39:08 -04:00
}
2017-11-21 15:41:45 -04:00
if ( auto_state . crosstrack ) {
2016-12-18 10:39:08 -04:00
nav_controller - > update_waypoint ( prev_WP_loc , flex_next_WP_loc ) ;
2017-11-21 15:41:45 -04:00
} else {
nav_controller - > update_waypoint ( current_loc , flex_next_WP_loc ) ;
2014-08-04 07:39:15 -03:00
}
2013-09-13 04:43:00 -03:00
// see if the user has specified a maximum distance to waypoint
2016-12-18 10:39:08 -04:00
// If override with p3 - then this is not used as it will overfly badly
if ( g . waypoint_max_radius > 0 & &
2015-01-01 00:17:45 -04:00
auto_state . wp_distance > ( uint16_t ) g . waypoint_max_radius ) {
2019-04-12 05:23:04 -03:00
if ( current_loc . past_interval_finish_line ( prev_WP_loc , flex_next_WP_loc ) ) {
2013-09-13 04:43:00 -03:00
// this is needed to ensure completion of the waypoint
2017-01-06 21:32:28 -04:00
if ( cmd_passby = = 0 ) {
2016-12-18 10:39:08 -04:00
prev_WP_loc = current_loc ;
}
2013-09-13 04:43:00 -03:00
}
return false ;
}
2014-09-02 22:23:29 -03:00
2017-01-06 21:32:28 -04:00
float acceptance_distance_m = 0 ; // default to: if overflown - let it fly up to the point
if ( cmd_acceptance_distance > 0 ) {
2014-09-02 22:23:29 -03:00
// allow user to override acceptance radius
2017-01-06 21:32:28 -04:00
acceptance_distance_m = cmd_acceptance_distance ;
} else if ( cmd_passby = = 0 ) {
2021-08-30 15:25:45 -03:00
acceptance_distance_m = nav_controller - > turn_distance ( get_wp_radius ( ) , auto_state . next_turn_angle ) ;
2014-09-02 22:23:29 -03:00
}
2022-07-03 02:52:16 -03:00
const float wp_dist = current_loc . get_distance ( flex_next_WP_loc ) ;
if ( wp_dist < = acceptance_distance_m ) {
2017-07-08 22:15:58 -03:00
gcs ( ) . send_text ( MAV_SEVERITY_INFO , " Reached waypoint #%i dist %um " ,
2014-03-03 09:50:45 -04:00
( unsigned ) mission . get_current_nav_cmd ( ) . index ,
2019-02-24 20:11:45 -04:00
( unsigned ) current_loc . get_distance ( flex_next_WP_loc ) ) ;
2012-08-16 21:50:15 -03:00
return true ;
2013-04-11 21:25:46 -03:00
}
2012-07-03 20:21:34 -03:00
// have we flown past the waypoint?
2019-04-12 05:23:04 -03:00
if ( current_loc . past_interval_finish_line ( prev_WP_loc , flex_next_WP_loc ) ) {
2017-07-08 22:15:58 -03:00
gcs ( ) . send_text ( MAV_SEVERITY_INFO , " Passed waypoint #%i dist %um " ,
2014-03-03 09:50:45 -04:00
( unsigned ) mission . get_current_nav_cmd ( ) . index ,
2019-02-24 20:11:45 -04:00
( unsigned ) current_loc . get_distance ( flex_next_WP_loc ) ) ;
2012-07-03 20:21:34 -03:00
return true ;
}
2012-08-16 21:50:15 -03:00
return false ;
2011-09-08 22:29:39 -03:00
}
2018-11-16 17:52:48 -04:00
bool Plane : : verify_loiter_unlim ( const AP_Mission : : Mission_Command & cmd )
2011-09-08 22:29:39 -03:00
{
2020-06-19 14:27:37 -03:00
// else use mission radius
update_loiter ( cmd . p1 ) ;
2012-08-16 21:50:15 -03:00
return false ;
2011-09-08 22:29:39 -03:00
}
2015-05-13 03:09:36 -03:00
bool Plane : : verify_loiter_time ( )
2011-09-08 22:29:39 -03:00
{
2016-03-02 12:42:27 -04:00
bool result = false ;
2017-01-30 13:44:35 -04:00
// mission radius is always aparm.loiter_radius
2016-01-19 00:04:30 -04:00
update_loiter ( 0 ) ;
2016-03-02 12:42:27 -04:00
2013-04-15 08:39:14 -03:00
if ( loiter . start_time_ms = = 0 ) {
2016-05-07 21:40:42 -03:00
if ( reached_loiter_target ( ) & & loiter . sum_cd > 1 ) {
2013-04-15 08:39:14 -03:00
// we've reached the target, start the timer
2015-05-13 19:05:32 -03:00
loiter . start_time_ms = millis ( ) ;
2013-04-15 08:39:14 -03:00
}
2016-03-02 12:42:27 -04:00
} else if ( condition_value ! = 0 ) {
// primary goal, loiter time
if ( ( millis ( ) - loiter . start_time_ms ) > loiter . time_max_ms ) {
// primary goal completed, initialize secondary heading goal
condition_value = 0 ;
result = verify_loiter_heading ( true ) ;
}
} else {
// secondary goal, loiter to heading
result = verify_loiter_heading ( false ) ;
}
if ( result ) {
2017-07-08 22:15:58 -03:00
gcs ( ) . send_text ( MAV_SEVERITY_INFO , " Loiter time complete " ) ;
2016-05-11 02:57:41 -03:00
auto_state . vtol_loiter = false ;
2012-08-16 21:50:15 -03:00
}
2016-03-02 12:42:27 -04:00
return result ;
2011-09-08 22:29:39 -03:00
}
2018-11-16 17:52:48 -04:00
bool Plane : : verify_loiter_turns ( const AP_Mission : : Mission_Command & cmd )
2011-09-08 22:29:39 -03:00
{
2016-03-02 12:42:27 -04:00
bool result = false ;
2018-11-16 17:52:48 -04:00
uint16_t radius = HIGHBYTE ( cmd . p1 ) ;
2022-05-11 00:40:48 -03:00
if ( cmd . type_specific_bits & ( 1U < < 0 ) ) {
// special storage handling allows for larger radii
radius * = 10 ;
}
2016-02-29 14:11:31 -04:00
update_loiter ( radius ) ;
2016-05-11 02:57:41 -03:00
// LOITER_TURNS makes no sense as VTOL
auto_state . vtol_loiter = false ;
2016-03-02 12:42:27 -04:00
if ( condition_value ! = 0 ) {
// primary goal, loiter time
2016-03-06 10:04:17 -04:00
if ( loiter . sum_cd > loiter . total_cd & & loiter . sum_cd > 1 ) {
2016-03-02 12:42:27 -04:00
// primary goal completed, initialize secondary heading goal
condition_value = 0 ;
result = verify_loiter_heading ( true ) ;
}
} else {
// secondary goal, loiter to heading
result = verify_loiter_heading ( false ) ;
}
if ( result ) {
2017-07-08 22:15:58 -03:00
gcs ( ) . send_text ( MAV_SEVERITY_INFO , " Loiter orbits complete " ) ;
2012-08-16 21:50:15 -03:00
}
2016-03-02 12:42:27 -04:00
return result ;
2011-09-08 22:29:39 -03:00
}
2015-04-23 18:39:25 -03:00
/*
verify a LOITER_TO_ALT command . This involves checking we have
reached both the desired altitude and desired heading . The desired
altitude only needs to be reached once .
*/
2018-11-16 17:52:48 -04:00
bool Plane : : verify_loiter_to_alt ( const AP_Mission : : Mission_Command & cmd )
2015-04-23 18:39:25 -03:00
{
2016-03-02 12:42:27 -04:00
bool result = false ;
2018-11-16 17:53:43 -04:00
2018-11-16 17:52:48 -04:00
update_loiter ( cmd . p1 ) ;
2015-03-13 18:48:21 -03:00
2017-02-21 07:56:32 -04:00
// condition_value == 0 means alt has never been reached
if ( condition_value = = 0 ) {
// primary goal, loiter to alt
if ( labs ( loiter . sum_cd ) > 1 & & ( loiter . reached_target_alt | | loiter . unable_to_acheive_target_alt ) ) {
2016-03-02 12:42:27 -04:00
// primary goal completed, initialize secondary heading goal
2017-02-21 07:56:32 -04:00
if ( loiter . unable_to_acheive_target_alt ) {
2019-08-30 06:57:30 -03:00
gcs ( ) . send_text ( MAV_SEVERITY_INFO , " Loiter to alt was stuck at %d " , int ( current_loc . alt / 100 ) ) ;
2017-02-21 07:56:32 -04:00
}
condition_value = 1 ;
2016-03-02 12:42:27 -04:00
result = verify_loiter_heading ( true ) ;
2015-03-13 18:48:21 -03:00
}
2016-03-02 12:42:27 -04:00
} else {
// secondary goal, loiter to heading
result = verify_loiter_heading ( false ) ;
2015-03-13 18:48:21 -03:00
}
2015-07-20 19:28:25 -03:00
2016-03-02 12:42:27 -04:00
if ( result ) {
2017-07-08 22:15:58 -03:00
gcs ( ) . send_text ( MAV_SEVERITY_INFO , " Loiter to alt complete " ) ;
2016-03-02 12:42:27 -04:00
}
return result ;
2015-03-13 18:48:21 -03:00
}
2015-05-13 03:09:36 -03:00
bool Plane : : verify_RTL ( )
2011-09-08 22:29:39 -03:00
{
2016-01-19 00:04:30 -04:00
if ( g . rtl_radius < 0 ) {
loiter . direction = - 1 ;
} else {
loiter . direction = 1 ;
}
update_loiter ( abs ( g . rtl_radius ) ) ;
2021-08-30 15:25:45 -03:00
if ( auto_state . wp_distance < = ( uint32_t ) MAX ( get_wp_radius ( ) , 0 ) | |
2016-05-07 21:40:42 -03:00
reached_loiter_target ( ) ) {
2017-07-08 22:15:58 -03:00
gcs ( ) . send_text ( MAV_SEVERITY_INFO , " Reached RTL location " ) ;
2013-04-11 21:25:46 -03:00
return true ;
} else {
2012-08-16 21:50:15 -03:00
return false ;
2013-04-11 21:25:46 -03:00
}
2011-09-08 22:29:39 -03:00
}
2015-05-13 03:09:36 -03:00
bool Plane : : verify_continue_and_change_alt ( )
2014-10-21 17:46:01 -03:00
{
2015-08-24 07:06:24 -03:00
// is waypoint info not available and heading hold is?
2019-04-08 08:45:29 -03:00
if ( prev_WP_loc . same_latlon_as ( next_WP_loc ) & &
2015-08-24 07:06:24 -03:00
steer_state . hold_course_cd ! = - 1 ) {
//keep flying the same course with fixed steering heading computed at start if cmd
nav_controller - > update_heading_hold ( steer_state . hold_course_cd ) ;
}
else {
// Is the next_WP less than 200 m away?
2019-02-24 20:11:45 -04:00
if ( current_loc . get_distance ( next_WP_loc ) < 200.0f ) {
2015-08-24 07:06:24 -03:00
//push another 300 m down the line
2019-04-05 10:02:44 -03:00
int32_t next_wp_bearing_cd = prev_WP_loc . get_bearing_to ( next_WP_loc ) ;
2019-04-05 03:11:27 -03:00
next_WP_loc . offset_bearing ( next_wp_bearing_cd * 0.01f , 300.0f ) ;
2015-08-24 07:06:24 -03:00
}
//keep flying the same course
nav_controller - > update_waypoint ( prev_WP_loc , next_WP_loc ) ;
}
2015-08-18 23:48:13 -03:00
//climbing?
if ( condition_value = = 1 & & adjusted_altitude_cm ( ) > = next_WP_loc . alt ) {
return true ;
}
//descending?
else if ( condition_value = = 2 & &
adjusted_altitude_cm ( ) < = next_WP_loc . alt ) {
return true ;
}
//don't care if we're climbing or descending
2015-08-27 03:22:44 -03:00
else if ( labs ( adjusted_altitude_cm ( ) - next_WP_loc . alt ) < = 500 ) {
2014-10-21 17:46:01 -03:00
return true ;
}
return false ;
}
2015-06-13 06:12:54 -03:00
/*
see if we have reached altitude or descent speed
*/
bool Plane : : verify_altitude_wait ( const AP_Mission : : Mission_Command & cmd )
{
if ( current_loc . alt > cmd . content . altitude_wait . altitude * 100.0f ) {
2017-07-08 22:15:58 -03:00
gcs ( ) . send_text ( MAV_SEVERITY_INFO , " Reached altitude " ) ;
2015-06-13 06:12:54 -03:00
return true ;
}
if ( auto_state . sink_rate > cmd . content . altitude_wait . descent_rate ) {
2017-07-08 22:15:58 -03:00
gcs ( ) . send_text ( MAV_SEVERITY_INFO , " Reached descent rate %.1f m/s " , ( double ) auto_state . sink_rate ) ;
2015-06-13 06:12:54 -03:00
return true ;
}
// if requested, wiggle servos
if ( cmd . content . altitude_wait . wiggle_time ! = 0 ) {
static uint32_t last_wiggle_ms ;
if ( auto_state . idle_wiggle_stage = = 0 & &
2015-11-19 23:04:52 -04:00
AP_HAL : : millis ( ) - last_wiggle_ms > cmd . content . altitude_wait . wiggle_time * 1000 ) {
2015-06-13 06:12:54 -03:00
auto_state . idle_wiggle_stage = 1 ;
2015-11-19 23:04:52 -04:00
last_wiggle_ms = AP_HAL : : millis ( ) ;
2015-06-13 06:12:54 -03:00
}
// idle_wiggle_stage is updated in set_servos_idle()
}
return false ;
}
2022-06-09 20:16:47 -03:00
// verify_nav_delay - check if we have waited long enough
bool Plane : : verify_nav_delay ( const AP_Mission : : Mission_Command & cmd )
{
2023-02-10 22:36:33 -04:00
if ( arming . is_armed_and_safety_off ( ) ) {
2022-06-09 20:16:47 -03:00
// don't delay while armed, we need a nav controller running
return true ;
}
if ( millis ( ) - nav_delay . time_start_ms > nav_delay . time_max_ms ) {
nav_delay . time_max_ms = 0 ;
return true ;
}
return false ;
}
2011-09-08 22:29:39 -03:00
/********************************************************************************/
// Condition (May) commands
/********************************************************************************/
2015-05-13 03:09:36 -03:00
void Plane : : do_wait_delay ( const AP_Mission : : Mission_Command & cmd )
2011-09-08 22:29:39 -03:00
{
2015-05-13 19:05:32 -03:00
condition_start = millis ( ) ;
2014-03-17 02:16:45 -03:00
condition_value = cmd . content . delay . seconds * 1000 ; // convert seconds to milliseconds
2011-09-08 22:29:39 -03:00
}
2015-05-13 03:09:36 -03:00
void Plane : : do_within_distance ( const AP_Mission : : Mission_Command & cmd )
2011-09-08 22:29:39 -03:00
{
2014-03-17 02:16:45 -03:00
condition_value = cmd . content . distance . meters ;
2011-09-08 22:29:39 -03:00
}
/********************************************************************************/
// Verify Condition (May) commands
/********************************************************************************/
2015-05-13 03:09:36 -03:00
bool Plane : : verify_wait_delay ( )
2011-09-08 22:29:39 -03:00
{
2015-05-13 19:05:32 -03:00
if ( ( unsigned ) ( millis ( ) - condition_start ) > ( unsigned ) condition_value ) {
2012-08-16 21:50:15 -03:00
condition_value = 0 ;
return true ;
}
return false ;
2011-09-08 22:29:39 -03:00
}
2015-05-13 03:09:36 -03:00
bool Plane : : verify_within_distance ( )
2011-09-08 22:29:39 -03:00
{
2015-11-27 13:11:58 -04:00
if ( auto_state . wp_distance < MAX ( condition_value , 0 ) ) {
2012-08-16 21:50:15 -03:00
condition_value = 0 ;
return true ;
}
return false ;
2011-09-08 22:29:39 -03:00
}
/********************************************************************************/
// Do (Now) commands
/********************************************************************************/
2015-05-13 03:09:36 -03:00
void Plane : : do_loiter_at_location ( )
2011-09-08 22:29:39 -03:00
{
2017-01-30 13:44:35 -04:00
if ( aparm . loiter_radius < 0 ) {
2013-04-15 08:31:11 -03:00
loiter . direction = - 1 ;
2013-04-14 09:04:25 -03:00
} else {
2013-04-15 08:31:11 -03:00
loiter . direction = 1 ;
2013-04-14 09:04:25 -03:00
}
2014-03-16 01:53:10 -03:00
next_WP_loc = current_loc ;
2011-09-08 22:29:39 -03:00
}
2020-10-04 15:20:47 -03:00
bool Plane : : do_change_speed ( const AP_Mission : : Mission_Command & cmd )
2011-09-08 22:29:39 -03:00
{
2014-03-17 02:16:45 -03:00
switch ( cmd . content . speed . speed_type )
2012-08-16 21:50:15 -03:00
{
case 0 : // Airspeed
2022-04-15 20:07:11 -03:00
if ( is_equal ( cmd . content . speed . target_ms , - 2.0f ) ) {
new_airspeed_cm = - 1 ; // return to default airspeed
return true ;
} else if ( ( cmd . content . speed . target_ms > = aparm . airspeed_min . get ( ) ) & &
( cmd . content . speed . target_ms < = aparm . airspeed_max . get ( ) ) ) {
new_airspeed_cm = cmd . content . speed . target_ms * 100 ; //new airspeed target for AUTO or GUIDED modes
2017-07-08 22:15:58 -03:00
gcs ( ) . send_text ( MAV_SEVERITY_INFO , " Set airspeed %u m/s " , ( unsigned ) cmd . content . speed . target_ms ) ;
2020-10-04 15:20:47 -03:00
return true ;
2012-08-16 21:50:15 -03:00
}
break ;
case 1 : // Ground speed
2017-07-08 22:15:58 -03:00
gcs ( ) . send_text ( MAV_SEVERITY_INFO , " Set groundspeed %u " , ( unsigned ) cmd . content . speed . target_ms ) ;
2016-11-17 21:07:10 -04:00
aparm . min_gndspeed_cm . set ( cmd . content . speed . target_ms * 100 ) ;
2020-10-04 15:20:47 -03:00
return true ;
2012-08-16 21:50:15 -03:00
}
2011-09-08 22:29:39 -03:00
2014-03-18 23:13:47 -03:00
if ( cmd . content . speed . throttle_pct > 0 & & cmd . content . speed . throttle_pct < = 100 ) {
2017-07-08 22:15:58 -03:00
gcs ( ) . send_text ( MAV_SEVERITY_INFO , " Set throttle %u " , ( unsigned ) cmd . content . speed . throttle_pct ) ;
2014-03-17 02:16:45 -03:00
aparm . throttle_cruise . set ( cmd . content . speed . throttle_pct ) ;
2020-10-04 15:20:47 -03:00
return true ;
2012-09-12 00:09:32 -03:00
}
2020-10-04 15:20:47 -03:00
return false ;
2011-09-08 22:29:39 -03:00
}
2015-05-13 03:09:36 -03:00
void Plane : : do_set_home ( const AP_Mission : : Mission_Command & cmd )
2011-09-08 22:29:39 -03:00
{
2014-03-28 16:52:48 -03:00
if ( cmd . p1 = = 1 & & gps . status ( ) > = AP_GPS : : GPS_OK_FIX_3D ) {
2018-05-29 20:47:50 -03:00
if ( ! set_home_persistently ( gps . location ( ) ) ) {
// silently ignore error
}
2012-08-16 21:50:15 -03:00
} else {
2019-02-13 17:46:04 -04:00
if ( ! AP : : ahrs ( ) . set_home ( cmd . content . location ) ) {
// silently ignore failure
2018-05-29 20:47:50 -03:00
}
2012-08-16 21:50:15 -03:00
}
2011-09-08 22:29:39 -03:00
}
2014-03-17 04:09:29 -03:00
// start_command_callback - callback function called from ap-mission when it begins a new mission command
// 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
2015-05-13 03:09:36 -03:00
bool Plane : : start_command_callback ( const AP_Mission : : Mission_Command & cmd )
2014-03-17 04:09:29 -03:00
{
2019-01-15 13:46:13 -04:00
if ( control_mode = = & mode_auto ) {
2014-03-17 04:09:29 -03:00
return start_command ( cmd ) ;
}
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
2015-05-13 03:09:36 -03:00
bool Plane : : verify_command_callback ( const AP_Mission : : Mission_Command & cmd )
2014-03-13 23:48:58 -03:00
{
2019-01-15 13:46:13 -04:00
if ( control_mode = = & mode_auto ) {
2015-07-20 03:11:34 -03:00
bool cmd_complete = verify_command ( cmd ) ;
// send message to GCS
if ( cmd_complete ) {
2017-07-07 22:55:12 -03:00
gcs ( ) . send_mission_item_reached_message ( cmd . index ) ;
2015-07-20 03:11:34 -03:00
}
return cmd_complete ;
2014-03-13 23:48:58 -03:00
}
return false ;
}
2014-03-17 04:09:29 -03:00
// exit_mission_callback - callback function called from ap-mission when the mission has completed
// 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
2015-05-13 03:09:36 -03:00
void Plane : : exit_mission_callback ( )
2014-03-13 23:48:58 -03:00
{
2019-01-15 13:46:13 -04:00
if ( control_mode = = & mode_auto ) {
2019-10-17 00:49:32 -03:00
set_mode ( mode_rtl , ModeReason : : MISSION_END ) ;
2017-07-08 22:15:58 -03:00
gcs ( ) . send_text ( MAV_SEVERITY_INFO , " Mission complete, changing mode to RTL " ) ;
2014-03-13 23:48:58 -03:00
}
}
2018-09-25 01:11:26 -03:00
2021-09-10 03:28:21 -03:00
# if HAL_QUADPLANE_ENABLED
2018-09-25 01:11:26 -03:00
bool Plane : : verify_landing_vtol_approach ( const AP_Mission : : Mission_Command & cmd )
{
2022-06-28 21:10:51 -03:00
const float radius = is_zero ( quadplane . fw_land_approach_radius ) ? aparm . loiter_radius : quadplane . fw_land_approach_radius ;
const int8_t direction = is_negative ( radius ) ? - 1 : 1 ;
const float abs_radius = fabsf ( radius ) ;
2023-01-14 19:36:56 -04:00
loiter . direction = direction ;
2018-09-25 01:11:26 -03:00
switch ( vtol_approach_s . approach_stage ) {
2021-03-23 18:27:37 -03:00
case RTL :
{
// fly home and loiter at RTL alt
2022-07-14 20:28:13 -03:00
nav_controller - > update_loiter ( cmd . content . location , abs_radius , direction ) ;
2021-03-23 18:27:37 -03:00
if ( plane . reached_loiter_target ( ) ) {
// decend to Q RTL alt
plane . do_RTL ( plane . home . alt + plane . quadplane . qrtl_alt * 100UL ) ;
plane . loiter_angle_reset ( ) ;
vtol_approach_s . approach_stage = LOITER_TO_ALT ;
}
break ;
}
2018-09-25 01:11:26 -03:00
case LOITER_TO_ALT :
2018-11-16 17:53:43 -04:00
{
2022-07-14 20:28:13 -03:00
nav_controller - > update_loiter ( cmd . content . location , abs_radius , direction ) ;
2018-11-16 17:53:43 -04:00
if ( labs ( loiter . sum_cd ) > 1 & & ( loiter . reached_target_alt | | loiter . unable_to_acheive_target_alt ) ) {
Vector3f wind = ahrs . wind_estimate ( ) ;
vtol_approach_s . approach_direction_deg = degrees ( atan2f ( - wind . y , - wind . x ) ) ;
gcs ( ) . send_text ( MAV_SEVERITY_INFO , " Selected an approach path of %.1f " , ( double ) vtol_approach_s . approach_direction_deg ) ;
2018-12-05 17:18:27 -04:00
vtol_approach_s . approach_stage = ENSURE_RADIUS ;
2018-11-16 17:53:43 -04:00
}
break ;
2018-09-25 01:11:26 -03:00
}
2018-12-05 17:18:27 -04:00
case ENSURE_RADIUS :
{
// validate that the vehicle is at least the expected distance away from the loiter point
// require an angle total of at least 2 centidegrees, due to special casing of 1 centidegree
2023-06-14 12:26:50 -03:00
if ( ( ( fabsF ( cmd . content . location . get_distance ( current_loc ) - abs_radius ) > 5.0f ) & &
2022-06-28 21:10:51 -03:00
( cmd . content . location . get_distance ( current_loc ) < abs_radius ) ) | |
2022-07-14 20:29:37 -03:00
( labs ( loiter . sum_cd ) < 2 ) ) {
2022-06-28 21:10:51 -03:00
nav_controller - > update_loiter ( cmd . content . location , abs_radius , direction ) ;
2018-12-05 17:18:27 -04:00
break ;
}
vtol_approach_s . approach_stage = WAIT_FOR_BREAKOUT ;
FALLTHROUGH ;
}
2018-09-25 01:11:26 -03:00
case WAIT_FOR_BREAKOUT :
{
2018-12-05 17:18:27 -04:00
nav_controller - > update_loiter ( cmd . content . location , radius , direction ) ;
2018-09-25 01:11:26 -03:00
2022-07-14 20:28:56 -03:00
const float breakout_direction_rad = radians ( vtol_approach_s . approach_direction_deg + ( direction > 0 ? 270 : 90 ) ) ;
2018-09-25 01:11:26 -03:00
// breakout when within 5 degrees of the opposite direction
2023-06-14 12:26:50 -03:00
if ( fabsF ( wrap_PI ( ahrs . yaw - breakout_direction_rad ) ) < radians ( 5.0f ) ) {
2018-09-25 01:11:26 -03:00
gcs ( ) . send_text ( MAV_SEVERITY_INFO , " Starting VTOL land approach path " ) ;
vtol_approach_s . approach_stage = APPROACH_LINE ;
set_next_WP ( cmd . content . location ) ;
// fallthrough
} else {
break ;
}
FALLTHROUGH ;
}
case APPROACH_LINE :
{
// project an apporach path
Location start = cmd . content . location ;
Location end = cmd . content . location ;
// project a 1km waypoint to either side of the landing location
2019-04-05 03:11:27 -03:00
start . offset_bearing ( vtol_approach_s . approach_direction_deg + 180 , 1000 ) ;
end . offset_bearing ( vtol_approach_s . approach_direction_deg , 1000 ) ;
2018-09-25 01:11:26 -03:00
nav_controller - > update_waypoint ( start , end ) ;
// check if we should move on to the next waypoint
2022-07-14 13:01:22 -03:00
Location breakout_stopping_loc = cmd . content . location ;
breakout_stopping_loc . offset_bearing ( vtol_approach_s . approach_direction_deg + 180 , quadplane . stopping_distance ( ) ) ;
const bool past_finish_line = current_loc . past_interval_finish_line ( start , breakout_stopping_loc ) ;
2022-06-28 21:10:51 -03:00
2022-07-14 13:01:22 -03:00
Location breakout_loc = cmd . content . location ;
breakout_loc . offset_bearing ( vtol_approach_s . approach_direction_deg + 180 , abs_radius ) ;
const bool half_radius = current_loc . line_path_proportion ( breakout_loc , cmd . content . location ) > 0.5 ;
2022-06-28 21:10:51 -03:00
bool lined_up = true ;
Vector3f vel_NED ;
if ( ahrs . get_velocity_NED ( vel_NED ) ) {
const Vector2f target_vec = current_loc . get_distance_NE ( cmd . content . location ) ;
const float angle_err = fabsf ( wrap_180 ( degrees ( vel_NED . xy ( ) . angle ( target_vec ) ) ) ) ;
lined_up = ( angle_err < 30 ) ;
}
if ( past_finish_line & & ( lined_up | | half_radius ) ) {
2018-09-25 01:11:26 -03:00
vtol_approach_s . approach_stage = VTOL_LANDING ;
quadplane . do_vtol_land ( cmd ) ;
// fallthrough
} else {
break ;
}
FALLTHROUGH ;
}
case VTOL_LANDING :
// nothing to do here, we should be into the quadplane landing code
return true ;
}
return false ;
}
2021-09-10 03:28:21 -03:00
# endif // HAL_QUADPLANE_ENABLED
2016-03-02 12:42:27 -04:00
bool Plane : : verify_loiter_heading ( bool init )
{
2021-09-10 03:28:21 -03:00
# if HAL_QUADPLANE_ENABLED
2016-05-07 21:40:42 -03:00
if ( quadplane . in_vtol_auto ( ) ) {
// skip heading verify if in VTOL auto
return true ;
}
2021-09-10 03:28:21 -03:00
# endif
2016-05-07 21:40:42 -03:00
2016-03-02 12:42:27 -04:00
//Get the lat/lon of next Nav waypoint after this one:
AP_Mission : : Mission_Command next_nav_cmd ;
if ( ! mission . get_next_nav_cmd ( mission . get_current_nav_index ( ) + 1 ,
next_nav_cmd ) ) {
//no next waypoint to shoot for -- go ahead and break out of loiter
return true ;
}
2019-06-05 17:24:15 -03:00
if ( init ) {
loiter . sum_cd = 0 ;
}
2019-06-07 12:08:28 -03:00
return plane . mode_loiter . isHeadingLinedUp ( next_WP_loc , next_nav_cmd . content . location ) ;
2016-03-02 12:42:27 -04:00
}
2021-08-30 15:25:45 -03:00
float Plane : : get_wp_radius ( ) const
{
# if HAL_QUADPLANE_ENABLED
if ( plane . quadplane . in_vtol_mode ( ) ) {
return plane . quadplane . wp_nav - > get_wp_radius_cm ( ) * 0.01 ;
}
# endif
return g . waypoint_radius ;
}
2021-10-25 00:59:23 -03:00
2021-11-15 01:08:34 -04:00
# if AP_SCRIPTING_ENABLED
2021-10-25 00:59:23 -03:00
/*
support for scripted navigation , with verify operation for completion
*/
void Plane : : do_nav_script_time ( const AP_Mission : : Mission_Command & cmd )
{
2022-10-26 19:50:10 -03:00
nav_scripting . enabled = true ;
2021-10-25 00:59:23 -03:00
nav_scripting . id + + ;
nav_scripting . start_ms = AP_HAL : : millis ( ) ;
2022-10-26 19:50:10 -03:00
nav_scripting . current_ms = nav_scripting . start_ms ;
2021-10-25 00:59:23 -03:00
// start with current roll rate, pitch rate and throttle
nav_scripting . roll_rate_dps = plane . rollController . get_pid_info ( ) . target ;
nav_scripting . pitch_rate_dps = plane . pitchController . get_pid_info ( ) . target ;
2022-09-15 00:51:06 -03:00
nav_scripting . yaw_rate_dps = degrees ( ahrs . get_gyro ( ) . z ) ;
2021-10-25 00:59:23 -03:00
nav_scripting . throttle_pct = SRV_Channels : : get_output_scaled ( SRV_Channel : : k_throttle ) ;
}
/*
wait for scripting to say that the mission item is complete
*/
bool Plane : : verify_nav_script_time ( const AP_Mission : : Mission_Command & cmd )
{
if ( cmd . content . nav_script_time . timeout_s > 0 ) {
const uint32_t now = AP_HAL : : millis ( ) ;
if ( now - nav_scripting . start_ms > cmd . content . nav_script_time . timeout_s * 1000U ) {
gcs ( ) . send_text ( MAV_SEVERITY_INFO , " NavScriptTime timed out " ) ;
2022-10-26 19:50:10 -03:00
nav_scripting . enabled = false ;
2022-12-22 17:21:59 -04:00
nav_scripting . rudder_offset_pct = 0 ;
nav_scripting . run_yaw_rate_controller = true ;
2021-10-25 00:59:23 -03:00
}
}
2022-10-26 19:50:10 -03:00
return ! nav_scripting . enabled ;
2021-10-25 00:59:23 -03:00
}
// check if we are in a NAV_SCRIPT_* command
2022-10-26 19:50:10 -03:00
bool Plane : : nav_scripting_active ( void )
2021-10-25 00:59:23 -03:00
{
2022-11-14 04:01:19 -04:00
if ( nav_scripting . enabled & & AP_HAL : : millis ( ) - nav_scripting . current_ms > 1000 ) {
// set_target_throttle_rate_rpy has not been called from script in last 1000ms
2022-10-26 19:50:10 -03:00
nav_scripting . enabled = false ;
nav_scripting . current_ms = 0 ;
2022-12-22 17:21:59 -04:00
nav_scripting . rudder_offset_pct = 0 ;
nav_scripting . run_yaw_rate_controller = true ;
2022-11-05 00:24:02 -03:00
gcs ( ) . send_text ( MAV_SEVERITY_INFO , " NavScript time out " ) ;
2022-10-26 19:50:10 -03:00
}
if ( control_mode = = & mode_auto & &
mission . get_current_nav_cmd ( ) . id ! = MAV_CMD_NAV_SCRIPT_TIME ) {
nav_scripting . enabled = false ;
}
return nav_scripting . enabled ;
2021-10-25 00:59:23 -03:00
}
// support for NAV_SCRIPTING mission command
2022-10-13 21:37:52 -03:00
bool Plane : : nav_script_time ( uint16_t & id , uint8_t & cmd , float & arg1 , float & arg2 , int16_t & arg3 , int16_t & arg4 )
2021-10-25 00:59:23 -03:00
{
if ( ! nav_scripting_active ( ) ) {
// not in NAV_SCRIPT_TIME
return false ;
}
const auto & c = mission . get_current_nav_cmd ( ) . content . nav_script_time ;
id = nav_scripting . id ;
cmd = c . command ;
2022-10-13 17:31:05 -03:00
arg1 = c . arg1 . get ( ) ;
arg2 = c . arg2 . get ( ) ;
2022-10-13 21:37:52 -03:00
arg3 = c . arg3 ;
arg4 = c . arg4 ;
2021-10-25 00:59:23 -03:00
return true ;
}
// called when script has completed the command
void Plane : : nav_script_time_done ( uint16_t id )
{
if ( id = = nav_scripting . id ) {
2022-10-26 19:50:10 -03:00
nav_scripting . enabled = false ;
2021-10-25 00:59:23 -03:00
}
}
2022-02-06 22:23:17 -04:00
// support for NAV_SCRIPTING mission command and aerobatics in other allowed modes
2022-02-07 16:29:39 -04:00
void Plane : : set_target_throttle_rate_rpy ( float throttle_pct , float roll_rate_dps , float pitch_rate_dps , float yaw_rate_dps )
2021-10-25 00:59:23 -03:00
{
2022-01-21 16:59:13 -04:00
nav_scripting . roll_rate_dps = constrain_float ( roll_rate_dps , - g . acro_roll_rate , g . acro_roll_rate ) ;
nav_scripting . pitch_rate_dps = constrain_float ( pitch_rate_dps , - g . acro_pitch_rate , g . acro_pitch_rate ) ;
nav_scripting . yaw_rate_dps = constrain_float ( yaw_rate_dps , - g . acro_yaw_rate , g . acro_yaw_rate ) ;
2022-10-26 18:55:10 -03:00
nav_scripting . throttle_pct = constrain_float ( throttle_pct , aparm . throttle_min , aparm . throttle_max ) ;
2022-02-06 22:23:17 -04:00
nav_scripting . current_ms = AP_HAL : : millis ( ) ;
2021-10-25 00:59:23 -03:00
}
2022-02-06 22:23:17 -04:00
2022-12-22 17:21:59 -04:00
// support for rudder offset override in aerobatic scripting
void Plane : : set_rudder_offset ( float rudder_pct , bool run_yaw_rate_controller )
{
nav_scripting . rudder_offset_pct = rudder_pct ;
nav_scripting . run_yaw_rate_controller = run_yaw_rate_controller ;
}
2022-02-06 22:23:17 -04:00
// enable NAV_SCRIPTING takeover in modes other than AUTO using script time mission commands
bool Plane : : nav_scripting_enable ( uint8_t mode )
{
uint8_t current_control_mode = control_mode - > mode_number ( ) ;
if ( current_control_mode = = mode ) {
switch ( current_control_mode ) {
case Mode : : Number : : CIRCLE :
case Mode : : Number : : STABILIZE :
case Mode : : Number : : ACRO :
case Mode : : Number : : FLY_BY_WIRE_A :
case Mode : : Number : : FLY_BY_WIRE_B :
case Mode : : Number : : CRUISE :
case Mode : : Number : : LOITER :
nav_scripting . enabled = true ;
2022-11-05 00:24:02 -03:00
nav_scripting . current_ms = AP_HAL : : millis ( ) ;
2022-02-06 22:23:17 -04:00
break ;
default :
nav_scripting . enabled = false ;
}
} else {
nav_scripting . enabled = false ;
}
return nav_scripting . enabled ;
}
2021-11-15 01:08:34 -04:00
# endif // AP_SCRIPTING_ENABLED
2023-01-17 02:47:03 -04:00
/*
return true if this is a LAND command
note that we consider a PAYLOAD_PLACE to be a land command as it
follows the landing logic for quadplanes
*/
bool Plane : : is_land_command ( uint16_t command ) const
{
return
command = = MAV_CMD_NAV_VTOL_LAND | |
command = = MAV_CMD_NAV_LAND | |
command = = MAV_CMD_NAV_PAYLOAD_PLACE ;
}
/*
return true if in a specific AUTO mission command
*/
bool Plane : : in_auto_mission_id ( uint16_t command ) const
{
return control_mode = = & mode_auto & & mission . get_current_nav_id ( ) = = command ;
}