2014-02-22 20:14:44 -04:00
/// @file AP_Mission.h
/// @brief Handles the MAVLINK command mission stack. Reads and writes mission to storage.
/*
* The AP_Mission library :
* - responsible for managing a list of commands made up of " nav " , " do " and " conditional " commands
* - reads and writes the mission commands to storage .
2016-05-12 13:59:11 -03:00
* - provides easy access to current , previous and upcoming waypoints
2014-02-22 20:14:44 -04:00
* - calls main program ' s command execution and verify functions .
* - accounts for the DO_JUMP command
*
*/
2016-02-17 21:25:36 -04:00
# pragma once
2014-02-22 20:14:44 -04:00
2022-08-14 19:18:01 -03:00
# include "AP_Mission_config.h"
2021-05-19 23:34:14 -03:00
2015-08-11 03:28:44 -03:00
# include <GCS_MAVLink/GCS_MAVLink.h>
# include <AP_Math/AP_Math.h>
# include <AP_Common/AP_Common.h>
2019-01-01 23:13:08 -04:00
# include <AP_Common/Location.h>
2015-08-11 03:28:44 -03:00
# include <AP_Param/AP_Param.h>
# include <StorageManager/StorageManager.h>
2022-10-13 17:30:41 -03:00
# include <AP_Common/float16.h>
2014-02-22 20:14:44 -04:00
// definitions
2014-03-20 02:57:01 -03:00
# define AP_MISSION_EEPROM_VERSION 0x65AE // version number stored in first four bytes of eeprom. increment this by one when eeprom format is changed
2014-02-22 20:14:44 -04:00
# define AP_MISSION_EEPROM_COMMAND_SIZE 15 // size in bytes of all mission commands
2021-10-12 19:50:03 -03:00
# ifndef AP_MISSION_MAX_NUM_DO_JUMP_COMMANDS
# if HAL_MEM_CLASS >= HAL_MEM_CLASS_500
# define AP_MISSION_MAX_NUM_DO_JUMP_COMMANDS 100 // allow up to 100 do-jump commands
# else
2015-11-03 09:46:29 -04:00
# define AP_MISSION_MAX_NUM_DO_JUMP_COMMANDS 15 // allow up to 15 do-jump commands
2021-10-12 19:50:03 -03:00
# endif
# endif
2014-12-18 04:01:56 -04:00
2014-02-28 08:23:38 -04:00
# define AP_MISSION_JUMP_REPEAT_FOREVER -1 // when do-jump command's repeat count is -1 this means endless repeat
2014-02-22 20:14:44 -04:00
# define AP_MISSION_CMD_ID_NONE 0 // mavlink cmd id of zero means invalid or missing command
2014-02-28 08:49:37 -04:00
# define AP_MISSION_CMD_INDEX_NONE 65535 // command index of 65535 means invalid or missing command
# define AP_MISSION_JUMP_TIMES_MAX 32767 // maximum number of times a jump can be executed. Used when jump tracking fails (i.e. when too many jumps in mission)
2014-02-22 20:14:44 -04:00
2014-02-27 09:02:12 -04:00
# define AP_MISSION_FIRST_REAL_COMMAND 1 // command #0 reserved to hold home position
2014-05-08 11:06:06 -03:00
# define AP_MISSION_RESTART_DEFAULT 0 // resume the mission from the last command run by default
2017-08-27 08:12:45 -03:00
# define AP_MISSION_OPTIONS_DEFAULT 0 // Do not clear the mission when rebooting
# define AP_MISSION_MASK_MISSION_CLEAR (1<<0) // If set then Clear the mission on boot
2020-02-17 19:44:53 -04:00
# define AP_MISSION_MASK_DIST_TO_LAND_CALC (1<<1) // Allow distance to best landing calculation to be run on failsafe
2020-03-03 23:28:41 -04:00
# define AP_MISSION_MASK_CONTINUE_AFTER_LAND (1<<2) // Allow mission to continue after land
2017-08-27 08:12:45 -03:00
2020-02-24 18:43:20 -04:00
# define AP_MISSION_MAX_WP_HISTORY 7 // The maximum number of previous wp commands that will be stored from the active missions history
# define LAST_WP_PASSED (AP_MISSION_MAX_WP_HISTORY-2)
2023-02-14 05:39:36 -04:00
# if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
# define AP_MISSION_SDCARD_FILENAME "APM / mission.stg"
# else
# define AP_MISSION_SDCARD_FILENAME "mission.stg"
# endif
2022-10-18 22:44:33 -03:00
union PackedContent ;
2014-02-22 20:14:44 -04:00
/// @class AP_Mission
/// @brief Object managing Mission
2020-05-04 21:27:56 -03:00
class AP_Mission
{
2014-02-22 20:14:44 -04:00
public :
// jump command structure
2014-03-17 02:14:45 -03:00
struct PACKED Jump_Command {
uint16_t target ; // target command id
int16_t num_times ; // num times to repeat. -1 = repeat forever
2014-02-22 20:14:44 -04:00
} ;
2014-03-17 02:14:45 -03:00
// condition delay command structure
struct PACKED Conditional_Delay_Command {
2014-03-18 23:13:04 -03:00
float seconds ; // period of delay in seconds
2014-03-17 02:14:45 -03:00
} ;
// condition delay command structure
struct PACKED Conditional_Distance_Command {
2014-03-18 23:13:04 -03:00
float meters ; // distance from next waypoint in meters
2014-03-17 02:14:45 -03:00
} ;
// condition yaw command structure
struct PACKED Yaw_Command {
2014-03-18 23:13:04 -03:00
float angle_deg ; // target angle in degrees (0=north, 90=east)
float turn_rate_dps ; // turn rate in degrees / second (0=use default)
int8_t direction ; // -1 = ccw, +1 = cw
uint8_t relative_angle ; // 0 = absolute angle, 1 = relative angle
2014-03-17 02:14:45 -03:00
} ;
// change speed command structure
struct PACKED Change_Speed_Command {
uint8_t speed_type ; // 0=airspeed, 1=ground speed
2014-03-18 23:13:04 -03:00
float target_ms ; // target speed in m/s, -1 means no change
2020-01-04 07:46:46 -04:00
float throttle_pct ; // throttle as a percentage (i.e. 1 ~ 100), 0 means no change
2014-03-17 02:14:45 -03:00
} ;
2014-03-18 23:13:04 -03:00
// set relay command structure
2014-03-17 02:14:45 -03:00
struct PACKED Set_Relay_Command {
uint8_t num ; // relay number from 1 to 4
uint8_t state ; // on = 3.3V or 5V (depending upon board), off = 0V. only used for do-set-relay, not for do-repeat-relay
2014-03-18 23:13:04 -03:00
} ;
// repeat relay command structure
struct PACKED Repeat_Relay_Command {
uint8_t num ; // relay number from 1 to 4
2014-03-17 02:14:45 -03:00
int16_t repeat_count ; // number of times to trigger the relay
2014-03-18 23:13:04 -03:00
float cycle_time ; // cycle time in seconds (the time between peaks or the time the relay is on and off for each cycle?)
2014-03-17 02:14:45 -03:00
} ;
2014-03-18 23:13:04 -03:00
// set servo command structure
2014-03-17 02:14:45 -03:00
struct PACKED Set_Servo_Command {
2014-03-18 23:13:04 -03:00
uint8_t channel ; // servo channel
uint16_t pwm ; // pwm value for servo
} ;
// repeat servo command structure
struct PACKED Repeat_Servo_Command {
uint8_t channel ; // servo channel
2014-03-17 02:14:45 -03:00
uint16_t pwm ; // pwm value for servo
int16_t repeat_count ; // number of times to move the servo (returns to trim in between)
2014-03-18 23:13:04 -03:00
float cycle_time ; // cycle time in seconds (the time between peaks or the time the servo is at the specified pwm value for each cycle?)
2014-03-17 02:14:45 -03:00
} ;
2015-03-21 08:56:50 -03:00
// mount control command structure
struct PACKED Mount_Control {
float pitch ; // pitch angle in degrees
float roll ; // roll angle in degrees
float yaw ; // yaw angle (relative to vehicle heading) in degrees
} ;
2015-03-28 22:29:21 -03:00
// digicam control command structure
struct PACKED Digicam_Configure {
uint8_t shooting_mode ; // ProgramAuto = 1, AV = 2, TV = 3, Man=4, IntelligentAuto=5, SuperiorAuto=6
uint16_t shutter_speed ;
uint8_t aperture ; // F stop number * 10
uint16_t ISO ; // 80, 100, 200, etc
uint8_t exposure_type ;
uint8_t cmd_id ;
float engine_cutoff_time ; // seconds
} ;
// digicam control command structure
struct PACKED Digicam_Control {
uint8_t session ; // 1 = on, 0 = off
uint8_t zoom_pos ;
2015-04-29 02:31:05 -03:00
int8_t zoom_step ; // +1 = zoom in, -1 = zoom out
2015-03-28 22:29:21 -03:00
uint8_t focus_lock ;
uint8_t shooting_cmd ;
uint8_t cmd_id ;
} ;
2014-03-17 02:14:45 -03:00
// set cam trigger distance command structure
struct PACKED Cam_Trigg_Distance {
2014-03-18 23:13:04 -03:00
float meters ; // distance
2020-05-04 21:27:56 -03:00
uint8_t trigger ; // triggers one image capture immediately
2014-03-17 02:14:45 -03:00
} ;
2014-09-17 04:21:12 -03:00
// gripper command structure
struct PACKED Gripper_Command {
uint8_t num ; // gripper number
uint8_t action ; // action (0 = release, 1 = grab)
} ;
2021-02-17 21:01:41 -04:00
// AUX_FUNCTION command structure
struct PACKED AuxFunction {
uint16_t function ; // from RC_Channel::AUX_FUNC
uint8_t switchpos ; // from RC_Channel::AuxSwitchPos
} ;
2014-04-23 09:36:56 -03:00
// high altitude balloon altitude wait
struct PACKED Altitude_Wait {
float altitude ; // meters
float descent_rate ; // m/s
uint8_t wiggle_time ; // seconds
} ;
2014-10-13 04:03:56 -03:00
// nav guided command
struct PACKED Guided_Limits_Command {
// max time is held in p1 field
float alt_min ; // min alt below which the command will be aborted. 0 for no lower alt limit
float alt_max ; // max alt above which the command will be aborted. 0 for no upper alt limit
float horiz_max ; // max horizontal distance the vehicle can move before the command will be aborted. 0 for no horizontal limit
} ;
2014-06-02 06:02:04 -03:00
2016-04-22 05:22:12 -03:00
// do VTOL transition
struct PACKED Do_VTOL_Transition {
uint8_t target_state ;
} ;
2020-05-04 21:27:56 -03:00
// navigation delay command structure
2016-04-18 04:12:40 -03:00
struct PACKED Navigation_Delay_Command {
float seconds ; // period of delay in seconds
int8_t hour_utc ; // absolute time's hour (utc)
int8_t min_utc ; // absolute time's min (utc)
int8_t sec_utc ; // absolute time's sec (utc)
} ;
2016-07-23 06:02:48 -03:00
// DO_ENGINE_CONTROL support
struct PACKED Do_Engine_Control {
bool start_control ; // start or stop engine
bool cold_start ; // use cold start procedure
uint16_t height_delay_cm ; // height delay for start
2023-09-28 15:51:37 -03:00
bool allow_disarmed_start ; // allow starting the engine while disarmed
2016-07-23 06:02:48 -03:00
} ;
2017-08-02 02:25:57 -03:00
// NAV_SET_YAW_SPEED support
struct PACKED Set_Yaw_Speed {
float angle_deg ; // target angle in degrees (0=north, 90=east)
float speed ; // speed in meters/second
uint8_t relative_angle ; // 0 = absolute angle, 1 = relative angle
} ;
2017-10-06 21:45:35 -03:00
// winch command structure
struct PACKED Winch_Command {
uint8_t num ; // winch number
uint8_t action ; // action (0 = relax, 1 = length control, 2 = rate control)
float release_length ; // cable distance to unwind in meters, negative numbers to wind in cable
float release_rate ; // release rate in meters/second
} ;
2021-02-25 21:08:22 -04:00
// Scripting command structure
struct PACKED scripting_Command {
float p1 ;
float p2 ;
float p3 ;
} ;
2022-10-18 22:59:40 -03:00
# if AP_SCRIPTING_ENABLED
2022-10-18 22:44:33 -03:00
// Scripting NAV command old version of storage format
struct PACKED nav_script_time_Command_tag0 {
uint8_t command ;
uint8_t timeout_s ;
float arg1 ;
float arg2 ;
} ;
// Scripting NAV command, new version of storage format
2021-10-25 00:59:11 -03:00
struct PACKED nav_script_time_Command {
uint8_t command ;
uint8_t timeout_s ;
2022-10-13 17:30:41 -03:00
Float16_t arg1 ;
Float16_t arg2 ;
2022-10-18 22:44:33 -03:00
// last 2 arguments need to be integers due to MISSION_ITEM_INT encoding
int16_t arg3 ;
int16_t arg4 ;
2021-10-25 00:59:11 -03:00
} ;
2022-10-18 22:59:40 -03:00
# endif
2022-05-25 01:52:01 -03:00
// Scripting NAV command (with verify)
struct PACKED nav_attitude_time_Command {
uint16_t time_sec ;
int16_t roll_deg ;
int8_t pitch_deg ;
int16_t yaw_deg ;
2022-10-18 22:42:50 -03:00
int16_t climb_rate ;
2022-05-25 01:52:01 -03:00
} ;
2022-06-02 09:23:47 -03:00
// MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW support
struct PACKED gimbal_manager_pitchyaw_Command {
int8_t pitch_angle_deg ;
int16_t yaw_angle_deg ;
int8_t pitch_rate_degs ;
int8_t yaw_rate_degs ;
uint8_t flags ;
uint8_t gimbal_id ;
} ;
2023-03-08 07:28:43 -04:00
// MAV_CMD_IMAGE_START_CAPTURE support
struct PACKED image_start_capture_Command {
2023-09-07 07:05:40 -03:00
uint8_t instance ;
2023-03-08 07:28:43 -04:00
float interval_s ;
uint16_t total_num_images ;
uint16_t start_seq_number ;
} ;
// MAV_CMD_SET_CAMERA_ZOOM support
struct PACKED set_camera_zoom_Command {
uint8_t zoom_type ;
float zoom_value ;
} ;
// MAV_CMD_SET_CAMERA_FOCUS support
struct PACKED set_camera_focus_Command {
uint8_t focus_type ;
float focus_value ;
} ;
2024-02-08 04:30:08 -04:00
// MAV_CMD_SET_CAMERA_SOURCE support
struct PACKED set_camera_source_Command {
uint8_t instance ;
uint8_t primary_source ;
uint8_t secondary_source ;
} ;
2023-03-08 07:28:43 -04:00
// MAV_CMD_VIDEO_START_CAPTURE support
struct PACKED video_start_capture_Command {
uint8_t video_stream_id ;
} ;
// MAV_CMD_VIDEO_STOP_CAPTURE support
struct PACKED video_stop_capture_Command {
uint8_t video_stream_id ;
} ;
2019-01-01 20:07:03 -04:00
union Content {
2014-02-22 20:14:44 -04:00
// jump structure
Jump_Command jump ;
2014-03-17 02:14:45 -03:00
// conditional delay
Conditional_Delay_Command delay ;
// conditional distance
Conditional_Distance_Command distance ;
// conditional yaw
Yaw_Command yaw ;
// change speed
Change_Speed_Command speed ;
2014-03-18 23:13:04 -03:00
// do-set-relay
2014-03-17 02:14:45 -03:00
Set_Relay_Command relay ;
2014-03-18 23:13:04 -03:00
// do-repeat-relay
Repeat_Relay_Command repeat_relay ;
// do-set-servo
2014-03-17 02:14:45 -03:00
Set_Servo_Command servo ;
2014-03-18 23:13:04 -03:00
// do-repeate-servo
Repeat_Servo_Command repeat_servo ;
2015-03-21 08:56:50 -03:00
// mount control
Mount_Control mount_control ;
2015-03-28 22:29:21 -03:00
// camera configure
Digicam_Configure digicam_configure ;
// camera control
Digicam_Control digicam_control ;
2014-03-17 02:14:45 -03:00
// cam trigg distance
Cam_Trigg_Distance cam_trigg_dist ;
2014-09-17 04:21:12 -03:00
// do-gripper
Gripper_Command gripper ;
2021-02-17 21:01:41 -04:00
// arbitrary aux function
AuxFunction auxfunction ;
2014-10-13 04:03:56 -03:00
// do-guided-limits
Guided_Limits_Command guided_limits ;
2020-07-09 04:01:54 -03:00
// high altitude balloon altitude wait
2014-04-23 09:36:56 -03:00
Altitude_Wait altitude_wait ;
2016-04-22 05:22:12 -03:00
// do vtol transition
Do_VTOL_Transition do_vtol_transition ;
2016-07-23 06:02:48 -03:00
// DO_ENGINE_CONTROL
Do_Engine_Control do_engine_control ;
2014-03-20 02:57:01 -03:00
2016-04-18 04:12:40 -03:00
// navigation delay
Navigation_Delay_Command nav_delay ;
2020-07-09 04:01:54 -03:00
// NAV_SET_YAW_SPEED support
2017-08-02 02:25:57 -03:00
Set_Yaw_Speed set_yaw_speed ;
2017-10-06 21:45:35 -03:00
// do-winch
Winch_Command winch ;
2021-02-25 21:08:22 -04:00
// do scripting
scripting_Command scripting ;
2022-10-18 22:59:40 -03:00
# if AP_SCRIPTING_ENABLED
2021-10-25 00:59:11 -03:00
// nav scripting
nav_script_time_Command nav_script_time ;
2022-10-18 22:59:40 -03:00
# endif
2022-05-25 01:52:01 -03:00
// nav attitude time
nav_attitude_time_Command nav_attitude_time ;
2022-06-02 09:23:47 -03:00
// MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW
gimbal_manager_pitchyaw_Command gimbal_manager_pitchyaw ;
2023-03-08 07:28:43 -04:00
// MAV_CMD_IMAGE_START_CAPTURE support
image_start_capture_Command image_start_capture ;
// MAV_CMD_SET_CAMERA_ZOOM support
set_camera_zoom_Command set_camera_zoom ;
// MAV_CMD_SET_CAMERA_FOCUS support
set_camera_focus_Command set_camera_focus ;
2024-02-08 04:30:08 -04:00
// MAV_CMD_SET_CAMEARA_SOURCE support
set_camera_source_Command set_camera_source ;
2023-03-08 07:28:43 -04:00
// MAV_CMD_VIDEO_START_CAPTURE support
video_start_capture_Command video_start_capture ;
// MAV_CMD_VIDEO_STOP_CAPTURE support
video_stop_capture_Command video_stop_capture ;
2017-08-02 02:25:57 -03:00
// location
2019-01-01 23:13:08 -04:00
Location location { } ; // Waypoint location
2014-02-22 20:14:44 -04:00
} ;
// command structure
2016-04-22 04:58:42 -03:00
struct Mission_Command {
2014-02-28 08:49:37 -04:00
uint16_t index ; // this commands position in the command list
2016-04-22 04:58:42 -03:00
uint16_t id ; // mavlink command id
2014-03-20 02:57:01 -03:00
uint16_t p1 ; // general purpose parameter 1
2014-02-22 20:14:44 -04:00
Content content ;
2017-11-26 18:24:05 -04:00
2022-05-11 00:40:48 -03:00
// for items which store in location, we offer a few more bits
// of storage:
uint8_t type_specific_bits ; // bitmask of set/unset bits
2017-11-26 18:24:05 -04:00
// return a human-readable interpretation of the ID stored in this command
const char * type ( ) const ;
2021-03-04 07:55:26 -04:00
// comparison operator (relies on all bytes in the structure even if they may not be used)
bool operator = = ( const Mission_Command & b ) const { return ( memcmp ( this , & b , sizeof ( Mission_Command ) ) = = 0 ) ; }
bool operator ! = ( const Mission_Command & b ) const { return ! operator = = ( b ) ; }
2024-01-12 00:14:19 -04:00
/*
return the number of turns for a LOITER_TURNS command
this has special handling for loiter turns from cmd . p1 and type_specific_bits
*/
float get_loiter_turns ( void ) const {
float turns = LOWBYTE ( p1 ) ;
if ( type_specific_bits & ( 1U < < 1 ) ) {
// special storage handling allows for fractional turns
turns * = ( 1.0 / 256.0 ) ;
}
return turns ;
}
2014-02-22 20:14:44 -04:00
} ;
2017-11-26 18:24:05 -04:00
2014-02-22 20:14:44 -04:00
// main program function pointers
2015-05-24 18:55:06 -03:00
FUNCTOR_TYPEDEF ( mission_cmd_fn_t , bool , const Mission_Command & ) ;
FUNCTOR_TYPEDEF ( mission_complete_fn_t , void ) ;
2014-02-22 20:14:44 -04:00
2017-12-12 21:06:12 -04:00
// constructor
2018-04-24 20:09:26 -03:00
AP_Mission ( mission_cmd_fn_t cmd_start_fn , mission_cmd_fn_t cmd_verify_fn , mission_complete_fn_t mission_complete_fn ) :
2017-12-12 21:06:12 -04:00
_cmd_start_fn ( cmd_start_fn ) ,
_cmd_verify_fn ( cmd_verify_fn ) ,
_mission_complete_fn ( mission_complete_fn ) ,
_prev_nav_cmd_id ( AP_MISSION_CMD_ID_NONE ) ,
_prev_nav_cmd_index ( AP_MISSION_CMD_INDEX_NONE ) ,
2021-06-17 15:00:38 -03:00
_prev_nav_cmd_wp_index ( AP_MISSION_CMD_INDEX_NONE )
2017-12-12 21:06:12 -04:00
{
2018-08-16 23:43:46 -03:00
# if CONFIG_HAL_BOARD == HAL_BOARD_SITL
if ( _singleton ! = nullptr ) {
AP_HAL : : panic ( " Mission must be singleton " ) ;
}
# endif
_singleton = this ;
2017-12-12 21:06:12 -04:00
// load parameter defaults
AP_Param : : setup_object_defaults ( this , var_info ) ;
// clear commands
_nav_cmd . index = AP_MISSION_CMD_INDEX_NONE ;
_do_cmd . index = AP_MISSION_CMD_INDEX_NONE ;
}
2018-08-16 23:43:46 -03:00
// get singleton instance
2020-05-04 21:27:56 -03:00
static AP_Mission * get_singleton ( )
{
2018-08-16 23:43:46 -03:00
return _singleton ;
}
2017-12-12 21:06:12 -04:00
/* Do not allow copies */
2022-09-30 06:50:43 -03:00
CLASS_NO_COPY ( AP_Mission ) ;
2020-05-04 21:27:56 -03:00
2014-02-22 20:14:44 -04:00
// mission state enumeration
enum mission_state {
MISSION_STOPPED = 0 ,
MISSION_RUNNING = 1 ,
MISSION_COMPLETE = 2
} ;
///
2014-02-24 01:50:24 -04:00
/// public mission methods
2014-02-22 20:14:44 -04:00
///
2014-03-11 00:52:23 -03:00
/// init - initialises this library including checks the version in eeprom matches this library
void init ( ) ;
2014-02-22 20:14:44 -04:00
/// status - returns the status of the mission (i.e. Mission_Started, Mission_Complete, Mission_Stopped
2020-05-04 21:27:56 -03:00
mission_state state ( ) const
{
return _flags . state ;
}
2014-02-22 20:14:44 -04:00
/// num_commands - returns total number of commands in the mission
2017-01-21 00:54:02 -04:00
/// this number includes offset 0, the home location
2020-05-04 21:27:56 -03:00
uint16_t num_commands ( ) const
{
return _cmd_total ;
}
2014-02-22 20:14:44 -04:00
2014-03-12 03:14:02 -03:00
/// num_commands_max - returns maximum number of commands that can be stored
2023-02-14 05:39:36 -04:00
uint16_t num_commands_max ( ) const {
return _commands_max ;
}
2014-03-12 03:14:02 -03:00
2014-02-22 20:14:44 -04:00
/// start - resets current commands to point to the beginning of the mission
/// To-Do: should we validate the mission first and return true/false?
void start ( ) ;
/// stop - stops mission execution. subsequent calls to update() will have no effect until the mission is started or resumed
void stop ( ) ;
/// resume - continues the mission execution from where we last left off
/// previous running commands will be re-initialised
void resume ( ) ;
2014-04-15 13:26:45 -03:00
/// start_or_resume - if MIS_AUTORESTART=0 this will call resume(), otherwise it will call start()
void start_or_resume ( ) ;
2016-05-19 07:32:48 -03:00
/// check mission starts with a takeoff command
bool starts_with_takeoff_cmd ( ) ;
2014-04-15 13:26:45 -03:00
2014-04-15 13:56:09 -03:00
/// reset - reset mission to the first command
void reset ( ) ;
2014-02-22 20:14:44 -04:00
/// clear - clears out mission
bool clear ( ) ;
2014-03-13 23:06:00 -03:00
/// truncate - truncate any mission items beyond given index
void truncate ( uint16_t index ) ;
2014-02-24 01:50:24 -04:00
/// update - ensures the command queues are loaded with the next command and calls main programs command_init and command_verify functions to progress the mission
/// should be called at 10hz or higher
void update ( ) ;
2014-02-22 20:14:44 -04:00
///
2014-02-24 01:50:24 -04:00
/// public command methods
2014-02-22 20:14:44 -04:00
///
2014-02-24 01:50:24 -04:00
/// add_cmd - adds a command to the end of the command list and writes to storage
/// returns true if successfully added, false on failure
/// cmd.index is updated with it's new position in the mission
bool add_cmd ( Mission_Command & cmd ) ;
2014-02-28 22:12:41 -04:00
/// replace_cmd - replaces the command at position 'index' in the command list with the provided cmd
/// replacing the current active command will have no effect until the command is restarted
/// returns true if successfully replaced, false on failure
2019-01-30 05:20:20 -04:00
bool replace_cmd ( uint16_t index , const Mission_Command & cmd ) ;
2014-02-28 22:12:41 -04:00
2014-02-24 01:50:24 -04:00
/// is_nav_cmd - returns true if the command's id is a "navigation" command, false if "do" or "conditional" command
static bool is_nav_cmd ( const Mission_Command & cmd ) ;
2014-04-21 22:37:53 -03:00
/// get_current_nav_cmd - returns the current "navigation" command
2020-05-04 21:27:56 -03:00
const Mission_Command & get_current_nav_cmd ( ) const
{
return _nav_cmd ;
}
2014-02-22 20:14:44 -04:00
2014-04-21 22:37:53 -03:00
/// get_current_nav_index - returns the current "navigation" command index
/// Note that this will return 0 if there is no command. This is
/// used in MAVLink reporting of the mission command
2020-05-04 21:27:56 -03:00
uint16_t get_current_nav_index ( ) const
{
return _nav_cmd . index = = AP_MISSION_CMD_INDEX_NONE ? 0 : _nav_cmd . index ;
}
2014-04-21 22:37:53 -03:00
2019-11-23 18:27:04 -04:00
/// get_current_nav_id - return the id of the current nav command
2020-05-04 21:27:56 -03:00
uint16_t get_current_nav_id ( ) const
{
return _nav_cmd . id ;
}
2019-11-23 18:27:04 -04:00
2016-05-13 20:06:25 -03:00
/// get_prev_nav_cmd_id - returns the previous "navigation" command id
/// if there was no previous nav command it returns AP_MISSION_CMD_ID_NONE
/// we do not return the entire command to save on RAM
2020-05-04 21:27:56 -03:00
uint16_t get_prev_nav_cmd_id ( ) const
{
return _prev_nav_cmd_id ;
}
2016-05-13 20:06:25 -03:00
2014-02-24 01:50:24 -04:00
/// get_prev_nav_cmd_index - returns the previous "navigation" commands index (i.e. position in the mission command list)
2014-03-22 00:45:35 -03:00
/// if there was no previous nav command it returns AP_MISSION_CMD_INDEX_NONE
2014-02-24 01:50:24 -04:00
/// we do not return the entire command to save on RAM
2020-05-04 21:27:56 -03:00
uint16_t get_prev_nav_cmd_index ( ) const
{
return _prev_nav_cmd_index ;
}
2014-02-24 01:50:24 -04:00
2015-08-23 22:06:31 -03:00
/// get_prev_nav_cmd_with_wp_index - returns the previous "navigation" commands index that contains a waypoint (i.e. position in the mission command list)
/// if there was no previous nav command it returns AP_MISSION_CMD_INDEX_NONE
/// we do not return the entire command to save on RAM
2020-05-04 21:27:56 -03:00
uint16_t get_prev_nav_cmd_with_wp_index ( ) const
{
return _prev_nav_cmd_wp_index ;
}
2015-08-23 22:06:31 -03:00
2014-02-23 03:54:53 -04:00
/// get_next_nav_cmd - gets next "navigation" command found at or after start_index
/// returns true if found, false if not found (i.e. reached end of mission command list)
/// accounts for do_jump commands
2014-02-28 08:49:37 -04:00
bool get_next_nav_cmd ( uint16_t start_index , Mission_Command & cmd ) ;
2014-02-23 03:54:53 -04:00
2014-04-06 20:29:54 -03:00
/// get the ground course of the next navigation leg in centidegrees
/// from 0 36000. Return default_angle if next navigation
/// leg cannot be determined
int32_t get_next_ground_course_cd ( int32_t default_angle ) ;
2014-02-28 22:12:41 -04:00
/// get_current_do_cmd - returns active "do" command
2020-05-04 21:27:56 -03:00
const Mission_Command & get_current_do_cmd ( ) const
{
return _do_cmd ;
}
2014-02-22 20:14:44 -04:00
2019-11-23 18:27:04 -04:00
/// get_current_do_cmd_id - returns id of the active "do" command
2020-05-04 21:27:56 -03:00
uint16_t get_current_do_cmd_id ( ) const
{
return _do_cmd . id ;
}
2019-11-23 18:27:04 -04:00
2014-02-28 21:19:38 -04:00
// set_current_cmd - jumps to command specified by index
2023-09-27 22:02:31 -03:00
bool set_current_cmd ( uint16_t index ) ;
2014-02-27 09:02:12 -04:00
2021-03-05 21:26:40 -04:00
// restart current navigation command. Used to handle external changes to mission
// returns true on success, false if current nav command has been deleted
bool restart_current_nav_cmd ( ) ;
2014-02-22 20:14:44 -04:00
/// load_cmd_from_storage - load command from storage
/// true is return if successful
2014-02-28 08:49:37 -04:00
bool read_cmd_from_storage ( uint16_t index , Mission_Command & cmd ) const ;
2014-02-22 20:14:44 -04:00
/// write_cmd_to_storage - write a command to storage
/// cmd.index is used to calculate the storage location
/// true is returned if successful
2019-01-30 05:20:20 -04:00
bool write_cmd_to_storage ( uint16_t index , const Mission_Command & cmd ) ;
2014-02-22 20:14:44 -04:00
2014-03-03 01:36:37 -04:00
/// write_home_to_storage - writes the special purpose cmd 0 (home) to storage
/// home is taken directly from ahrs
void write_home_to_storage ( ) ;
2019-01-30 19:27:22 -04:00
static MAV_MISSION_RESULT convert_MISSION_ITEM_to_MISSION_ITEM_INT ( const mavlink_mission_item_t & mission_item ,
2020-05-04 21:27:56 -03:00
mavlink_mission_item_int_t & mission_item_int ) WARN_IF_UNUSED ;
2019-01-30 19:27:22 -04:00
static MAV_MISSION_RESULT convert_MISSION_ITEM_INT_to_MISSION_ITEM ( const mavlink_mission_item_int_t & mission_item_int ,
2020-05-04 21:27:56 -03:00
mavlink_mission_item_t & mission_item ) WARN_IF_UNUSED ;
2019-01-30 19:27:22 -04:00
// mavlink_int_to_mission_cmd - converts mavlink message to an AP_Mission::Mission_Command object which can be stored to eeprom
2015-12-21 01:02:23 -04:00
// return MAV_MISSION_ACCEPTED on success, MAV_MISSION_RESULT error on failure
2016-02-28 02:47:00 -04:00
static MAV_MISSION_RESULT mavlink_int_to_mission_cmd ( const mavlink_mission_item_int_t & packet , AP_Mission : : Mission_Command & cmd ) ;
2016-05-06 14:26:54 -03:00
2019-01-30 19:27:22 -04:00
// mission_cmd_to_mavlink_int - converts an AP_Mission::Mission_Command object to a mavlink message which can be sent to the GCS
2014-02-28 02:55:02 -04:00
// return true on success, false on failure
2016-02-28 02:47:00 -04:00
static bool mission_cmd_to_mavlink_int ( const AP_Mission : : Mission_Command & cmd , mavlink_mission_item_int_t & packet ) ;
2014-02-28 02:55:02 -04:00
2014-08-06 03:17:11 -03:00
// return the last time the mission changed in milliseconds
2020-05-04 21:27:56 -03:00
uint32_t last_change_time_ms ( void ) const
{
return _last_change_time_ms ;
}
2014-08-06 03:17:11 -03:00
2014-10-17 14:34:04 -03:00
// find the nearest landing sequence starting point (DO_LAND_START) and
2014-10-24 00:06:35 -03:00
// return its index. Returns 0 if no appropriate DO_LAND_START point can
// be found.
2024-03-27 14:59:52 -03:00
uint16_t get_landing_sequence_start ( const Location & current_loc ) ;
2014-10-17 14:34:04 -03:00
2016-11-25 20:45:11 -04:00
// find the nearest landing sequence starting point (DO_LAND_START) and
// switch to that mission item. Returns false if no DO_LAND_START
// available.
2024-03-27 14:59:52 -03:00
bool jump_to_landing_sequence ( const Location & current_loc ) ;
2016-11-25 20:45:11 -04:00
2018-12-05 19:28:11 -04:00
// jumps the mission to the closest landing abort that is planned, returns false if unable to find a valid abort
2024-03-27 14:59:52 -03:00
bool jump_to_abort_landing_sequence ( const Location & current_loc ) ;
// Scripting helpers for the above functions to fill in the location
# if AP_SCRIPTING_ENABLED
bool jump_to_landing_sequence ( void ) ;
2018-12-05 19:28:11 -04:00
bool jump_to_abort_landing_sequence ( void ) ;
2024-03-27 14:59:52 -03:00
# endif
2018-12-05 19:28:11 -04:00
2020-02-17 19:44:53 -04:00
// check which is the shortest route to landing an RTL via a DO_LAND_START or continuing on the current mission plan
2024-03-27 14:59:52 -03:00
bool is_best_land_sequence ( const Location & current_loc ) ;
2020-02-17 19:44:53 -04:00
// set in_landing_sequence flag
2020-05-04 21:27:56 -03:00
void set_in_landing_sequence_flag ( bool flag )
{
_flags . in_landing_sequence = flag ;
}
2020-02-17 19:44:53 -04:00
2020-09-14 23:26:29 -03:00
// get in_landing_sequence flag
bool get_in_landing_sequence_flag ( ) const {
return _flags . in_landing_sequence ;
}
2020-02-23 05:52:57 -04:00
// force mission to resume when start_or_resume() is called
2020-05-04 21:27:56 -03:00
void set_force_resume ( bool force_resume )
{
_force_resume = force_resume ;
}
2020-02-23 05:52:57 -04:00
2018-08-19 22:37:54 -03:00
// get a reference to the AP_Mission semaphore, allowing an external caller to lock the
// storage while working with multiple waypoints
2020-05-04 21:27:56 -03:00
HAL_Semaphore & get_semaphore ( void )
{
2018-08-19 22:37:54 -03:00
return _rsem ;
}
2018-12-25 01:17:39 -04:00
// returns true if the mission contains the requested items
bool contains_item ( MAV_CMD command ) const ;
2020-06-22 18:23:46 -03:00
// returns true if the mission has a terrain relative mission item
2022-08-09 01:35:58 -03:00
bool contains_terrain_alt_items ( void ) ;
2023-01-15 20:03:55 -04:00
// returns true if the mission cmd has a location
static bool cmd_has_location ( const uint16_t command ) ;
2022-08-03 22:24:43 -03:00
2020-02-24 18:43:20 -04:00
// reset the mission history to prevent recalling previous mission histories when restarting missions.
void reset_wp_history ( void ) ;
2020-03-03 23:28:41 -04:00
/*
return true if MIS_OPTIONS is set to allow continue of mission
2021-08-30 17:22:58 -03:00
logic after a land and the next waypoint is a takeoff . If this
is false then after a landing is complete the vehicle should
disarm and mission logic should stop
2020-03-03 23:28:41 -04:00
*/
2021-08-30 17:22:58 -03:00
bool continue_after_land_check_for_takeoff ( void ) ;
2020-03-03 23:28:41 -04:00
bool continue_after_land ( void ) const {
return ( _options . get ( ) & AP_MISSION_MASK_CONTINUE_AFTER_LAND ) ! = 0 ;
}
2014-02-22 20:14:44 -04:00
// user settable parameters
static const struct AP_Param : : GroupInfo var_info [ ] ;
2020-05-04 21:27:56 -03:00
// allow lua to get/set any WP items in any order in a mavlink-ish kinda way.
2021-02-01 12:26:31 -04:00
bool get_item ( uint16_t index , mavlink_mission_item_int_t & result ) const ;
2020-05-04 21:27:56 -03:00
bool set_item ( uint16_t index , mavlink_mission_item_int_t & source ) ;
2023-02-21 21:47:01 -04:00
// Jump Tags. When a JUMP_TAG is run in the mission, either via DO_JUMP_TAG or
// by just being the next item, the tag is remembered and the age is set to 1.
// Only the most recent tag is remembered. It's age is how many NAV items have
// progressed since the tag was seen. While executing the tag, the
// age will be 1. The next NAV command after it will tick the age to 2, and so on.
bool get_last_jump_tag ( uint16_t & tag , uint16_t & age ) const ;
2023-02-21 21:24:05 -04:00
// Set the mission index to the first JUMP_TAG with this tag.
// Returns true on success, else false if no appropriate JUMP_TAG match can be found or if setting the index failed
bool jump_to_tag ( const uint16_t tag ) ;
// find the first JUMP_TAG with this tag and return its index.
// Returns 0 if no appropriate JUMP_TAG match can be found.
uint16_t get_index_of_jump_tag ( const uint16_t tag ) const ;
2023-09-27 22:10:29 -03:00
bool is_valid_index ( const uint16_t index ) const { return index < _cmd_total ; }
2023-02-14 05:39:36 -04:00
# if AP_SDCARD_STORAGE_ENABLED
bool failed_sdcard_storage ( void ) const {
return _failed_sdcard_storage ;
}
# endif
2014-02-22 20:14:44 -04:00
private :
2018-08-16 23:43:46 -03:00
static AP_Mission * _singleton ;
2014-08-13 01:43:37 -03:00
static StorageAccess _storage ;
2014-02-22 20:14:44 -04:00
2019-01-01 20:07:03 -04:00
static bool stored_in_location ( uint16_t id ) ;
2023-02-21 21:24:05 -04:00
struct {
uint16_t age ; // a value of 0 means we have never seen a tag. Once a tag is seen, age will increment every time the mission index changes.
uint16_t tag ; // most recent tag that was successfully jumped to. Only valid if age > 0
} _jump_tag ;
2014-02-22 20:14:44 -04:00
struct Mission_Flags {
mission_state state ;
2021-06-17 15:00:38 -03:00
bool nav_cmd_loaded ; // true if a "navigation" command has been loaded into _nav_cmd
bool do_cmd_loaded ; // true if a "do"/"conditional" command has been loaded into _do_cmd
bool do_cmd_all_done ; // true if all "do"/"conditional" commands have been completed (stops unnecessary searching through eeprom for do commands)
bool in_landing_sequence ; // true if the mission has jumped to a landing
bool resuming_mission ; // true if the mission is resuming and set false once the aircraft attains the interrupted WP
2014-02-22 20:14:44 -04:00
} _flags ;
2020-02-24 18:43:20 -04:00
// mission WP resume history
uint16_t _wp_index_history [ AP_MISSION_MAX_WP_HISTORY ] ; // storing the nav_cmd index for the last 6 WPs
2014-02-23 03:54:53 -04:00
///
/// private methods
///
/// complete - mission is marked complete and clean-up performed including calling the mission_complete_fn
void complete ( ) ;
2018-10-22 23:56:46 -03:00
bool verify_command ( const Mission_Command & cmd ) ;
bool start_command ( const Mission_Command & cmd ) ;
2014-02-23 03:54:53 -04:00
/// advance_current_nav_cmd - moves current nav command forward
2018-08-22 19:38:29 -03:00
// starting_index is used to set the index from which searching will begin, leave as 0 to search from the current navigation target
2014-02-23 03:54:53 -04:00
/// do command will also be loaded
/// accounts for do-jump commands
2014-02-24 01:50:24 -04:00
// returns true if command is advanced, false if failed (i.e. mission completed)
2018-08-22 19:38:29 -03:00
bool advance_current_nav_cmd ( uint16_t starting_index = 0 ) ;
2014-02-23 03:54:53 -04:00
/// advance_current_do_cmd - moves current do command forward
/// accounts for do-jump commands
/// returns true if successfully advanced (can it ever be unsuccessful?)
void advance_current_do_cmd ( ) ;
/// get_next_cmd - gets next command found at or after start_index
/// returns true if found, false if not found (i.e. mission complete)
2014-02-22 20:14:44 -04:00
/// accounts for do_jump commands
2014-02-23 03:54:53 -04:00
/// increment_jump_num_times_if_found should be set to true if advancing the active navigation command
2020-02-17 19:44:53 -04:00
bool get_next_cmd ( uint16_t start_index , Mission_Command & cmd , bool increment_jump_num_times_if_found , bool send_gcs_msg = true ) ;
2014-02-23 03:54:53 -04:00
/// get_next_do_cmd - gets next "do" or "conditional" command after start_index
/// returns true if found, false if not found
/// stops and returns false if it hits another navigation command before it finds the first do or conditional command
/// accounts for do_jump commands but never increments the jump's num_times_run (get_next_nav_cmd is responsible for this)
2014-02-28 08:49:37 -04:00
bool get_next_do_cmd ( uint16_t start_index , Mission_Command & cmd ) ;
2014-02-23 03:54:53 -04:00
///
/// jump handling methods
///
// init_jump_tracking - initialise jump_tracking variables
void init_jump_tracking ( ) ;
/// get_jump_times_run - returns number of times the jump command has been run
2014-02-28 08:23:38 -04:00
/// return is signed to be consistent with do-jump cmd's repeat count which can be -1 (to signify to repeat forever)
int16_t get_jump_times_run ( const Mission_Command & cmd ) ;
2014-02-23 03:54:53 -04:00
/// increment_jump_times_run - increments the recorded number of times the jump command has been run
2020-02-17 19:44:53 -04:00
void increment_jump_times_run ( Mission_Command & cmd , bool send_gcs_msg = true ) ;
2014-02-22 20:14:44 -04:00
2014-03-11 00:52:23 -03:00
/// check_eeprom_version - checks version of missions stored in eeprom matches this library
/// command list will be cleared if they do not match
void check_eeprom_version ( ) ;
2020-02-17 19:44:53 -04:00
// check if command is a landing type command. Asside the obvious, MAV_CMD_DO_PARACHUTE is considered a type of landing
bool is_landing_type_cmd ( uint16_t id ) const ;
2022-06-09 20:14:40 -03:00
// check if command is a takeoff type command.
bool is_takeoff_type_cmd ( uint16_t id ) const ;
2020-02-17 19:44:53 -04:00
// approximate the distance travelled to get to a landing. DO_JUMP commands are observed in look forward.
bool distance_to_landing ( uint16_t index , float & tot_distance , Location current_loc ) ;
2020-02-24 18:43:20 -04:00
// calculate the location of a resume cmd wp
bool calc_rewind_pos ( Mission_Command & rewind_cmd ) ;
// update progress made in mission to store last position in the event of mission exit
void update_exit_position ( void ) ;
2023-02-21 21:24:05 -04:00
void on_mission_timestamp_change ( ) ;
2018-04-26 02:46:46 -03:00
/// sanity checks that the masked fields are not NaN's or infinite
static MAV_MISSION_RESULT sanity_check_params ( const mavlink_mission_item_int_t & packet ) ;
2021-08-30 17:22:58 -03:00
/// check if the next nav command is a takeoff, skipping delays
bool is_takeoff_next ( uint16_t start_index ) ;
2014-02-22 20:14:44 -04:00
// pointer to main program functions
mission_cmd_fn_t _cmd_start_fn ; // pointer to function which will be called when a new command is started
mission_cmd_fn_t _cmd_verify_fn ; // pointer to function which will be called repeatedly to ensure a command is progressing
2014-02-23 03:54:53 -04:00
mission_complete_fn_t _mission_complete_fn ; // pointer to function which will be called when mission completes
2014-02-22 20:14:44 -04:00
2021-06-17 15:00:38 -03:00
// parameters
AP_Int16 _cmd_total ; // total number of commands in the mission
AP_Int16 _options ; // bitmask options for missions, currently for mission clearing on reboot but can be expanded as required
AP_Int8 _restart ; // controls mission starting point when entering Auto mode (either restart from beginning of mission or resume from last command run)
2014-02-22 20:14:44 -04:00
// internal variables
2021-06-17 15:00:38 -03:00
bool _force_resume ; // when set true it forces mission to resume irrespective of MIS_RESTART param.
uint16_t _repeat_dist ; // Distance to repeat on mission resume (m), can be set with MAV_CMD_DO_SET_RESUME_REPEAT_DIST
2014-02-22 20:14:44 -04:00
struct Mission_Command _nav_cmd ; // current "navigation" command. It's position in the command list is held in _nav_cmd.index
struct Mission_Command _do_cmd ; // current "do" command. It's position in the command list is held in _do_cmd.index
2020-02-24 18:43:20 -04:00
struct Mission_Command _resume_cmd ; // virtual wp command that is used to resume mission if the mission needs to be rewound on resume.
2016-05-13 20:06:25 -03:00
uint16_t _prev_nav_cmd_id ; // id of the previous "navigation" command. (WAYPOINT, LOITER_TO_ALT, ect etc)
2014-02-28 08:49:37 -04:00
uint16_t _prev_nav_cmd_index ; // index of the previous "navigation" command. Rarely used which is why we don't store the whole command
2015-08-23 22:06:31 -03:00
uint16_t _prev_nav_cmd_wp_index ; // index of the previous "navigation" command that contains a waypoint. Rarely used which is why we don't store the whole command
2023-02-02 18:58:39 -04:00
Location _exit_position ; // the position in the mission that the mission was exited
2014-02-23 03:54:53 -04:00
// jump related variables
struct jump_tracking_struct {
2014-02-28 08:49:37 -04:00
uint16_t index ; // index of do-jump commands in mission
2014-02-28 08:23:38 -04:00
int16_t num_times_run ; // number of times this jump command has been run
2014-02-23 03:54:53 -04:00
} _jump_tracking [ AP_MISSION_MAX_NUM_DO_JUMP_COMMANDS ] ;
2014-08-06 03:17:11 -03:00
// last time that mission changed
uint32_t _last_change_time_ms ;
2023-02-21 21:24:05 -04:00
uint32_t _last_change_time_prev_ms ;
2018-08-19 22:37:54 -03:00
2023-02-14 05:39:36 -04:00
// maximum number of commands that will fit in storage
uint16_t _commands_max ;
# if AP_SDCARD_STORAGE_ENABLED
bool _failed_sdcard_storage ;
# endif
// fast call to get command ID of a mission index
uint16_t get_command_id ( uint16_t index ) const ;
2022-08-03 22:24:43 -03:00
// memoisation of contains-relative:
2022-08-09 01:35:58 -03:00
bool _contains_terrain_alt_items ; // true if the mission has terrain-relative items
uint32_t _last_contains_relative_calculated_ms ; // will be equal to _last_change_time_ms if _contains_terrain_alt_items is up-to-date
bool calculate_contains_terrain_alt_items ( void ) const ;
2020-02-24 18:43:20 -04:00
2018-08-19 22:37:54 -03:00
// multi-thread support. This is static so it can be used from
// const functions
2020-01-18 17:57:26 -04:00
static HAL_Semaphore _rsem ;
2018-10-23 01:45:34 -03:00
// mission items common to all vehicles:
2021-02-17 21:01:41 -04:00
bool start_command_do_aux_function ( const AP_Mission : : Mission_Command & cmd ) ;
2018-10-23 01:45:34 -03:00
bool start_command_do_gripper ( const AP_Mission : : Mission_Command & cmd ) ;
2018-10-23 03:11:47 -03:00
bool start_command_do_servorelayevents ( const AP_Mission : : Mission_Command & cmd ) ;
2018-10-23 04:03:50 -03:00
bool start_command_camera ( const AP_Mission : : Mission_Command & cmd ) ;
2019-01-31 20:16:42 -04:00
bool start_command_parachute ( const AP_Mission : : Mission_Command & cmd ) ;
2020-02-24 18:43:20 -04:00
bool command_do_set_repeat_dist ( const AP_Mission : : Mission_Command & cmd ) ;
2020-07-02 20:04:27 -03:00
bool start_command_do_sprayer ( const AP_Mission : : Mission_Command & cmd ) ;
2021-02-25 21:08:22 -04:00
bool start_command_do_scripting ( const AP_Mission : : Mission_Command & cmd ) ;
2022-06-02 09:23:47 -03:00
bool start_command_do_gimbal_manager_pitchyaw ( const AP_Mission : : Mission_Command & cmd ) ;
2022-10-18 22:44:33 -03:00
/*
handle format conversion of storage format to allow us to update
format to take advantage of new packing
*/
void format_conversion ( uint8_t tag_byte , const Mission_Command & cmd , PackedContent & packed_content ) const ;
2014-02-22 20:14:44 -04:00
} ;
2018-08-16 23:43:46 -03:00
2020-05-04 21:27:56 -03:00
namespace AP
{
AP_Mission * mission ( ) ;
2018-08-16 23:43:46 -03:00
} ;