25 #define AP_MISSION_EEPROM_VERSION 0x65AE // version number stored in first four bytes of eeprom. increment this by one when eeprom format is changed 26 #define AP_MISSION_EEPROM_COMMAND_SIZE 15 // size in bytes of all mission commands 28 #define AP_MISSION_MAX_NUM_DO_JUMP_COMMANDS 15 // allow up to 15 do-jump commands 30 #define AP_MISSION_JUMP_REPEAT_FOREVER -1 // when do-jump command's repeat count is -1 this means endless repeat 32 #define AP_MISSION_CMD_ID_NONE 0 // mavlink cmd id of zero means invalid or missing command 33 #define AP_MISSION_CMD_INDEX_NONE 65535 // command index of 65535 means invalid or missing command 34 #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) 36 #define AP_MISSION_FIRST_REAL_COMMAND 1 // command #0 reserved to hold home position 38 #define AP_MISSION_RESTART_DEFAULT 0 // resume the mission from the last command run by default 40 #define AP_MISSION_OPTIONS_DEFAULT 0 // Do not clear the mission when rebooting 41 #define AP_MISSION_MASK_MISSION_CLEAR (1<<0) // If set then Clear the mission on boot 275 const char *type()
const;
284 AP_Mission(
AP_AHRS &
ahrs, mission_cmd_fn_t cmd_start_fn, mission_cmd_fn_t cmd_verify_fn, mission_complete_fn_t mission_complete_fn) :
static bool is_nav_cmd(const Mission_Command &cmd)
is_nav_cmd - returns true if the command's id is a "navigation" command, false if "do" or "conditiona...
Do_Engine_Control do_engine_control
static bool mission_cmd_to_mavlink_int(const AP_Mission::Mission_Command &cmd, mavlink_mission_item_int_t &packet)
static MAV_MISSION_RESULT mavlink_cmd_long_to_mission_cmd(const mavlink_command_long_t &packet, AP_Mission::Mission_Command &cmd)
uint16_t _prev_nav_cmd_wp_index
uint16_t get_prev_nav_cmd_id() const
void complete()
complete - mission is marked complete and clean-up performed including calling the mission_complete_f...
Mount_Control mount_control
Repeat_Servo_Command repeat_servo
AP_Mission(AP_AHRS &ahrs, mission_cmd_fn_t cmd_start_fn, mission_cmd_fn_t cmd_verify_fn, mission_complete_fn_t mission_complete_fn)
void start_or_resume()
start_or_resume - if MIS_AUTORESTART=0 this will call resume(), otherwise it will call start() ...
bool jump_to_landing_sequence(void)
struct Mission_Command _do_cmd
uint16_t get_current_nav_index() const
void init()
init - initialises this library including checks the version in eeprom matches this library ...
void truncate(uint16_t index)
truncate - truncate any mission items beyond given index
uint16_t num_commands() const
static MAV_MISSION_RESULT sanity_check_params(const mavlink_mission_item_int_t &packet)
sanity checks that the masked fields are not NaN's or infinite
Digicam_Control digicam_control
Conditional_Delay_Command delay
AP_Mission & operator=(const AP_Mission &)=delete
Repeat_Relay_Command repeat_relay
Conditional_Distance_Command distance
bool add_cmd(Mission_Command &cmd)
Navigation_Delay_Command nav_delay
const Mission_Command & get_current_nav_cmd() const
get_current_nav_cmd - returns the current "navigation" command
void reset()
reset - reset mission to the first command
void check_eeprom_version()
Guided_Limits_Command guided_limits
bool read_cmd_from_storage(uint16_t index, Mission_Command &cmd) const
void init_jump_tracking()
void stop()
stop - stops mission execution. subsequent calls to update() will have no effect until the mission is...
bool replace_cmd(uint16_t index, Mission_Command &cmd)
struct AP_Mission::Mission_Flags _flags
mission_cmd_fn_t _cmd_verify_fn
A system for managing and storing variables that are of general interest to the system.
static bool mission_cmd_to_mavlink(const AP_Mission::Mission_Command &cmd, mavlink_mission_item_t &packet)
static MAV_MISSION_RESULT mavlink_to_mission_cmd(const mavlink_mission_item_t &packet, AP_Mission::Mission_Command &cmd)
const Mission_Command & get_current_do_cmd() const
get_current_do_cmd - returns active "do" command
uint16_t get_prev_nav_cmd_index() const
mission_state state() const
status - returns the status of the mission (i.e. Mission_Started, Mission_Complete, Mission_Stopped
bool advance_current_nav_cmd()
uint16_t get_prev_nav_cmd_with_wp_index() const
uint32_t last_change_time_ms(void) const
Change_Speed_Command speed
bool set_current_cmd(uint16_t index)
uint16_t get_landing_sequence_start()
Altitude_Wait altitude_wait
uint16_t _prev_nav_cmd_id
struct Mission_Command _nav_cmd
Set_Yaw_Speed set_yaw_speed
bool get_next_nav_cmd(uint16_t start_index, Mission_Command &cmd)
uint16_t num_commands_max() const
num_commands_max - returns maximum number of commands that can be stored
Digicam_Configure digicam_configure
Common definitions and utility routines for the ArduPilot libraries.
mission_complete_fn_t _mission_complete_fn
uint16_t _prev_nav_cmd_index
void advance_current_do_cmd()
int32_t get_next_ground_course_cd(int32_t default_angle)
#define AP_MISSION_CMD_INDEX_NONE
bool get_next_do_cmd(uint16_t start_index, Mission_Command &cmd)
static MAV_MISSION_RESULT mavlink_int_to_mission_cmd(const mavlink_mission_item_int_t &packet, AP_Mission::Mission_Command &cmd)
Cam_Trigg_Distance cam_trigg_dist
Do_VTOL_Transition do_vtol_transition
FUNCTOR_TYPEDEF(mission_cmd_fn_t, bool, const Mission_Command &)
void write_home_to_storage()
#define AP_MISSION_MAX_NUM_DO_JUMP_COMMANDS
#define AP_MISSION_CMD_ID_NONE
mission_cmd_fn_t _cmd_start_fn
bool starts_with_takeoff_cmd()
check mission starts with a takeoff command
uint32_t _last_change_time_ms
static const struct AP_Param::GroupInfo var_info[]
void increment_jump_times_run(Mission_Command &cmd)
increment_jump_times_run - increments the recorded number of times the jump command has been run ...
int16_t get_jump_times_run(const Mission_Command &cmd)
get_jump_times_run - returns number of times the jump command has been run
struct AP_Mission::jump_tracking_struct _jump_tracking[AP_MISSION_MAX_NUM_DO_JUMP_COMMANDS]
static StorageAccess _storage
bool get_next_cmd(uint16_t start_index, Mission_Command &cmd, bool increment_jump_num_times_if_found)
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)
bool write_cmd_to_storage(uint16_t index, Mission_Command &cmd)