52 static_assert(
sizeof(
union Content) == 12,
"AP_Mission: Content must be 12 bytes");
143 if (cmd.
id != MAV_CMD_NAV_TAKEOFF) {
287 return (cmd.
id <= MAV_CMD_NAV_LAST || cmd.
id == MAV_CMD_NAV_SET_YAW_SPEED);
295 uint16_t cmd_index = start_index;
325 return default_angle;
328 if (cmd.
id == MAV_CMD_NAV_GUIDED_ENABLE ||
329 cmd.
id == MAV_CMD_NAV_DELAY) {
330 return default_angle;
332 if (cmd.
id == MAV_CMD_NAV_SET_YAW_SPEED) {
456 if (index >= (
unsigned)
_cmd_total && index != 0) {
463 cmd.
id = MAV_CMD_NAV_WAYPOINT;
528 home_cmd.
id = MAV_CMD_NAV_WAYPOINT;
535 switch (packet.command) {
536 case MAV_CMD_NAV_WAYPOINT:
537 nan_mask = ~(1 << 3);
539 case MAV_CMD_NAV_LAND:
540 nan_mask = ~(1 << 3);
542 case MAV_CMD_NAV_TAKEOFF:
543 nan_mask = ~(1 << 3);
545 case MAV_CMD_NAV_VTOL_TAKEOFF:
546 nan_mask = ~(1 << 3);
548 case MAV_CMD_NAV_VTOL_LAND:
549 nan_mask = ~((1 << 2) | (1 << 3));
556 if (((nan_mask & (1 << 0)) && isnan(packet.param1)) ||
557 isinf(packet.param1)) {
558 return MAV_MISSION_INVALID_PARAM1;
560 if (((nan_mask & (1 << 1)) && isnan(packet.param2)) ||
561 isinf(packet.param2)) {
562 return MAV_MISSION_INVALID_PARAM2;
564 if (((nan_mask & (1 << 2)) && isnan(packet.param3)) ||
565 isinf(packet.param3)) {
566 return MAV_MISSION_INVALID_PARAM3;
568 if (((nan_mask & (1 << 3)) && isnan(packet.param4)) ||
569 isinf(packet.param4)) {
570 return MAV_MISSION_INVALID_PARAM4;
572 return MAV_MISSION_ACCEPTED;
579 bool copy_location =
false;
580 bool copy_alt =
false;
583 cmd.
index = packet.seq;
584 cmd.
id = packet.command;
588 if (param_check != MAV_MISSION_ACCEPTED) {
597 return MAV_MISSION_INVALID;
599 case MAV_CMD_NAV_WAYPOINT:
601 copy_location =
true;
607 #if APM_BUILD_TYPE(APM_BUILD_ArduPlane) 609 uint16_t acp = packet.param2;
610 uint16_t passby = packet.param3;
613 passby =
MIN(0xFF,passby);
616 cmd.
p1 = (passby << 8) | (acp & 0x00FF);
619 cmd.
p1 = packet.param1;
624 case MAV_CMD_NAV_LOITER_UNLIM:
625 copy_location =
true;
626 cmd.
p1 = fabsf(packet.param3);
630 case MAV_CMD_NAV_LOITER_TURNS:
632 copy_location =
true;
633 uint16_t num_turns = packet.param1;
634 uint16_t radius_m = fabsf(packet.param3);
635 cmd.
p1 = (radius_m<<8) | (num_turns & 0x00FF);
641 case MAV_CMD_NAV_LOITER_TIME:
642 copy_location =
true;
643 cmd.
p1 = packet.param1;
648 case MAV_CMD_NAV_RETURN_TO_LAUNCH:
651 case MAV_CMD_NAV_LAND:
652 copy_location =
true;
653 cmd.
p1 = packet.param1;
657 case MAV_CMD_NAV_TAKEOFF:
658 copy_location =
true;
659 cmd.
p1 = packet.param1;
662 case MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT:
663 copy_location =
true;
664 cmd.
p1 = packet.param1;
670 case MAV_CMD_NAV_LOITER_TO_ALT:
671 copy_location =
true;
672 cmd.
p1 = fabsf(packet.param2);
677 case MAV_CMD_NAV_SPLINE_WAYPOINT:
678 copy_location =
true;
679 cmd.
p1 = packet.param1;
682 case MAV_CMD_NAV_GUIDED_ENABLE:
683 cmd.
p1 = packet.param1;
686 case MAV_CMD_NAV_DELAY:
693 case MAV_CMD_CONDITION_DELAY:
697 case MAV_CMD_CONDITION_DISTANCE:
701 case MAV_CMD_CONDITION_YAW:
708 case MAV_CMD_DO_SET_MODE:
709 cmd.
p1 = packet.param1;
712 case MAV_CMD_DO_JUMP:
717 case MAV_CMD_DO_CHANGE_SPEED:
723 case MAV_CMD_DO_SET_HOME:
724 copy_location =
true;
725 cmd.
p1 = packet.param1;
728 case MAV_CMD_DO_SET_RELAY:
733 case MAV_CMD_DO_REPEAT_RELAY:
739 case MAV_CMD_DO_SET_SERVO:
744 case MAV_CMD_DO_REPEAT_SERVO:
751 case MAV_CMD_DO_LAND_START:
752 copy_location =
true;
755 case MAV_CMD_DO_SET_ROI:
756 copy_location =
true;
757 cmd.
p1 = packet.param1;
760 case MAV_CMD_DO_DIGICAM_CONFIGURE:
770 case MAV_CMD_DO_DIGICAM_CONTROL:
779 case MAV_CMD_DO_MOUNT_CONTROL:
785 case MAV_CMD_DO_SET_CAM_TRIGG_DIST:
789 case MAV_CMD_DO_FENCE_ENABLE:
790 cmd.
p1 = packet.param1;
793 case MAV_CMD_DO_PARACHUTE:
794 cmd.
p1 = packet.param1;
797 case MAV_CMD_DO_INVERTED_FLIGHT:
798 cmd.
p1 = packet.param1;
801 case MAV_CMD_DO_GRIPPER:
806 case MAV_CMD_DO_GUIDED_LIMITS:
807 cmd.
p1 = packet.param1;
813 case MAV_CMD_DO_AUTOTUNE_ENABLE:
814 cmd.
p1 = packet.param1;
817 case MAV_CMD_NAV_ALTITUDE_WAIT:
823 case MAV_CMD_NAV_VTOL_TAKEOFF:
824 copy_location =
true;
827 case MAV_CMD_NAV_VTOL_LAND:
828 copy_location =
true;
831 case MAV_CMD_DO_VTOL_TRANSITION:
835 case MAV_CMD_DO_SET_REVERSE:
836 cmd.
p1 = packet.param1;
839 case MAV_CMD_DO_ENGINE_CONTROL:
845 case MAV_CMD_NAV_PAYLOAD_PLACE:
846 cmd.
p1 = packet.param1*100;
847 copy_location =
true;
850 case MAV_CMD_NAV_SET_YAW_SPEED:
856 case MAV_CMD_DO_WINCH:
865 return MAV_MISSION_UNSUPPORTED;
869 if (copy_location || copy_alt) {
874 return MAV_MISSION_INVALID_PARAM5_X;
877 return MAV_MISSION_INVALID_PARAM6_Y;
881 return MAV_MISSION_INVALID_PARAM7;
891 switch (packet.frame) {
893 case MAV_FRAME_MISSION:
894 case MAV_FRAME_GLOBAL:
898 case MAV_FRAME_GLOBAL_RELATIVE_ALT:
902 #if AP_TERRAIN_AVAILABLE 903 case MAV_FRAME_GLOBAL_TERRAIN_ALT:
913 return MAV_MISSION_UNSUPPORTED_FRAME;
918 return MAV_MISSION_ACCEPTED;
924 mavlink_mission_item_int_t mav_cmd = {};
926 mav_cmd.param1 = packet.param1;
927 mav_cmd.param2 = packet.param2;
928 mav_cmd.param3 = packet.param3;
929 mav_cmd.param4 = packet.param4;
930 mav_cmd.z = packet.z;
931 mav_cmd.seq = packet.seq;
932 mav_cmd.command = packet.command;
933 mav_cmd.target_system = packet.target_system;
934 mav_cmd.target_component = packet.target_component;
935 mav_cmd.frame = packet.frame;
936 mav_cmd.current = packet.current;
937 mav_cmd.autocontinue = packet.autocontinue;
946 switch (packet.command) {
947 case MAV_CMD_DO_DIGICAM_CONTROL:
948 case MAV_CMD_DO_DIGICAM_CONFIGURE:
949 mav_cmd.x = packet.x;
950 mav_cmd.y = packet.y;
957 return MAV_MISSION_INVALID_PARAM5_X;
960 return MAV_MISSION_INVALID_PARAM6_Y;
962 mav_cmd.x = packet.x * 1.0e7f;
963 mav_cmd.y = packet.y * 1.0e7f;
975 mavlink_mission_item_int_t mav_cmd = {};
979 packet.param1 = mav_cmd.param1;
980 packet.param2 = mav_cmd.param2;
981 packet.param3 = mav_cmd.param3;
982 packet.param4 = mav_cmd.param4;
983 packet.z = mav_cmd.z;
984 packet.seq = mav_cmd.seq;
985 packet.command = mav_cmd.command;
986 packet.target_system = mav_cmd.target_system;
987 packet.target_component = mav_cmd.target_component;
988 packet.frame = mav_cmd.frame;
989 packet.current = mav_cmd.current;
990 packet.autocontinue = mav_cmd.autocontinue;
999 switch (packet.command) {
1000 case MAV_CMD_DO_DIGICAM_CONTROL:
1001 case MAV_CMD_DO_DIGICAM_CONFIGURE:
1002 packet.x = mav_cmd.x;
1003 packet.y = mav_cmd.y;
1009 packet.x = mav_cmd.x * 1.0e-7
f;
1010 packet.y = mav_cmd.y * 1.0e-7
f;
1021 mavlink_mission_item_t miss_item = {0};
1023 miss_item.param1 = packet.param1;
1024 miss_item.param2 = packet.param2;
1025 miss_item.param3 = packet.param3;
1026 miss_item.param4 = packet.param4;
1028 miss_item.command = packet.command;
1029 miss_item.target_system = packet.target_system;
1030 miss_item.target_component = packet.target_component;
1039 bool copy_location =
false;
1040 bool copy_alt =
false;
1043 packet.seq = cmd.
index;
1044 packet.command = cmd.
id;
1052 packet.autocontinue = 1;
1060 case MAV_CMD_NAV_WAYPOINT:
1061 copy_location =
true;
1062 #if APM_BUILD_TYPE(APM_BUILD_ArduPlane) 1069 packet.param1 = cmd.
p1;
1073 case MAV_CMD_NAV_LOITER_UNLIM:
1074 copy_location =
true;
1075 packet.param3 = (float)cmd.
p1;
1077 packet.param3 *= -1;
1081 case MAV_CMD_NAV_LOITER_TURNS:
1082 copy_location =
true;
1086 packet.param3 = -packet.param3;
1091 case MAV_CMD_NAV_LOITER_TIME:
1092 copy_location =
true;
1093 packet.param1 = cmd.
p1;
1102 case MAV_CMD_NAV_RETURN_TO_LAUNCH:
1105 case MAV_CMD_NAV_LAND:
1106 copy_location =
true;
1107 packet.param1 = cmd.
p1;
1111 case MAV_CMD_NAV_TAKEOFF:
1112 copy_location =
true;
1113 packet.param1 = cmd.
p1;
1116 case MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT:
1117 copy_location =
true;
1118 packet.param1 = cmd.
p1;
1124 case MAV_CMD_NAV_LOITER_TO_ALT:
1125 copy_location =
true;
1126 packet.param2 = cmd.
p1;
1128 packet.param2 = -packet.param2;
1133 case MAV_CMD_NAV_SPLINE_WAYPOINT:
1134 copy_location =
true;
1135 packet.param1 = cmd.
p1;
1138 case MAV_CMD_NAV_GUIDED_ENABLE:
1139 packet.param1 = cmd.
p1;
1142 case MAV_CMD_NAV_DELAY:
1149 case MAV_CMD_CONDITION_DELAY:
1153 case MAV_CMD_CONDITION_DISTANCE:
1157 case MAV_CMD_CONDITION_YAW:
1164 case MAV_CMD_DO_SET_MODE:
1165 packet.param1 = cmd.
p1;
1168 case MAV_CMD_DO_JUMP:
1173 case MAV_CMD_DO_CHANGE_SPEED:
1179 case MAV_CMD_DO_SET_HOME:
1180 copy_location =
true;
1181 packet.param1 = cmd.
p1;
1184 case MAV_CMD_DO_SET_RELAY:
1189 case MAV_CMD_DO_REPEAT_RELAY:
1195 case MAV_CMD_DO_SET_SERVO:
1200 case MAV_CMD_DO_REPEAT_SERVO:
1207 case MAV_CMD_DO_LAND_START:
1208 copy_location =
true;
1211 case MAV_CMD_DO_SET_ROI:
1212 copy_location =
true;
1213 packet.param1 = cmd.
p1;
1216 case MAV_CMD_DO_DIGICAM_CONFIGURE:
1226 case MAV_CMD_DO_DIGICAM_CONTROL:
1235 case MAV_CMD_DO_MOUNT_CONTROL:
1241 case MAV_CMD_DO_SET_CAM_TRIGG_DIST:
1245 case MAV_CMD_DO_FENCE_ENABLE:
1246 packet.param1 = cmd.
p1;
1249 case MAV_CMD_DO_PARACHUTE:
1250 packet.param1 = cmd.
p1;
1253 case MAV_CMD_DO_INVERTED_FLIGHT:
1254 packet.param1 = cmd.
p1;
1257 case MAV_CMD_DO_GRIPPER:
1262 case MAV_CMD_DO_GUIDED_LIMITS:
1263 packet.param1 = cmd.
p1;
1269 case MAV_CMD_DO_AUTOTUNE_ENABLE:
1270 packet.param1 = cmd.
p1;
1273 case MAV_CMD_DO_SET_REVERSE:
1274 packet.param1 = cmd.
p1;
1277 case MAV_CMD_NAV_ALTITUDE_WAIT:
1283 case MAV_CMD_NAV_VTOL_TAKEOFF:
1284 copy_location =
true;
1287 case MAV_CMD_NAV_VTOL_LAND:
1288 copy_location =
true;
1291 case MAV_CMD_DO_VTOL_TRANSITION:
1295 case MAV_CMD_DO_ENGINE_CONTROL:
1301 case MAV_CMD_NAV_PAYLOAD_PLACE:
1302 copy_location =
true;
1303 packet.param1 = cmd.
p1/100.0f;
1306 case MAV_CMD_NAV_SET_YAW_SPEED:
1312 case MAV_CMD_DO_WINCH:
1325 if (copy_location) {
1329 if (copy_location || copy_alt) {
1332 packet.frame = MAV_FRAME_GLOBAL_RELATIVE_ALT;
1334 packet.frame = MAV_FRAME_GLOBAL;
1336 #if AP_TERRAIN_AVAILABLE 1349 packet.frame = MAV_FRAME_GLOBAL_TERRAIN_ALT;
1412 uint8_t max_loops = 255;
1442 if (max_loops-- == 0) {
1448 cmd_index = cmd.
index+1;
1506 uint16_t cmd_index = start_index;
1511 uint8_t max_loops = 64;
1520 if (temp_cmd.
id == MAV_CMD_DO_JUMP) {
1522 if (max_loops-- == 0) {
1533 if (!increment_jump_num_times_if_found && jump_index == cmd_index) {
1541 jump_index = cmd_index;
1553 if (increment_jump_num_times_if_found) {
1644 if (cmd.
id != MAV_CMD_DO_JUMP) {
1701 uint16_t landing_start_index = 0;
1702 float min_distance = -1;
1710 if (tmp.
id == MAV_CMD_DO_LAND_START) {
1712 if (min_distance < 0 || tmp_distance < min_distance) {
1713 min_distance = tmp_distance;
1714 landing_start_index = i;
1719 return landing_start_index;
1737 gcs().
send_text(MAV_SEVERITY_INFO,
"Landing sequence start");
1741 gcs().
send_text(MAV_SEVERITY_WARNING,
"Unable to start landing sequence");
1747 case MAV_CMD_NAV_WAYPOINT:
1749 case MAV_CMD_NAV_RETURN_TO_LAUNCH:
1751 case MAV_CMD_NAV_LOITER_UNLIM:
1753 case MAV_CMD_NAV_LOITER_TIME:
1755 case MAV_CMD_NAV_SET_YAW_SPEED:
1757 case MAV_CMD_CONDITION_DELAY:
1759 case MAV_CMD_CONDITION_DISTANCE:
1761 case MAV_CMD_DO_CHANGE_SPEED:
1762 return "ChangeSpeed";
1763 case MAV_CMD_DO_SET_HOME:
1765 case MAV_CMD_DO_SET_SERVO:
1767 case MAV_CMD_DO_SET_RELAY:
1769 case MAV_CMD_DO_REPEAT_SERVO:
1770 return "RepeatServo";
1771 case MAV_CMD_DO_REPEAT_RELAY:
1772 return "RepeatRelay";
1773 case MAV_CMD_DO_CONTROL_VIDEO:
1775 case MAV_CMD_DO_DIGICAM_CONFIGURE:
1776 return "DigiCamCfg";
1777 case MAV_CMD_DO_DIGICAM_CONTROL:
1778 return "DigiCamCtrl";
1779 case MAV_CMD_DO_SET_CAM_TRIGG_DIST:
1780 return "SetCamTrigDst";
1781 case MAV_CMD_DO_SET_ROI:
1783 case MAV_CMD_DO_SET_REVERSE:
1784 return "SetReverse";
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
#define AP_MISSION_JUMP_TIMES_MAX
void complete()
complete - mission is marked complete and clean-up performed including calling the mission_complete_f...
uint8_t read_byte(uint16_t loc) const
Mount_Control mount_control
Repeat_Servo_Command repeat_servo
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)
void write_uint16(uint16_t loc, uint16_t value) const
virtual bool get_position(struct Location &loc) const =0
struct Mission_Command _do_cmd
Interface definition for the various Ground Control System.
uint16_t read_uint16(uint16_t loc) const
const struct Location & get_home(void) 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
#define AP_GROUPINFO(name, idx, clazz, element, def)
uint16_t num_commands() const
#define AP_MISSION_OPTIONS_DEFAULT
float get_distance(const struct Location &loc1, const struct Location &loc2)
uint16_t size(void) 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
bool check_lng(float lng)
Conditional_Delay_Command delay
Repeat_Relay_Command repeat_relay
Conditional_Distance_Command distance
bool add_cmd(Mission_Command &cmd)
Navigation_Delay_Command nav_delay
void reset()
reset - reset mission to the first command
void check_eeprom_version()
void write_byte(uint16_t loc, uint8_t value) const
int32_t lat
param 3 - Latitude * 10**7
int32_t get_bearing_cd(const struct Location &loc1, const struct Location &loc2)
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
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 char * type() const
int32_t alt
param 2 - Altitude in centimeters (meters * 100) see LOCATION_ALT_MAX_M
#define AP_MISSION_RESTART_DEFAULT
mission_state state() const
status - returns the status of the mission (i.e. Mission_Started, Mission_Complete, Mission_Stopped
bool advance_current_nav_cmd()
#define AP_MISSION_JUMP_REPEAT_FOREVER
Handles the MAVLINK command mission stack. Reads and writes mission to storage.
#define AP_MISSION_EEPROM_COMMAND_SIZE
Change_Speed_Command speed
bool set_current_cmd(uint16_t index)
uint16_t get_landing_sequence_start()
#define AP_MISSION_MASK_MISSION_CLEAR
Altitude_Wait altitude_wait
uint16_t _prev_nav_cmd_id
void send_text(MAV_SEVERITY severity, const char *fmt,...)
struct Mission_Command _nav_cmd
bool read_block(void *dst, uint16_t src, size_t n) const
Location_Option_Flags flags
options bitmask (1<<0 = relative altitude)
Set_Yaw_Speed set_yaw_speed
uint32_t read_uint32(uint16_t loc) const
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
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
#define AP_MISSION_EEPROM_VERSION
void write_uint32(uint16_t loc, uint32_t value) const
mission_complete_fn_t _mission_complete_fn
bool check_lat(float lat)
int32_t lng
param 4 - Longitude * 10**7
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 write_block(uint16_t dst, const void *src, size_t n) const
bool get_next_do_cmd(uint16_t start_index, Mission_Command &cmd)
#define AP_MISSION_FIRST_REAL_COMMAND
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
bool is_negative(const T fVal1)
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 ...
#define LOCATION_ALT_MAX_M
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)
bool write_cmd_to_storage(uint16_t index, Mission_Command &cmd)