AP_Mission.h 25 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594
  1. /// @file AP_Mission.h
  2. /// @brief Handles the MAVLINK command mission stack. Reads and writes mission to storage.
  3. /*
  4. * The AP_Mission library:
  5. * - responsible for managing a list of commands made up of "nav", "do" and "conditional" commands
  6. * - reads and writes the mission commands to storage.
  7. * - provides easy access to current, previous and upcoming waypoints
  8. * - calls main program's command execution and verify functions.
  9. * - accounts for the DO_JUMP command
  10. *
  11. */
  12. #pragma once
  13. #include <AP_HAL/AP_HAL.h>
  14. #include <AP_Vehicle/AP_Vehicle.h>
  15. #include <GCS_MAVLink/GCS_MAVLink.h>
  16. #include <AP_Math/AP_Math.h>
  17. #include <AP_Common/AP_Common.h>
  18. #include <AP_Common/Location.h>
  19. #include <AP_Param/AP_Param.h>
  20. #include <StorageManager/StorageManager.h>
  21. // definitions
  22. #define AP_MISSION_EEPROM_VERSION 0x65AE // version number stored in first four bytes of eeprom. increment this by one when eeprom format is changed
  23. #define AP_MISSION_EEPROM_COMMAND_SIZE 15 // size in bytes of all mission commands
  24. #define AP_MISSION_MAX_NUM_DO_JUMP_COMMANDS 15 // allow up to 15 do-jump commands
  25. #define AP_MISSION_JUMP_REPEAT_FOREVER -1 // when do-jump command's repeat count is -1 this means endless repeat
  26. #define AP_MISSION_CMD_ID_NONE 0 // mavlink cmd id of zero means invalid or missing command
  27. #define AP_MISSION_CMD_INDEX_NONE 65535 // command index of 65535 means invalid or missing command
  28. #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)
  29. #define AP_MISSION_FIRST_REAL_COMMAND 1 // command #0 reserved to hold home position
  30. #define AP_MISSION_RESTART_DEFAULT 0 // resume the mission from the last command run by default
  31. #define AP_MISSION_OPTIONS_DEFAULT 0 // Do not clear the mission when rebooting
  32. #define AP_MISSION_MASK_MISSION_CLEAR (1<<0) // If set then Clear the mission on boot
  33. /// @class AP_Mission
  34. /// @brief Object managing Mission
  35. class AP_Mission {
  36. public:
  37. // jump command structure
  38. struct PACKED Jump_Command {
  39. uint16_t target; // target command id
  40. int16_t num_times; // num times to repeat. -1 = repeat forever
  41. };
  42. // condition delay command structure
  43. struct PACKED Conditional_Delay_Command {
  44. float seconds; // period of delay in seconds
  45. };
  46. // condition delay command structure
  47. struct PACKED Conditional_Distance_Command {
  48. float meters; // distance from next waypoint in meters
  49. };
  50. // condition yaw command structure
  51. struct PACKED Yaw_Command {
  52. float angle_deg; // target angle in degrees (0=north, 90=east)
  53. float turn_rate_dps; // turn rate in degrees / second (0=use default)
  54. int8_t direction; // -1 = ccw, +1 = cw
  55. uint8_t relative_angle; // 0 = absolute angle, 1 = relative angle
  56. };
  57. // change speed command structure
  58. struct PACKED Change_Speed_Command {
  59. uint8_t speed_type; // 0=airspeed, 1=ground speed
  60. float target_ms; // target speed in m/s, -1 means no change
  61. float throttle_pct; // throttle as a percentage (i.e. 0 ~ 100), -1 means no change
  62. };
  63. // set relay command structure
  64. struct PACKED Set_Relay_Command {
  65. uint8_t num; // relay number from 1 to 4
  66. uint8_t state; // on = 3.3V or 5V (depending upon board), off = 0V. only used for do-set-relay, not for do-repeat-relay
  67. };
  68. // repeat relay command structure
  69. struct PACKED Repeat_Relay_Command {
  70. uint8_t num; // relay number from 1 to 4
  71. int16_t repeat_count; // number of times to trigger the relay
  72. float cycle_time; // cycle time in seconds (the time between peaks or the time the relay is on and off for each cycle?)
  73. };
  74. // set servo command structure
  75. struct PACKED Set_Servo_Command {
  76. uint8_t channel; // servo channel
  77. uint16_t pwm; // pwm value for servo
  78. };
  79. // repeat servo command structure
  80. struct PACKED Repeat_Servo_Command {
  81. uint8_t channel; // servo channel
  82. uint16_t pwm; // pwm value for servo
  83. int16_t repeat_count; // number of times to move the servo (returns to trim in between)
  84. 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?)
  85. };
  86. // mount control command structure
  87. struct PACKED Mount_Control {
  88. float pitch; // pitch angle in degrees
  89. float roll; // roll angle in degrees
  90. float yaw; // yaw angle (relative to vehicle heading) in degrees
  91. };
  92. // digicam control command structure
  93. struct PACKED Digicam_Configure {
  94. uint8_t shooting_mode; // ProgramAuto = 1, AV = 2, TV = 3, Man=4, IntelligentAuto=5, SuperiorAuto=6
  95. uint16_t shutter_speed;
  96. uint8_t aperture; // F stop number * 10
  97. uint16_t ISO; // 80, 100, 200, etc
  98. uint8_t exposure_type;
  99. uint8_t cmd_id;
  100. float engine_cutoff_time; // seconds
  101. };
  102. // digicam control command structure
  103. struct PACKED Digicam_Control {
  104. uint8_t session; // 1 = on, 0 = off
  105. uint8_t zoom_pos;
  106. int8_t zoom_step; // +1 = zoom in, -1 = zoom out
  107. uint8_t focus_lock;
  108. uint8_t shooting_cmd;
  109. uint8_t cmd_id;
  110. };
  111. // set cam trigger distance command structure
  112. struct PACKED Cam_Trigg_Distance {
  113. float meters; // distance
  114. };
  115. // gripper command structure
  116. struct PACKED Gripper_Command {
  117. uint8_t num; // gripper number
  118. uint8_t action; // action (0 = release, 1 = grab)
  119. };
  120. // high altitude balloon altitude wait
  121. struct PACKED Altitude_Wait {
  122. float altitude; // meters
  123. float descent_rate; // m/s
  124. uint8_t wiggle_time; // seconds
  125. };
  126. // nav guided command
  127. struct PACKED Guided_Limits_Command {
  128. // max time is held in p1 field
  129. float alt_min; // min alt below which the command will be aborted. 0 for no lower alt limit
  130. float alt_max; // max alt above which the command will be aborted. 0 for no upper alt limit
  131. float horiz_max; // max horizontal distance the vehicle can move before the command will be aborted. 0 for no horizontal limit
  132. };
  133. // do VTOL transition
  134. struct PACKED Do_VTOL_Transition {
  135. uint8_t target_state;
  136. };
  137. // navigation delay command structure
  138. struct PACKED Navigation_Delay_Command {
  139. float seconds; // period of delay in seconds
  140. int8_t hour_utc; // absolute time's hour (utc)
  141. int8_t min_utc; // absolute time's min (utc)
  142. int8_t sec_utc; // absolute time's sec (utc)
  143. };
  144. // DO_ENGINE_CONTROL support
  145. struct PACKED Do_Engine_Control {
  146. bool start_control; // start or stop engine
  147. bool cold_start; // use cold start procedure
  148. uint16_t height_delay_cm; // height delay for start
  149. };
  150. // NAV_SET_YAW_SPEED support
  151. struct PACKED Set_Yaw_Speed {
  152. float angle_deg; // target angle in degrees (0=north, 90=east)
  153. float speed; // speed in meters/second
  154. uint8_t relative_angle; // 0 = absolute angle, 1 = relative angle
  155. };
  156. // winch command structure
  157. struct PACKED Winch_Command {
  158. uint8_t num; // winch number
  159. uint8_t action; // action (0 = relax, 1 = length control, 2 = rate control)
  160. float release_length; // cable distance to unwind in meters, negative numbers to wind in cable
  161. float release_rate; // release rate in meters/second
  162. };
  163. union Content {
  164. // jump structure
  165. Jump_Command jump;
  166. // conditional delay
  167. Conditional_Delay_Command delay;
  168. // conditional distance
  169. Conditional_Distance_Command distance;
  170. // conditional yaw
  171. Yaw_Command yaw;
  172. // change speed
  173. Change_Speed_Command speed;
  174. // do-set-relay
  175. Set_Relay_Command relay;
  176. // do-repeat-relay
  177. Repeat_Relay_Command repeat_relay;
  178. // do-set-servo
  179. Set_Servo_Command servo;
  180. // do-repeate-servo
  181. Repeat_Servo_Command repeat_servo;
  182. // mount control
  183. Mount_Control mount_control;
  184. // camera configure
  185. Digicam_Configure digicam_configure;
  186. // camera control
  187. Digicam_Control digicam_control;
  188. // cam trigg distance
  189. Cam_Trigg_Distance cam_trigg_dist;
  190. // do-gripper
  191. Gripper_Command gripper;
  192. // do-guided-limits
  193. Guided_Limits_Command guided_limits;
  194. // cam trigg distance
  195. Altitude_Wait altitude_wait;
  196. // do vtol transition
  197. Do_VTOL_Transition do_vtol_transition;
  198. // DO_ENGINE_CONTROL
  199. Do_Engine_Control do_engine_control;
  200. // navigation delay
  201. Navigation_Delay_Command nav_delay;
  202. // navigation delay
  203. Set_Yaw_Speed set_yaw_speed;
  204. // do-winch
  205. Winch_Command winch;
  206. // location
  207. Location location{}; // Waypoint location
  208. };
  209. // command structure
  210. struct Mission_Command {
  211. uint16_t index; // this commands position in the command list
  212. uint16_t id; // mavlink command id
  213. uint16_t p1; // general purpose parameter 1
  214. Content content;
  215. // return a human-readable interpretation of the ID stored in this command
  216. const char *type() const;
  217. };
  218. // main program function pointers
  219. FUNCTOR_TYPEDEF(mission_cmd_fn_t, bool, const Mission_Command&);
  220. FUNCTOR_TYPEDEF(mission_complete_fn_t, void);
  221. // constructor
  222. AP_Mission(mission_cmd_fn_t cmd_start_fn, mission_cmd_fn_t cmd_verify_fn, mission_complete_fn_t mission_complete_fn) :
  223. _cmd_start_fn(cmd_start_fn),
  224. _cmd_verify_fn(cmd_verify_fn),
  225. _mission_complete_fn(mission_complete_fn),
  226. _prev_nav_cmd_id(AP_MISSION_CMD_ID_NONE),
  227. _prev_nav_cmd_index(AP_MISSION_CMD_INDEX_NONE),
  228. _prev_nav_cmd_wp_index(AP_MISSION_CMD_INDEX_NONE),
  229. _last_change_time_ms(0)
  230. {
  231. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  232. if (_singleton != nullptr) {
  233. AP_HAL::panic("Mission must be singleton");
  234. }
  235. #endif
  236. _singleton = this;
  237. // load parameter defaults
  238. AP_Param::setup_object_defaults(this, var_info);
  239. // clear commands
  240. _nav_cmd.index = AP_MISSION_CMD_INDEX_NONE;
  241. _do_cmd.index = AP_MISSION_CMD_INDEX_NONE;
  242. // initialise other internal variables
  243. _flags.state = MISSION_STOPPED;
  244. _flags.nav_cmd_loaded = false;
  245. _flags.do_cmd_loaded = false;
  246. }
  247. // get singleton instance
  248. static AP_Mission *get_singleton() {
  249. return _singleton;
  250. }
  251. /* Do not allow copies */
  252. AP_Mission(const AP_Mission &other) = delete;
  253. AP_Mission &operator=(const AP_Mission&) = delete;
  254. // mission state enumeration
  255. enum mission_state {
  256. MISSION_STOPPED=0,
  257. MISSION_RUNNING=1,
  258. MISSION_COMPLETE=2
  259. };
  260. ///
  261. /// public mission methods
  262. ///
  263. /// init - initialises this library including checks the version in eeprom matches this library
  264. void init();
  265. /// status - returns the status of the mission (i.e. Mission_Started, Mission_Complete, Mission_Stopped
  266. mission_state state() const { return _flags.state; }
  267. /// num_commands - returns total number of commands in the mission
  268. /// this number includes offset 0, the home location
  269. uint16_t num_commands() const { return _cmd_total; }
  270. /// num_commands_max - returns maximum number of commands that can be stored
  271. uint16_t num_commands_max() const;
  272. /// start - resets current commands to point to the beginning of the mission
  273. /// To-Do: should we validate the mission first and return true/false?
  274. void start();
  275. /// stop - stops mission execution. subsequent calls to update() will have no effect until the mission is started or resumed
  276. void stop();
  277. /// resume - continues the mission execution from where we last left off
  278. /// previous running commands will be re-initialised
  279. void resume();
  280. /// start_or_resume - if MIS_AUTORESTART=0 this will call resume(), otherwise it will call start()
  281. void start_or_resume();
  282. /// check mission starts with a takeoff command
  283. bool starts_with_takeoff_cmd();
  284. /// reset - reset mission to the first command
  285. void reset();
  286. /// clear - clears out mission
  287. bool clear();
  288. /// truncate - truncate any mission items beyond given index
  289. void truncate(uint16_t index);
  290. /// 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
  291. /// should be called at 10hz or higher
  292. void update();
  293. ///
  294. /// public command methods
  295. ///
  296. /// add_cmd - adds a command to the end of the command list and writes to storage
  297. /// returns true if successfully added, false on failure
  298. /// cmd.index is updated with it's new position in the mission
  299. bool add_cmd(Mission_Command& cmd);
  300. /// replace_cmd - replaces the command at position 'index' in the command list with the provided cmd
  301. /// replacing the current active command will have no effect until the command is restarted
  302. /// returns true if successfully replaced, false on failure
  303. bool replace_cmd(uint16_t index, const Mission_Command& cmd);
  304. /// is_nav_cmd - returns true if the command's id is a "navigation" command, false if "do" or "conditional" command
  305. static bool is_nav_cmd(const Mission_Command& cmd);
  306. /// get_current_nav_cmd - returns the current "navigation" command
  307. const Mission_Command& get_current_nav_cmd() const { return _nav_cmd; }
  308. /// get_current_nav_index - returns the current "navigation" command index
  309. /// Note that this will return 0 if there is no command. This is
  310. /// used in MAVLink reporting of the mission command
  311. uint16_t get_current_nav_index() const {
  312. return _nav_cmd.index==AP_MISSION_CMD_INDEX_NONE?0:_nav_cmd.index; }
  313. /// get_prev_nav_cmd_id - returns the previous "navigation" command id
  314. /// if there was no previous nav command it returns AP_MISSION_CMD_ID_NONE
  315. /// we do not return the entire command to save on RAM
  316. uint16_t get_prev_nav_cmd_id() const { return _prev_nav_cmd_id; }
  317. /// get_prev_nav_cmd_index - returns the previous "navigation" commands index (i.e. position in the mission command list)
  318. /// if there was no previous nav command it returns AP_MISSION_CMD_INDEX_NONE
  319. /// we do not return the entire command to save on RAM
  320. uint16_t get_prev_nav_cmd_index() const { return _prev_nav_cmd_index; }
  321. /// 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)
  322. /// if there was no previous nav command it returns AP_MISSION_CMD_INDEX_NONE
  323. /// we do not return the entire command to save on RAM
  324. uint16_t get_prev_nav_cmd_with_wp_index() const { return _prev_nav_cmd_wp_index; }
  325. /// get_next_nav_cmd - gets next "navigation" command found at or after start_index
  326. /// returns true if found, false if not found (i.e. reached end of mission command list)
  327. /// accounts for do_jump commands
  328. bool get_next_nav_cmd(uint16_t start_index, Mission_Command& cmd);
  329. /// get the ground course of the next navigation leg in centidegrees
  330. /// from 0 36000. Return default_angle if next navigation
  331. /// leg cannot be determined
  332. int32_t get_next_ground_course_cd(int32_t default_angle);
  333. /// get_current_do_cmd - returns active "do" command
  334. const Mission_Command& get_current_do_cmd() const { return _do_cmd; }
  335. // set_current_cmd - jumps to command specified by index
  336. bool set_current_cmd(uint16_t index);
  337. /// load_cmd_from_storage - load command from storage
  338. /// true is return if successful
  339. bool read_cmd_from_storage(uint16_t index, Mission_Command& cmd) const;
  340. /// write_cmd_to_storage - write a command to storage
  341. /// cmd.index is used to calculate the storage location
  342. /// true is returned if successful
  343. bool write_cmd_to_storage(uint16_t index, const Mission_Command& cmd);
  344. /// write_home_to_storage - writes the special purpose cmd 0 (home) to storage
  345. /// home is taken directly from ahrs
  346. void write_home_to_storage();
  347. static MAV_MISSION_RESULT convert_MISSION_ITEM_to_MISSION_ITEM_INT(const mavlink_mission_item_t &mission_item,
  348. mavlink_mission_item_int_t &mission_item_int) WARN_IF_UNUSED;
  349. static MAV_MISSION_RESULT convert_MISSION_ITEM_INT_to_MISSION_ITEM(const mavlink_mission_item_int_t &mission_item_int,
  350. mavlink_mission_item_t &mission_item) WARN_IF_UNUSED;
  351. // mavlink_int_to_mission_cmd - converts mavlink message to an AP_Mission::Mission_Command object which can be stored to eeprom
  352. // return MAV_MISSION_ACCEPTED on success, MAV_MISSION_RESULT error on failure
  353. static MAV_MISSION_RESULT mavlink_int_to_mission_cmd(const mavlink_mission_item_int_t& packet, AP_Mission::Mission_Command& cmd);
  354. // mavlink_cmd_long_to_mission_cmd - converts a mavlink cmd long to an AP_Mission::Mission_Command object which can be stored to eeprom
  355. // return MAV_MISSION_ACCEPTED on success, MAV_MISSION_RESULT error on failure
  356. static MAV_MISSION_RESULT mavlink_cmd_long_to_mission_cmd(const mavlink_command_long_t& packet, AP_Mission::Mission_Command& cmd);
  357. // mission_cmd_to_mavlink_int - converts an AP_Mission::Mission_Command object to a mavlink message which can be sent to the GCS
  358. // return true on success, false on failure
  359. static bool mission_cmd_to_mavlink_int(const AP_Mission::Mission_Command& cmd, mavlink_mission_item_int_t& packet);
  360. // return the last time the mission changed in milliseconds
  361. uint32_t last_change_time_ms(void) const { return _last_change_time_ms; }
  362. // find the nearest landing sequence starting point (DO_LAND_START) and
  363. // return its index. Returns 0 if no appropriate DO_LAND_START point can
  364. // be found.
  365. uint16_t get_landing_sequence_start();
  366. // find the nearest landing sequence starting point (DO_LAND_START) and
  367. // switch to that mission item. Returns false if no DO_LAND_START
  368. // available.
  369. bool jump_to_landing_sequence(void);
  370. // jumps the mission to the closest landing abort that is planned, returns false if unable to find a valid abort
  371. bool jump_to_abort_landing_sequence(void);
  372. // get a reference to the AP_Mission semaphore, allowing an external caller to lock the
  373. // storage while working with multiple waypoints
  374. HAL_Semaphore_Recursive &get_semaphore(void) {
  375. return _rsem;
  376. }
  377. // returns true if the mission contains the requested items
  378. bool contains_item(MAV_CMD command) const;
  379. // user settable parameters
  380. static const struct AP_Param::GroupInfo var_info[];
  381. private:
  382. static AP_Mission *_singleton;
  383. static StorageAccess _storage;
  384. static bool stored_in_location(uint16_t id);
  385. struct Mission_Flags {
  386. mission_state state;
  387. uint8_t nav_cmd_loaded : 1; // true if a "navigation" command has been loaded into _nav_cmd
  388. uint8_t do_cmd_loaded : 1; // true if a "do"/"conditional" command has been loaded into _do_cmd
  389. uint8_t do_cmd_all_done : 1; // true if all "do"/"conditional" commands have been completed (stops unnecessary searching through eeprom for do commands)
  390. } _flags;
  391. ///
  392. /// private methods
  393. ///
  394. /// complete - mission is marked complete and clean-up performed including calling the mission_complete_fn
  395. void complete();
  396. bool verify_command(const Mission_Command& cmd);
  397. bool start_command(const Mission_Command& cmd);
  398. /// advance_current_nav_cmd - moves current nav command forward
  399. // starting_index is used to set the index from which searching will begin, leave as 0 to search from the current navigation target
  400. /// do command will also be loaded
  401. /// accounts for do-jump commands
  402. // returns true if command is advanced, false if failed (i.e. mission completed)
  403. bool advance_current_nav_cmd(uint16_t starting_index = 0);
  404. /// advance_current_do_cmd - moves current do command forward
  405. /// accounts for do-jump commands
  406. /// returns true if successfully advanced (can it ever be unsuccessful?)
  407. void advance_current_do_cmd();
  408. /// get_next_cmd - gets next command found at or after start_index
  409. /// returns true if found, false if not found (i.e. mission complete)
  410. /// accounts for do_jump commands
  411. /// increment_jump_num_times_if_found should be set to true if advancing the active navigation command
  412. bool get_next_cmd(uint16_t start_index, Mission_Command& cmd, bool increment_jump_num_times_if_found);
  413. /// get_next_do_cmd - gets next "do" or "conditional" command after start_index
  414. /// returns true if found, false if not found
  415. /// stops and returns false if it hits another navigation command before it finds the first do or conditional command
  416. /// accounts for do_jump commands but never increments the jump's num_times_run (get_next_nav_cmd is responsible for this)
  417. bool get_next_do_cmd(uint16_t start_index, Mission_Command& cmd);
  418. ///
  419. /// jump handling methods
  420. ///
  421. // init_jump_tracking - initialise jump_tracking variables
  422. void init_jump_tracking();
  423. /// get_jump_times_run - returns number of times the jump command has been run
  424. /// return is signed to be consistent with do-jump cmd's repeat count which can be -1 (to signify to repeat forever)
  425. int16_t get_jump_times_run(const Mission_Command& cmd);
  426. /// increment_jump_times_run - increments the recorded number of times the jump command has been run
  427. void increment_jump_times_run(Mission_Command& cmd);
  428. /// check_eeprom_version - checks version of missions stored in eeprom matches this library
  429. /// command list will be cleared if they do not match
  430. void check_eeprom_version();
  431. /// sanity checks that the masked fields are not NaN's or infinite
  432. static MAV_MISSION_RESULT sanity_check_params(const mavlink_mission_item_int_t& packet);
  433. // parameters
  434. AP_Int16 _cmd_total; // total number of commands in the mission
  435. AP_Int8 _restart; // controls mission starting point when entering Auto mode (either restart from beginning of mission or resume from last command run)
  436. AP_Int16 _options; // bitmask options for missions, currently for mission clearing on reboot but can be expanded as required
  437. // pointer to main program functions
  438. mission_cmd_fn_t _cmd_start_fn; // pointer to function which will be called when a new command is started
  439. mission_cmd_fn_t _cmd_verify_fn; // pointer to function which will be called repeatedly to ensure a command is progressing
  440. mission_complete_fn_t _mission_complete_fn; // pointer to function which will be called when mission completes
  441. // internal variables
  442. struct Mission_Command _nav_cmd; // current "navigation" command. It's position in the command list is held in _nav_cmd.index
  443. struct Mission_Command _do_cmd; // current "do" command. It's position in the command list is held in _do_cmd.index
  444. uint16_t _prev_nav_cmd_id; // id of the previous "navigation" command. (WAYPOINT, LOITER_TO_ALT, ect etc)
  445. uint16_t _prev_nav_cmd_index; // index of the previous "navigation" command. Rarely used which is why we don't store the whole command
  446. 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
  447. // jump related variables
  448. struct jump_tracking_struct {
  449. uint16_t index; // index of do-jump commands in mission
  450. int16_t num_times_run; // number of times this jump command has been run
  451. } _jump_tracking[AP_MISSION_MAX_NUM_DO_JUMP_COMMANDS];
  452. // last time that mission changed
  453. uint32_t _last_change_time_ms;
  454. // multi-thread support. This is static so it can be used from
  455. // const functions
  456. static HAL_Semaphore_Recursive _rsem;
  457. // mission items common to all vehicles:
  458. bool start_command_do_gripper(const AP_Mission::Mission_Command& cmd);
  459. bool start_command_do_servorelayevents(const AP_Mission::Mission_Command& cmd);
  460. bool start_command_camera(const AP_Mission::Mission_Command& cmd);
  461. bool start_command_parachute(const AP_Mission::Mission_Command& cmd);
  462. };
  463. namespace AP {
  464. AP_Mission *mission();
  465. };