APM:Libraries
AP_Mission.h
Go to the documentation of this file.
1 
4 /*
5  * The AP_Mission library:
6  * - responsible for managing a list of commands made up of "nav", "do" and "conditional" commands
7  * - reads and writes the mission commands to storage.
8  * - provides easy access to current, previous and upcoming waypoints
9  * - calls main program's command execution and verify functions.
10  * - accounts for the DO_JUMP command
11  *
12  */
13 #pragma once
14 
15 #include <AP_HAL/AP_HAL.h>
16 #include <AP_Vehicle/AP_Vehicle.h>
18 #include <AP_Math/AP_Math.h>
19 #include <AP_Common/AP_Common.h>
20 #include <AP_Param/AP_Param.h>
21 #include <AP_AHRS/AP_AHRS.h>
23 
24 // definitions
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
27 
28 #define AP_MISSION_MAX_NUM_DO_JUMP_COMMANDS 15 // allow up to 15 do-jump commands
29 
30 #define AP_MISSION_JUMP_REPEAT_FOREVER -1 // when do-jump command's repeat count is -1 this means endless repeat
31 
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)
35 
36 #define AP_MISSION_FIRST_REAL_COMMAND 1 // command #0 reserved to hold home position
37 
38 #define AP_MISSION_RESTART_DEFAULT 0 // resume the mission from the last command run by default
39 
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
42 
45 class AP_Mission {
46 
47 public:
48  // jump command structure
50  uint16_t target; // target command id
51  int16_t num_times; // num times to repeat. -1 = repeat forever
52  };
53 
54  // condition delay command structure
56  float seconds; // period of delay in seconds
57  };
58 
59  // condition delay command structure
61  float meters; // distance from next waypoint in meters
62  };
63 
64  // condition yaw command structure
66  float angle_deg; // target angle in degrees (0=north, 90=east)
67  float turn_rate_dps; // turn rate in degrees / second (0=use default)
68  int8_t direction; // -1 = ccw, +1 = cw
69  uint8_t relative_angle; // 0 = absolute angle, 1 = relative angle
70  };
71 
72  // change speed command structure
74  uint8_t speed_type; // 0=airspeed, 1=ground speed
75  float target_ms; // target speed in m/s, -1 means no change
76  float throttle_pct; // throttle as a percentage (i.e. 0 ~ 100), -1 means no change
77  };
78 
79  // set relay command structure
81  uint8_t num; // relay number from 1 to 4
82  uint8_t state; // on = 3.3V or 5V (depending upon board), off = 0V. only used for do-set-relay, not for do-repeat-relay
83  };
84 
85  // repeat relay command structure
87  uint8_t num; // relay number from 1 to 4
88  int16_t repeat_count; // number of times to trigger the relay
89  float cycle_time; // cycle time in seconds (the time between peaks or the time the relay is on and off for each cycle?)
90  };
91 
92  // set servo command structure
94  uint8_t channel; // servo channel
95  uint16_t pwm; // pwm value for servo
96  };
97 
98  // repeat servo command structure
100  uint8_t channel; // servo channel
101  uint16_t pwm; // pwm value for servo
102  int16_t repeat_count; // number of times to move the servo (returns to trim in between)
103  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?)
104  };
105 
106  // mount control command structure
108  float pitch; // pitch angle in degrees
109  float roll; // roll angle in degrees
110  float yaw; // yaw angle (relative to vehicle heading) in degrees
111  };
112 
113  // digicam control command structure
115  uint8_t shooting_mode; // ProgramAuto = 1, AV = 2, TV = 3, Man=4, IntelligentAuto=5, SuperiorAuto=6
116  uint16_t shutter_speed;
117  uint8_t aperture; // F stop number * 10
118  uint16_t ISO; // 80, 100, 200, etc
119  uint8_t exposure_type;
120  uint8_t cmd_id;
121  float engine_cutoff_time; // seconds
122  };
123 
124  // digicam control command structure
126  uint8_t session; // 1 = on, 0 = off
127  uint8_t zoom_pos;
128  int8_t zoom_step; // +1 = zoom in, -1 = zoom out
129  uint8_t focus_lock;
130  uint8_t shooting_cmd;
131  uint8_t cmd_id;
132  };
133 
134  // set cam trigger distance command structure
136  float meters; // distance
137  };
138 
139  // gripper command structure
141  uint8_t num; // gripper number
142  uint8_t action; // action (0 = release, 1 = grab)
143  };
144 
145  // high altitude balloon altitude wait
147  float altitude; // meters
148  float descent_rate; // m/s
149  uint8_t wiggle_time; // seconds
150  };
151 
152  // nav guided command
154  // max time is held in p1 field
155  float alt_min; // min alt below which the command will be aborted. 0 for no lower alt limit
156  float alt_max; // max alt above which the command will be aborted. 0 for no upper alt limit
157  float horiz_max; // max horizontal distance the vehicle can move before the command will be aborted. 0 for no horizontal limit
158  };
159 
160  // do VTOL transition
162  uint8_t target_state;
163  };
164 
165  // navigation delay command structure
167  float seconds; // period of delay in seconds
168  int8_t hour_utc; // absolute time's hour (utc)
169  int8_t min_utc; // absolute time's min (utc)
170  int8_t sec_utc; // absolute time's sec (utc)
171  };
172 
173  // DO_ENGINE_CONTROL support
175  bool start_control; // start or stop engine
176  bool cold_start; // use cold start procedure
177  uint16_t height_delay_cm; // height delay for start
178  };
179 
180  // NAV_SET_YAW_SPEED support
182  float angle_deg; // target angle in degrees (0=north, 90=east)
183  float speed; // speed in meters/second
184  uint8_t relative_angle; // 0 = absolute angle, 1 = relative angle
185  };
186 
187  // winch command structure
189  uint8_t num; // winch number
190  uint8_t action; // action (0 = relax, 1 = length control, 2 = rate control)
191  float release_length; // cable distance to unwind in meters, negative numbers to wind in cable
192  float release_rate; // release rate in meters/second
193  };
194 
195  union PACKED Content {
196  // jump structure
198 
199  // conditional delay
201 
202  // conditional distance
204 
205  // conditional yaw
207 
208  // change speed
210 
211  // do-set-relay
213 
214  // do-repeat-relay
216 
217  // do-set-servo
219 
220  // do-repeate-servo
222 
223  // mount control
225 
226  // camera configure
228 
229  // camera control
231 
232  // cam trigg distance
234 
235  // do-gripper
237 
238  // do-guided-limits
240 
241  // cam trigg distance
243 
244  // do vtol transition
246 
247  // DO_ENGINE_CONTROL
249 
250  // navigation delay
252 
253  // navigation delay
255 
256  // do-winch
258 
259  // location
260  Location location; // Waypoint location
261 
262  // raw bytes, for reading/writing to eeprom. Note that only 10 bytes are available
263  // if a 16 bit command ID is used
264  uint8_t bytes[12];
265  };
266 
267  // command structure
269  uint16_t index; // this commands position in the command list
270  uint16_t id; // mavlink command id
271  uint16_t p1; // general purpose parameter 1
273 
274  // return a human-readable interpretation of the ID stored in this command
275  const char *type() const;
276  };
277 
278 
279  // main program function pointers
280  FUNCTOR_TYPEDEF(mission_cmd_fn_t, bool, const Mission_Command&);
281  FUNCTOR_TYPEDEF(mission_complete_fn_t, void);
282 
283  // constructor
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) :
285  _ahrs(ahrs),
286  _cmd_start_fn(cmd_start_fn),
287  _cmd_verify_fn(cmd_verify_fn),
288  _mission_complete_fn(mission_complete_fn),
293  {
294  // load parameter defaults
296 
297  // clear commands
300 
301  // initialise other internal variables
303  _flags.nav_cmd_loaded = false;
304  _flags.do_cmd_loaded = false;
305  }
306 
307  /* Do not allow copies */
308  AP_Mission(const AP_Mission &other) = delete;
309  AP_Mission &operator=(const AP_Mission&) = delete;
310 
311  // mission state enumeration
316  };
317 
321 
323  void init();
324 
326  mission_state state() const { return _flags.state; }
327 
330  uint16_t num_commands() const { return _cmd_total; }
331 
333  uint16_t num_commands_max() const;
334 
337  void start();
338 
340  void stop();
341 
344  void resume();
345 
347  void start_or_resume();
348 
351 
353  void reset();
354 
357  bool clear();
358 
360  void truncate(uint16_t index);
361 
364  void update();
365 
369 
373  bool add_cmd(Mission_Command& cmd);
374 
378  bool replace_cmd(uint16_t index, Mission_Command& cmd);
379 
381  static bool is_nav_cmd(const Mission_Command& cmd);
382 
384  const Mission_Command& get_current_nav_cmd() const { return _nav_cmd; }
385 
389  uint16_t get_current_nav_index() const {
391 
395  uint16_t get_prev_nav_cmd_id() const { return _prev_nav_cmd_id; }
396 
400  uint16_t get_prev_nav_cmd_index() const { return _prev_nav_cmd_index; }
401 
406 
410  bool get_next_nav_cmd(uint16_t start_index, Mission_Command& cmd);
411 
415  int32_t get_next_ground_course_cd(int32_t default_angle);
416 
418  const Mission_Command& get_current_do_cmd() const { return _do_cmd; }
419 
420  // set_current_cmd - jumps to command specified by index
421  bool set_current_cmd(uint16_t index);
422 
425  bool read_cmd_from_storage(uint16_t index, Mission_Command& cmd) const;
426 
430  bool write_cmd_to_storage(uint16_t index, Mission_Command& cmd);
431 
434  void write_home_to_storage();
435 
436  // mavlink_to_mission_cmd - converts mavlink message to an AP_Mission::Mission_Command object which can be stored to eeprom
437  // return MAV_MISSION_ACCEPTED on success, MAV_MISSION_RESULT error on failure
438  static MAV_MISSION_RESULT mavlink_to_mission_cmd(const mavlink_mission_item_t& packet, AP_Mission::Mission_Command& cmd);
439  static MAV_MISSION_RESULT mavlink_int_to_mission_cmd(const mavlink_mission_item_int_t& packet, AP_Mission::Mission_Command& cmd);
440 
441  // mavlink_cmd_long_to_mission_cmd - converts a mavlink cmd long to an AP_Mission::Mission_Command object which can be stored to eeprom
442  // return MAV_MISSION_ACCEPTED on success, MAV_MISSION_RESULT error on failure
443  static MAV_MISSION_RESULT mavlink_cmd_long_to_mission_cmd(const mavlink_command_long_t& packet, AP_Mission::Mission_Command& cmd);
444 
445  // mission_cmd_to_mavlink - converts an AP_Mission::Mission_Command object to a mavlink message which can be sent to the GCS
446  // return true on success, false on failure
447  static bool mission_cmd_to_mavlink(const AP_Mission::Mission_Command& cmd, mavlink_mission_item_t& packet);
448  static bool mission_cmd_to_mavlink_int(const AP_Mission::Mission_Command& cmd, mavlink_mission_item_int_t& packet);
449 
450  // return the last time the mission changed in milliseconds
451  uint32_t last_change_time_ms(void) const { return _last_change_time_ms; }
452 
453  // find the nearest landing sequence starting point (DO_LAND_START) and
454  // return its index. Returns 0 if no appropriate DO_LAND_START point can
455  // be found.
456  uint16_t get_landing_sequence_start();
457 
458  // find the nearest landing sequence starting point (DO_LAND_START) and
459  // switch to that mission item. Returns false if no DO_LAND_START
460  // available.
461  bool jump_to_landing_sequence(void);
462 
463  // user settable parameters
464  static const struct AP_Param::GroupInfo var_info[];
465 
466 private:
468 
469  struct Mission_Flags {
471  uint8_t nav_cmd_loaded : 1; // true if a "navigation" command has been loaded into _nav_cmd
472  uint8_t do_cmd_loaded : 1; // true if a "do"/"conditional" command has been loaded into _do_cmd
473  uint8_t do_cmd_all_done : 1; // true if all "do"/"conditional" commands have been completed (stops unnecessary searching through eeprom for do commands)
474  } _flags;
475 
479 
481  void complete();
482 
486  // returns true if command is advanced, false if failed (i.e. mission completed)
488 
492  void advance_current_do_cmd();
493 
498  bool get_next_cmd(uint16_t start_index, Mission_Command& cmd, bool increment_jump_num_times_if_found);
499 
504  bool get_next_do_cmd(uint16_t start_index, Mission_Command& cmd);
505 
509  // init_jump_tracking - initialise jump_tracking variables
510  void init_jump_tracking();
511 
514  int16_t get_jump_times_run(const Mission_Command& cmd);
515 
518 
521  void check_eeprom_version();
522 
524  static MAV_MISSION_RESULT sanity_check_params(const mavlink_mission_item_int_t& packet);
525 
526  // references to external libraries
527  const AP_AHRS& _ahrs; // used only for home position
528 
529  // parameters
530  AP_Int16 _cmd_total; // total number of commands in the mission
531  AP_Int8 _restart; // controls mission starting point when entering Auto mode (either restart from beginning of mission or resume from last command run)
532  AP_Int16 _options; // bitmask options for missions, currently for mission clearing on reboot but can be expanded as required
533 
534  // pointer to main program functions
535  mission_cmd_fn_t _cmd_start_fn; // pointer to function which will be called when a new command is started
536  mission_cmd_fn_t _cmd_verify_fn; // pointer to function which will be called repeatedly to ensure a command is progressing
537  mission_complete_fn_t _mission_complete_fn; // pointer to function which will be called when mission completes
538 
539  // internal variables
540  struct Mission_Command _nav_cmd; // current "navigation" command. It's position in the command list is held in _nav_cmd.index
541  struct Mission_Command _do_cmd; // current "do" command. It's position in the command list is held in _do_cmd.index
542  uint16_t _prev_nav_cmd_id; // id of the previous "navigation" command. (WAYPOINT, LOITER_TO_ALT, ect etc)
543  uint16_t _prev_nav_cmd_index; // index of the previous "navigation" command. Rarely used which is why we don't store the whole command
544  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
545 
546  // jump related variables
548  uint16_t index; // index of do-jump commands in mission
549  int16_t num_times_run; // number of times this jump command has been run
551 
552  // last time that mission changed
554 };
static bool is_nav_cmd(const Mission_Command &cmd)
is_nav_cmd - returns true if the command&#39;s id is a "navigation" command, false if "do" or "conditiona...
Definition: AP_Mission.cpp:284
Do_Engine_Control do_engine_control
Definition: AP_Mission.h:248
static bool mission_cmd_to_mavlink_int(const AP_Mission::Mission_Command &cmd, mavlink_mission_item_int_t &packet)
Jump_Command jump
Definition: AP_Mission.h:197
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
Definition: AP_Mission.h:544
uint16_t get_prev_nav_cmd_id() const
Definition: AP_Mission.h:395
void complete()
complete - mission is marked complete and clean-up performed including calling the mission_complete_f...
Mount_Control mount_control
Definition: AP_Mission.h:224
Repeat_Servo_Command repeat_servo
Definition: AP_Mission.h:221
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)
Definition: AP_Mission.h:284
AP_AHRS_NavEKF & ahrs
Definition: AHRS_Test.cpp:39
void start_or_resume()
start_or_resume - if MIS_AUTORESTART=0 this will call resume(), otherwise it will call start() ...
Definition: AP_Mission.cpp:150
bool jump_to_landing_sequence(void)
struct Mission_Command _do_cmd
Definition: AP_Mission.h:541
Object managing Mission.
Definition: AP_Mission.h:45
uint16_t get_current_nav_index() const
Definition: AP_Mission.h:389
void start()
Definition: AP_Mission.cpp:65
void init()
init - initialises this library including checks the version in eeprom matches this library ...
Definition: AP_Mission.cpp:45
void truncate(uint16_t index)
truncate - truncate any mission items beyond given index
Definition: AP_Mission.cpp:197
uint16_t num_commands() const
Definition: AP_Mission.h:330
static MAV_MISSION_RESULT sanity_check_params(const mavlink_mission_item_int_t &packet)
sanity checks that the masked fields are not NaN&#39;s or infinite
Definition: AP_Mission.cpp:533
Digicam_Control digicam_control
Definition: AP_Mission.h:230
Conditional_Delay_Command delay
Definition: AP_Mission.h:200
AP_Mission & operator=(const AP_Mission &)=delete
Repeat_Relay_Command repeat_relay
Definition: AP_Mission.h:215
AP_Int8 _restart
Definition: AP_Mission.h:531
Conditional_Distance_Command distance
Definition: AP_Mission.h:203
bool add_cmd(Mission_Command &cmd)
Definition: AP_Mission.cpp:254
Navigation_Delay_Command nav_delay
Definition: AP_Mission.h:251
const Mission_Command & get_current_nav_cmd() const
get_current_nav_cmd - returns the current "navigation" command
Definition: AP_Mission.h:384
void reset()
reset - reset mission to the first command
Definition: AP_Mission.cpp:160
void check_eeprom_version()
bool clear()
Definition: AP_Mission.cpp:175
Guided_Limits_Command guided_limits
Definition: AP_Mission.h:239
bool read_cmd_from_storage(uint16_t index, Mission_Command &cmd) const
Definition: AP_Mission.cpp:453
void init_jump_tracking()
void stop()
stop - stops mission execution. subsequent calls to update() will have no effect until the mission is...
Definition: AP_Mission.cpp:79
bool replace_cmd(uint16_t index, Mission_Command &cmd)
Definition: AP_Mission.cpp:272
struct AP_Mission::Mission_Flags _flags
mission_cmd_fn_t _cmd_verify_fn
Definition: AP_Mission.h:536
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)
Definition: AP_Mission.cpp:973
static MAV_MISSION_RESULT mavlink_to_mission_cmd(const mavlink_mission_item_t &packet, AP_Mission::Mission_Command &cmd)
Definition: AP_Mission.cpp:922
Set_Relay_Command relay
Definition: AP_Mission.h:212
Gripper_Command gripper
Definition: AP_Mission.h:236
const Mission_Command & get_current_do_cmd() const
get_current_do_cmd - returns active "do" command
Definition: AP_Mission.h:418
uint16_t get_prev_nav_cmd_index() const
Definition: AP_Mission.h:400
mission_state state() const
status - returns the status of the mission (i.e. Mission_Started, Mission_Complete, Mission_Stopped
Definition: AP_Mission.h:326
Yaw_Command yaw
Definition: AP_Mission.h:206
bool advance_current_nav_cmd()
uint16_t get_prev_nav_cmd_with_wp_index() const
Definition: AP_Mission.h:405
uint32_t last_change_time_ms(void) const
Definition: AP_Mission.h:451
Change_Speed_Command speed
Definition: AP_Mission.h:209
bool set_current_cmd(uint16_t index)
Definition: AP_Mission.cpp:339
uint16_t get_landing_sequence_start()
Altitude_Wait altitude_wait
Definition: AP_Mission.h:242
uint16_t _prev_nav_cmd_id
Definition: AP_Mission.h:542
struct Mission_Command _nav_cmd
Definition: AP_Mission.h:540
void resume()
Definition: AP_Mission.cpp:86
Set_Yaw_Speed set_yaw_speed
Definition: AP_Mission.h:254
void update()
Definition: AP_Mission.cpp:206
bool get_next_nav_cmd(uint16_t start_index, Mission_Command &cmd)
Definition: AP_Mission.cpp:293
uint16_t num_commands_max() const
num_commands_max - returns maximum number of commands that can be stored
Digicam_Configure digicam_configure
Definition: AP_Mission.h:227
Common definitions and utility routines for the ArduPilot libraries.
mission_complete_fn_t _mission_complete_fn
Definition: AP_Mission.h:537
AP_Int16 _options
Definition: AP_Mission.h:532
uint16_t _prev_nav_cmd_index
Definition: AP_Mission.h:543
void advance_current_do_cmd()
int32_t get_next_ground_course_cd(int32_t default_angle)
Definition: AP_Mission.cpp:321
#define AP_MISSION_CMD_INDEX_NONE
Definition: AP_Mission.h:33
AP_Int16 _cmd_total
Definition: AP_Mission.h:530
Set_Servo_Command servo
Definition: AP_Mission.h:218
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)
Definition: AP_Mission.cpp:577
Cam_Trigg_Distance cam_trigg_dist
Definition: AP_Mission.h:233
Do_VTOL_Transition do_vtol_transition
Definition: AP_Mission.h:245
FUNCTOR_TYPEDEF(mission_cmd_fn_t, bool, const Mission_Command &)
void write_home_to_storage()
Definition: AP_Mission.cpp:525
#define AP_MISSION_MAX_NUM_DO_JUMP_COMMANDS
Definition: AP_Mission.h:28
#define AP_MISSION_CMD_ID_NONE
Definition: AP_Mission.h:32
#define PACKED
Definition: AP_Common.h:28
mission_cmd_fn_t _cmd_start_fn
Definition: AP_Mission.h:535
bool starts_with_takeoff_cmd()
check mission starts with a takeoff command
Definition: AP_Mission.cpp:132
uint32_t _last_change_time_ms
Definition: AP_Mission.h:553
static const struct AP_Param::GroupInfo var_info[]
Definition: AP_Mission.h:464
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]
const AP_AHRS & _ahrs
Definition: AP_Mission.h:527
static StorageAccess _storage
Definition: AP_Mission.h:467
bool get_next_cmd(uint16_t start_index, Mission_Command &cmd, bool increment_jump_num_times_if_found)
Winch_Command winch
Definition: AP_Mission.h:257
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)
Definition: AP_Param.cpp:1214
bool write_cmd_to_storage(uint16_t index, Mission_Command &cmd)
Definition: AP_Mission.cpp:494