170 cmd.
id = MAV_CMD_NAV_WAYPOINT;
181 cmd.
id = MAV_CMD_NAV_TAKEOFF;
192 cmd.
id = MAV_CMD_NAV_WAYPOINT;
203 cmd.
id = MAV_CMD_NAV_WAYPOINT;
213 cmd.
id = MAV_CMD_DO_JUMP;
221 cmd.
id = MAV_CMD_NAV_RETURN_TO_LAUNCH;
241 cmd.
id = MAV_CMD_NAV_WAYPOINT;
252 cmd.
id = MAV_CMD_DO_SET_ROI;
263 cmd.
id = MAV_CMD_DO_CHANGE_SPEED;
274 cmd.
id = MAV_CMD_DO_SET_SERVO;
280 cmd.
id = MAV_CMD_DO_JUMP;
298 cmd.
id = MAV_CMD_NAV_WAYPOINT;
309 cmd.
id = MAV_CMD_DO_JUMP;
317 cmd.
id = MAV_CMD_NAV_TAKEOFF;
328 cmd.
id = MAV_CMD_NAV_WAYPOINT;
350 cmd.
id = MAV_CMD_NAV_WAYPOINT;
361 cmd.
id = MAV_CMD_NAV_TAKEOFF;
372 cmd.
id = MAV_CMD_DO_SET_ROI;
383 cmd.
id = MAV_CMD_DO_JUMP;
391 cmd.
id = MAV_CMD_NAV_WAYPOINT;
414 cmd.
id = MAV_CMD_NAV_WAYPOINT;
425 cmd.
id = MAV_CMD_DO_SET_ROI;
436 cmd.
id = MAV_CMD_DO_CHANGE_SPEED;
447 cmd.
id = MAV_CMD_NAV_TAKEOFF;
458 cmd.
id = MAV_CMD_DO_SET_ROI;
469 cmd.
id = MAV_CMD_NAV_WAYPOINT;
491 cmd.
id = MAV_CMD_NAV_WAYPOINT;
502 cmd.
id = MAV_CMD_NAV_TAKEOFF;
513 cmd.
id = MAV_CMD_DO_SET_ROI;
524 cmd.
id = MAV_CMD_NAV_WAYPOINT;
535 cmd.
id = MAV_CMD_DO_CHANGE_SPEED;
546 cmd.
id = MAV_CMD_DO_SET_ROI;
567 cmd.
id = MAV_CMD_NAV_WAYPOINT;
578 cmd.
id = MAV_CMD_NAV_TAKEOFF;
589 cmd.
id = MAV_CMD_DO_SET_ROI;
600 cmd.
id = MAV_CMD_NAV_WAYPOINT;
611 cmd.
id = MAV_CMD_DO_CHANGE_SPEED;
622 cmd.
id = MAV_CMD_DO_SET_ROI;
633 cmd.
id = MAV_CMD_DO_JUMP;
670 if (cmd.
id == MAV_CMD_DO_JUMP) {
688 cmd.
id = MAV_CMD_NAV_WAYPOINT;
699 cmd.
id = MAV_CMD_NAV_TAKEOFF;
710 cmd.
id = MAV_CMD_NAV_WAYPOINT;
721 cmd.
id = MAV_CMD_NAV_WAYPOINT;
731 cmd.
id = MAV_CMD_DO_SET_ROI;
742 cmd.
id = MAV_CMD_NAV_RETURN_TO_LAUNCH;
762 for(uint8_t i=0; i<11; i++) {
794 cmd.
id = MAV_CMD_NAV_WAYPOINT;
805 cmd.
id = MAV_CMD_NAV_TAKEOFF;
816 cmd.
id = MAV_CMD_DO_SET_ROI;
827 cmd.
id = MAV_CMD_NAV_WAYPOINT;
838 cmd.
id = MAV_CMD_NAV_WAYPOINT;
848 cmd.
id = MAV_CMD_DO_SET_ROI;
859 cmd.
id = MAV_CMD_NAV_RETURN_TO_LAUNCH;
876 for(uint8_t i=0; i<11; i++) {
899 cmd.
id = MAV_CMD_NAV_WAYPOINT;
910 cmd.
id = MAV_CMD_NAV_TAKEOFF;
921 cmd.
id = MAV_CMD_DO_SET_ROI;
932 cmd.
id = MAV_CMD_NAV_WAYPOINT;
943 cmd.
id = MAV_CMD_NAV_WAYPOINT;
953 cmd.
id = MAV_CMD_DO_SET_ROI;
964 cmd.
id = MAV_CMD_NAV_RETURN_TO_LAUNCH;
981 for(uint8_t i=0; i<11; i++) {
1036 cmd.
id = MAV_CMD_NAV_WAYPOINT;
1047 cmd.
id = MAV_CMD_NAV_TAKEOFF;
1058 cmd.
id = MAV_CMD_DO_SET_ROI;
1069 cmd.
id = MAV_CMD_NAV_WAYPOINT;
1080 cmd.
id = MAV_CMD_NAV_WAYPOINT;
1090 cmd.
id = MAV_CMD_NAV_RETURN_TO_LAUNCH;
1107 for(uint8_t i=0; i<9; i++) {
1113 cmd.
id = MAV_CMD_DO_SET_ROI;
1137 uint16_t num_commands = 0;
1139 bool failed_to_add =
false;
1140 bool failed_to_read =
false;
1141 bool success =
true;
1144 while (!failed_to_add) {
1146 cmd.
id = MAV_CMD_NAV_WAYPOINT;
1154 failed_to_add =
true;
1161 for (i=0; i<num_commands; i++) {
1163 hal.
console->
printf(
"failed to retrieve command #%u\n",(
unsigned int)i);
1164 failed_to_read =
true;
1168 hal.
console->
printf(
"successfully read command #%u\n",(
unsigned int)i);
1170 hal.
console->
printf(
"cmd %u's alt does not match, expected %u but read %u\n",
1181 if (failed_to_read) {
1220 missiontest.
setup();
struct timespec start_time
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...
bool verify_cmd(const AP_Mission::Mission_Command &cmd)
static MissionTest missiontest
AP_HAL::UARTDriver * console
void mission_complete(void)
void run_set_current_cmd_test()
void init_mission_no_nav_commands()
uint16_t num_commands() const
void init_mission_ends_with_do_commands()
bool start_cmd(const AP_Mission::Mission_Command &cmd)
bool add_cmd(Mission_Command &cmd)
int32_t lat
param 3 - Latitude * 10**7
bool read_cmd_from_storage(uint16_t index, Mission_Command &cmd) const
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)
virtual void delay(uint16_t ms)=0
virtual void printf(const char *,...) FMT_PRINTF(2
int32_t alt
param 2 - Altitude in centimeters (meters * 100) see LOCATION_ALT_MAX_M
mission_state state() const
status - returns the status of the mission (i.e. Mission_Started, Mission_Complete, Mission_Stopped
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Handles the MAVLINK command mission stack. Reads and writes mission to storage.
void init_mission_endless_loop()
void init_mission_starts_with_do_commands()
#define AP_MISSION_EEPROM_COMMAND_SIZE
bool set_current_cmd(uint16_t index)
void run_set_current_cmd_while_stopped_test()
uint16_t num_commands_max() const
num_commands_max - returns maximum number of commands that can be stored
int32_t lng
param 4 - Longitude * 10**7
void init_mission_jump_to_nonnav()
void run_replace_cmd_test()
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
uint8_t verify_do_cmd_iterations_to_complete
uint8_t verify_nav_cmd_iterations_to_complete
AP_HAL::Scheduler * scheduler
void init_mission_ends_with_jump_command()