APM:Libraries
AP_Mission.cpp
Go to the documentation of this file.
1 
4 #include "AP_Mission.h"
6 #include <GCS_MAVLink/GCS.h>
7 
9 
10  // @Param: TOTAL
11  // @DisplayName: Total mission commands
12  // @Description: The number of mission mission items that has been loaded by the ground station. Do not change this manually.
13  // @Range: 0 32766
14  // @Increment: 1
15  // @User: Advanced
16  AP_GROUPINFO("TOTAL", 0, AP_Mission, _cmd_total, 0),
17 
18  // @Param: RESTART
19  // @DisplayName: Mission Restart when entering Auto mode
20  // @Description: Controls mission starting point when entering Auto mode (either restart from beginning of mission or resume from last command run)
21  // @Values: 0:Resume Mission, 1:Restart Mission
22  // @User: Advanced
23  AP_GROUPINFO("RESTART", 1, AP_Mission, _restart, AP_MISSION_RESTART_DEFAULT),
24 
25  // @Param: OPTIONS
26  // @DisplayName: Mission options bitmask
27  // @Description: Bitmask of what options to use in missions.
28  // @Bitmask: 0:Clear Mission on reboot
29  // @User: Advanced
30  AP_GROUPINFO("OPTIONS", 2, AP_Mission, _options, AP_MISSION_OPTIONS_DEFAULT),
31 
33 };
34 
35 extern const AP_HAL::HAL& hal;
36 
37 // storage object
39 
43 
46 {
47  // check_eeprom_version - checks version of missions stored in eeprom matches this library
48  // command list will be cleared if they do not match
50 
51  // changes in Content size break the storage
52  static_assert(sizeof(union Content) == 12, "AP_Mission: Content must be 12 bytes");
53 
54  // If Mission Clear bit is set then it should clear the mission, otherwise retain the mission.
56  gcs().send_text(MAV_SEVERITY_INFO, "Clearing Mission");
57  clear();
58  }
59 
61 }
62 
66 {
68 
69  reset(); // reset mission to the first command, resets jump tracking
70 
71  // advance to the first command
72  if (!advance_current_nav_cmd()) {
73  // on failure set mission complete
74  complete();
75  }
76 }
77 
80 {
82 }
83 
87 {
88  // if mission had completed then start it from the first command
89  if (_flags.state == MISSION_COMPLETE) {
90  start();
91  return;
92  }
93 
94  // if mission had stopped then restart it
95  if (_flags.state == MISSION_STOPPED) {
97 
98  // if no valid nav command index restart from beginning
100  start();
101  return;
102  }
103  }
104 
105  // ensure cache coherence
107  // if we failed to read the command from storage, then the command may have
108  // been from a previously loaded mission it is illogical to ever resume
109  // flying to a command that has been excluded from the current mission
110  start();
111  return;
112  }
113 
114  // restart active navigation command. We run these on resume()
115  // regardless of whether the mission was stopped, as we may be
116  // re-entering AUTO mode and the nav_cmd callback needs to be run
117  // to setup the current target waypoint
118 
119  // Note: if there is no active command then the mission must have been stopped just after the previous nav command completed
120  // update will take care of finding and starting the nav command
121  if (_flags.nav_cmd_loaded) {
123  }
124 
125  // restart active do command
128  }
129 }
130 
133 {
134  Mission_Command cmd = {};
135  uint16_t cmd_index = _restart ? AP_MISSION_CMD_INDEX_NONE : _nav_cmd.index;
136  if (cmd_index == AP_MISSION_CMD_INDEX_NONE) {
137  cmd_index = AP_MISSION_FIRST_REAL_COMMAND;
138  }
139 
140  if (!get_next_nav_cmd(cmd_index, cmd)) {
141  return false;
142  }
143  if (cmd.id != MAV_CMD_NAV_TAKEOFF) {
144  return false;
145  }
146  return true;
147 }
148 
151 {
152  if (_restart) {
153  start();
154  } else {
155  resume();
156  }
157 }
158 
161 {
162  _flags.nav_cmd_loaded = false;
163  _flags.do_cmd_loaded = false;
164  _flags.do_cmd_all_done = false;
171 }
172 
176 {
177  // do not allow clearing the mission while it is running
178  if (_flags.state == MISSION_RUNNING) {
179  return false;
180  }
181 
182  // remove all commands
183  _cmd_total.set_and_save(0);
184 
185  // clear index to commands
188  _flags.nav_cmd_loaded = false;
189  _flags.do_cmd_loaded = false;
190 
191  // return success
192  return true;
193 }
194 
195 
197 void AP_Mission::truncate(uint16_t index)
198 {
199  if ((unsigned)_cmd_total > index) {
200  _cmd_total.set_and_save(index);
201  }
202 }
203 
207 {
208  // exit immediately if not running or no mission commands
209  if (_flags.state != MISSION_RUNNING || _cmd_total == 0) {
210  return;
211  }
212 
213  // check if we have an active nav command
215  // advance in mission if no active nav command
216  if (!advance_current_nav_cmd()) {
217  // failure to advance nav command means mission has completed
218  complete();
219  return;
220  }
221  }else{
222  // run the active nav command
223  if (_cmd_verify_fn(_nav_cmd)) {
224  // market _nav_cmd as complete (it will be started on the next iteration)
225  _flags.nav_cmd_loaded = false;
226  // immediately advance to the next mission command
227  if (!advance_current_nav_cmd()) {
228  // failure to advance nav command means mission has completed
229  complete();
230  return;
231  }
232  }
233  }
234 
235  // check if we have an active do command
236  if (!_flags.do_cmd_loaded) {
238  }else{
239  // run the active do command
240  if (_cmd_verify_fn(_do_cmd)) {
241  // market _nav_cmd as complete (it will be started on the next iteration)
242  _flags.do_cmd_loaded = false;
243  }
244  }
245 }
246 
250 
255 {
256  // attempt to write the command to storage
257  bool ret = write_cmd_to_storage(_cmd_total, cmd);
258 
259  if (ret) {
260  // update command's index
261  cmd.index = _cmd_total;
262  // increment total number of commands
263  _cmd_total.set_and_save(_cmd_total + 1);
264  }
265 
266  return ret;
267 }
268 
272 bool AP_Mission::replace_cmd(uint16_t index, Mission_Command& cmd)
273 {
274  // sanity check index
275  if (index >= (unsigned)_cmd_total) {
276  return false;
277  }
278 
279  // attempt to write the command to storage
280  return write_cmd_to_storage(index, cmd);
281 }
282 
285 {
286  // NAV commands all have ids below MAV_CMD_NAV_LAST except NAV_SET_YAW_SPEED
287  return (cmd.id <= MAV_CMD_NAV_LAST || cmd.id == MAV_CMD_NAV_SET_YAW_SPEED);
288 }
289 
293 bool AP_Mission::get_next_nav_cmd(uint16_t start_index, Mission_Command& cmd)
294 {
295  uint16_t cmd_index = start_index;
296 
297  // search until the end of the mission command list
298  while(cmd_index < (unsigned)_cmd_total) {
299  // get next command
300  if (!get_next_cmd(cmd_index, cmd, false)) {
301  // no more commands so return failure
302  return false;
303  }else{
304  // if found a "navigation" command then return it
305  if (is_nav_cmd(cmd)) {
306  return true;
307  }else{
308  // move on in list
309  cmd_index++;
310  }
311  }
312  }
313 
314  // if we got this far we did not find a navigation command
315  return false;
316 }
317 
321 int32_t AP_Mission::get_next_ground_course_cd(int32_t default_angle)
322 {
323  Mission_Command cmd;
324  if (!get_next_nav_cmd(_nav_cmd.index+1, cmd)) {
325  return default_angle;
326  }
327  // special handling for nav commands with no target location
328  if (cmd.id == MAV_CMD_NAV_GUIDED_ENABLE ||
329  cmd.id == MAV_CMD_NAV_DELAY) {
330  return default_angle;
331  }
332  if (cmd.id == MAV_CMD_NAV_SET_YAW_SPEED) {
333  return (_nav_cmd.content.set_yaw_speed.angle_deg * 100);
334  }
336 }
337 
338 // set_current_cmd - jumps to command specified by index
339 bool AP_Mission::set_current_cmd(uint16_t index)
340 {
341  Mission_Command cmd;
342 
343  // sanity check index and that we have a mission
344  if (index >= (unsigned)_cmd_total || _cmd_total == 1) {
345  return false;
346  }
347 
348  // stop the current running do command
350  _flags.do_cmd_loaded = false;
351  _flags.do_cmd_all_done = false;
352 
353  // stop current nav cmd
354  _flags.nav_cmd_loaded = false;
355 
356  // if index is zero then the user wants to completely restart the mission
357  if (index == 0 || _flags.state == MISSION_COMPLETE) {
361  // reset the jump tracking to zero
363  if (index == 0) {
364  index = 1;
365  }
366  }
367 
368  // if the mission is stopped or completed move the nav_cmd index to the specified point and set the state to stopped
369  // so that if the user resumes the mission it will begin at the specified index
370  if (_flags.state != MISSION_RUNNING) {
371  // search until we find next nav command or reach end of command list
372  while (!_flags.nav_cmd_loaded) {
373  // get next command
374  if (!get_next_cmd(index, cmd, true)) {
376  return false;
377  }
378 
379  // check if navigation or "do" command
380  if (is_nav_cmd(cmd)) {
381  // set current navigation command
382  _nav_cmd = cmd;
383  _flags.nav_cmd_loaded = true;
384  }else{
385  // set current do command
386  if (!_flags.do_cmd_loaded) {
387  _do_cmd = cmd;
388  _flags.do_cmd_loaded = true;
389  }
390  }
391  // move onto next command
392  index = cmd.index+1;
393  }
394 
395  // if we have not found a do command then set flag to show there are no do-commands to be run before nav command completes
396  if (!_flags.do_cmd_loaded) {
397  _flags.do_cmd_all_done = true;
398  }
399 
400  // if we got this far then the mission can safely be "resumed" from the specified index so we set the state to "stopped"
402  return true;
403  }
404 
405  // the state must be MISSION_RUNNING
406  // search until we find next nav command or reach end of command list
407  while (!_flags.nav_cmd_loaded) {
408  // get next command
409  if (!get_next_cmd(index, cmd, true)) {
410  // if we run out of nav commands mark mission as complete
411  complete();
412  // return true because we did what was requested
413  // which was apparently to jump to a command at the end of the mission
414  return true;
415  }
416 
417  // check if navigation or "do" command
418  if (is_nav_cmd(cmd)) {
419  // save previous nav command index
422  // save separate previous nav command index if it contains lat,long,alt
423  if (!(cmd.content.location.lat == 0 && cmd.content.location.lng == 0)) {
425  }
426  // set current navigation command and start it
427  _nav_cmd = cmd;
428  _flags.nav_cmd_loaded = true;
430  }else{
431  // set current do command and start it (if not already set)
432  if (!_flags.do_cmd_loaded) {
433  _do_cmd = cmd;
434  _flags.do_cmd_loaded = true;
436  }
437  }
438  // move onto next command
439  index = cmd.index+1;
440  }
441 
442  // if we have not found a do command then set flag to show there are no do-commands to be run before nav command completes
443  if (!_flags.do_cmd_loaded) {
444  _flags.do_cmd_all_done = true;
445  }
446 
447  // if we got this far we must have successfully advanced the nav command
448  return true;
449 }
450 
453 bool AP_Mission::read_cmd_from_storage(uint16_t index, Mission_Command& cmd) const
454 {
455  // exit immediately if index is beyond last command but we always let cmd #0 (i.e. home) be read
456  if (index >= (unsigned)_cmd_total && index != 0) {
457  return false;
458  }
459 
460  // special handling for command #0 which is home
461  if (index == 0) {
462  cmd.index = 0;
463  cmd.id = MAV_CMD_NAV_WAYPOINT;
464  cmd.p1 = 0;
465  cmd.content.location = _ahrs.get_home();
466  }else{
467  // Find out proper location in memory by using the start_byte position + the index
468  // we can load a command, we don't process it yet
469  // read WP position
470  uint16_t pos_in_storage = 4 + (index * AP_MISSION_EEPROM_COMMAND_SIZE);
471 
472  uint8_t b1 = _storage.read_byte(pos_in_storage);
473  if (b1 == 0) {
474  cmd.id = _storage.read_uint16(pos_in_storage+1);
475  cmd.p1 = _storage.read_uint16(pos_in_storage+3);
476  _storage.read_block(cmd.content.bytes, pos_in_storage+5, 10);
477  } else {
478  cmd.id = b1;
479  cmd.p1 = _storage.read_uint16(pos_in_storage+1);
480  _storage.read_block(cmd.content.bytes, pos_in_storage+3, 12);
481  }
482 
483  // set command's index to it's position in eeprom
484  cmd.index = index;
485  }
486 
487  // return success
488  return true;
489 }
490 
495 {
496  // range check cmd's index
497  if (index >= num_commands_max()) {
498  return false;
499  }
500 
501  // calculate where in storage the command should be placed
502  uint16_t pos_in_storage = 4 + (index * AP_MISSION_EEPROM_COMMAND_SIZE);
503 
504  if (cmd.id < 256) {
505  _storage.write_byte(pos_in_storage, cmd.id);
506  _storage.write_uint16(pos_in_storage+1, cmd.p1);
507  _storage.write_block(pos_in_storage+3, cmd.content.bytes, 12);
508  } else {
509  // if the command ID is above 256 we store a 0 followed by the 16 bit command ID
510  _storage.write_byte(pos_in_storage, 0);
511  _storage.write_uint16(pos_in_storage+1, cmd.id);
512  _storage.write_uint16(pos_in_storage+3, cmd.p1);
513  _storage.write_block(pos_in_storage+5, cmd.content.bytes, 10);
514  }
515 
516  // remember when the mission last changed
518 
519  // return success
520  return true;
521 }
522 
526 {
527  Mission_Command home_cmd = {};
528  home_cmd.id = MAV_CMD_NAV_WAYPOINT;
529  home_cmd.content.location = _ahrs.get_home();
530  write_cmd_to_storage(0,home_cmd);
531 }
532 
533 MAV_MISSION_RESULT AP_Mission::sanity_check_params(const mavlink_mission_item_int_t& packet) {
534  uint8_t nan_mask;
535  switch (packet.command) {
536  case MAV_CMD_NAV_WAYPOINT:
537  nan_mask = ~(1 << 3); // param 4 can be nan
538  break;
539  case MAV_CMD_NAV_LAND:
540  nan_mask = ~(1 << 3); // param 4 can be nan
541  break;
542  case MAV_CMD_NAV_TAKEOFF:
543  nan_mask = ~(1 << 3); // param 4 can be nan
544  break;
545  case MAV_CMD_NAV_VTOL_TAKEOFF:
546  nan_mask = ~(1 << 3); // param 4 can be nan
547  break;
548  case MAV_CMD_NAV_VTOL_LAND:
549  nan_mask = ~((1 << 2) | (1 << 3)); // param 3 and 4 can be nan
550  break;
551  default:
552  nan_mask = 0xff;
553  break;
554  }
555 
556  if (((nan_mask & (1 << 0)) && isnan(packet.param1)) ||
557  isinf(packet.param1)) {
558  return MAV_MISSION_INVALID_PARAM1;
559  }
560  if (((nan_mask & (1 << 1)) && isnan(packet.param2)) ||
561  isinf(packet.param2)) {
562  return MAV_MISSION_INVALID_PARAM2;
563  }
564  if (((nan_mask & (1 << 2)) && isnan(packet.param3)) ||
565  isinf(packet.param3)) {
566  return MAV_MISSION_INVALID_PARAM3;
567  }
568  if (((nan_mask & (1 << 3)) && isnan(packet.param4)) ||
569  isinf(packet.param4)) {
570  return MAV_MISSION_INVALID_PARAM4;
571  }
572  return MAV_MISSION_ACCEPTED;
573 }
574 
575 // mavlink_to_mission_cmd - converts mavlink message to an AP_Mission::Mission_Command object which can be stored to eeprom
576 // return MAV_MISSION_ACCEPTED on success, MAV_MISSION_RESULT error on failure
577 MAV_MISSION_RESULT AP_Mission::mavlink_int_to_mission_cmd(const mavlink_mission_item_int_t& packet, AP_Mission::Mission_Command& cmd)
578 {
579  bool copy_location = false;
580  bool copy_alt = false;
581 
582  // command's position in mission list and mavlink id
583  cmd.index = packet.seq;
584  cmd.id = packet.command;
585  cmd.content.location.options = 0;
586 
587  MAV_MISSION_RESULT param_check = sanity_check_params(packet);
588  if (param_check != MAV_MISSION_ACCEPTED) {
589  return param_check;
590  }
591 
592  // command specific conversions from mavlink packet to mission command
593  switch (cmd.id) {
594 
595  case 0:
596  // this is reserved for storing 16 bit command IDs
597  return MAV_MISSION_INVALID;
598 
599  case MAV_CMD_NAV_WAYPOINT: // MAV ID: 16
600  {
601  copy_location = true;
602  /*
603  the 15 byte limit means we can't fit both delay and radius
604  in the cmd structure. When we expand the mission structure
605  we can do this properly
606  */
607 #if APM_BUILD_TYPE(APM_BUILD_ArduPlane)
608  // acceptance radius in meters and pass by distance in meters
609  uint16_t acp = packet.param2; // param 2 is acceptance radius in meters is held in low p1
610  uint16_t passby = packet.param3; // param 3 is pass by distance in meters is held in high p1
611 
612  // limit to 255 so it does not wrap during the shift or mask operation
613  passby = MIN(0xFF,passby);
614  acp = MIN(0xFF,acp);
615 
616  cmd.p1 = (passby << 8) | (acp & 0x00FF);
617 #else
618  // delay at waypoint in seconds (this is for copters???)
619  cmd.p1 = packet.param1;
620 #endif
621  }
622  break;
623 
624  case MAV_CMD_NAV_LOITER_UNLIM: // MAV ID: 17
625  copy_location = true;
626  cmd.p1 = fabsf(packet.param3); // store radius as 16bit since no other params are competing for space
627  cmd.content.location.flags.loiter_ccw = (packet.param3 < 0); // -1 = counter clockwise, +1 = clockwise
628  break;
629 
630  case MAV_CMD_NAV_LOITER_TURNS: // MAV ID: 18
631  {
632  copy_location = true;
633  uint16_t num_turns = packet.param1; // param 1 is number of times to circle is held in low p1
634  uint16_t radius_m = fabsf(packet.param3); // param 3 is radius in meters is held in high p1
635  cmd.p1 = (radius_m<<8) | (num_turns & 0x00FF); // store radius in high byte of p1, num turns in low byte of p1
636  cmd.content.location.flags.loiter_ccw = (packet.param3 < 0);
637  cmd.content.location.flags.loiter_xtrack = (packet.param4 > 0); // 0 to xtrack from center of waypoint, 1 to xtrack from tangent exit location
638  }
639  break;
640 
641  case MAV_CMD_NAV_LOITER_TIME: // MAV ID: 19
642  copy_location = true;
643  cmd.p1 = packet.param1; // loiter time in seconds uses all 16 bits, 8bit seconds is too small. No room for radius.
644  cmd.content.location.flags.loiter_ccw = (packet.param3 < 0);
645  cmd.content.location.flags.loiter_xtrack = (packet.param4 > 0); // 0 to xtrack from center of waypoint, 1 to xtrack from tangent exit location
646  break;
647 
648  case MAV_CMD_NAV_RETURN_TO_LAUNCH: // MAV ID: 20
649  break;
650 
651  case MAV_CMD_NAV_LAND: // MAV ID: 21
652  copy_location = true;
653  cmd.p1 = packet.param1; // abort target altitude(m) (plane only)
654  cmd.content.location.flags.loiter_ccw = is_negative(packet.param4); // yaw direction, (plane deepstall only)
655  break;
656 
657  case MAV_CMD_NAV_TAKEOFF: // MAV ID: 22
658  copy_location = true; // only altitude is used
659  cmd.p1 = packet.param1; // minimum pitch (plane only)
660  break;
661 
662  case MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT: // MAV ID: 30
663  copy_location = true; // lat/lng used for heading lock
664  cmd.p1 = packet.param1; // Climb/Descend
665  // 0 = Neutral, cmd complete at +/- 5 of indicated alt.
666  // 1 = Climb, cmd complete at or above indicated alt.
667  // 2 = Descend, cmd complete at or below indicated alt.
668  break;
669 
670  case MAV_CMD_NAV_LOITER_TO_ALT: // MAV ID: 31
671  copy_location = true;
672  cmd.p1 = fabsf(packet.param2); // param2 is radius in meters
673  cmd.content.location.flags.loiter_ccw = (packet.param2 < 0);
674  cmd.content.location.flags.loiter_xtrack = (packet.param4 > 0); // 0 to xtrack from center of waypoint, 1 to xtrack from tangent exit location
675  break;
676 
677  case MAV_CMD_NAV_SPLINE_WAYPOINT: // MAV ID: 82
678  copy_location = true;
679  cmd.p1 = packet.param1; // delay at waypoint in seconds
680  break;
681 
682  case MAV_CMD_NAV_GUIDED_ENABLE: // MAV ID: 92
683  cmd.p1 = packet.param1; // on/off. >0.5 means "on", hand-over control to external controller
684  break;
685 
686  case MAV_CMD_NAV_DELAY: // MAV ID: 94
687  cmd.content.nav_delay.seconds = packet.param1; // delay in seconds
688  cmd.content.nav_delay.hour_utc = packet.param2;// absolute time's hour (utc)
689  cmd.content.nav_delay.min_utc = packet.param3;// absolute time's min (utc)
690  cmd.content.nav_delay.sec_utc = packet.param4; // absolute time's second (utc)
691  break;
692 
693  case MAV_CMD_CONDITION_DELAY: // MAV ID: 112
694  cmd.content.delay.seconds = packet.param1; // delay in seconds
695  break;
696 
697  case MAV_CMD_CONDITION_DISTANCE: // MAV ID: 114
698  cmd.content.distance.meters = packet.param1; // distance in meters from next waypoint
699  break;
700 
701  case MAV_CMD_CONDITION_YAW: // MAV ID: 115
702  cmd.content.yaw.angle_deg = packet.param1; // target angle in degrees
703  cmd.content.yaw.turn_rate_dps = packet.param2; // 0 = use default turn rate otherwise specific turn rate in deg/sec
704  cmd.content.yaw.direction = packet.param3; // -1 = ccw, +1 = cw
705  cmd.content.yaw.relative_angle = packet.param4; // lng=0: absolute angle provided, lng=1: relative angle provided
706  break;
707 
708  case MAV_CMD_DO_SET_MODE: // MAV ID: 176
709  cmd.p1 = packet.param1; // flight mode identifier
710  break;
711 
712  case MAV_CMD_DO_JUMP: // MAV ID: 177
713  cmd.content.jump.target = packet.param1; // jump-to command number
714  cmd.content.jump.num_times = packet.param2; // repeat count
715  break;
716 
717  case MAV_CMD_DO_CHANGE_SPEED: // MAV ID: 178
718  cmd.content.speed.speed_type = packet.param1; // 0 = airspeed, 1 = ground speed
719  cmd.content.speed.target_ms = packet.param2; // target speed in m/s
720  cmd.content.speed.throttle_pct = packet.param3; // throttle as a percentage from 0 ~ 100%
721  break;
722 
723  case MAV_CMD_DO_SET_HOME:
724  copy_location = true;
725  cmd.p1 = packet.param1; // p1=0 means use current location, p=1 means use provided location
726  break;
727 
728  case MAV_CMD_DO_SET_RELAY: // MAV ID: 181
729  cmd.content.relay.num = packet.param1; // relay number
730  cmd.content.relay.state = packet.param2; // 0:off, 1:on
731  break;
732 
733  case MAV_CMD_DO_REPEAT_RELAY: // MAV ID: 182
734  cmd.content.repeat_relay.num = packet.param1; // relay number
735  cmd.content.repeat_relay.repeat_count = packet.param2; // count
736  cmd.content.repeat_relay.cycle_time = packet.param3; // time converted from seconds to milliseconds
737  break;
738 
739  case MAV_CMD_DO_SET_SERVO: // MAV ID: 183
740  cmd.content.servo.channel = packet.param1; // channel
741  cmd.content.servo.pwm = packet.param2; // PWM
742  break;
743 
744  case MAV_CMD_DO_REPEAT_SERVO: // MAV ID: 184
745  cmd.content.repeat_servo.channel = packet.param1; // channel
746  cmd.content.repeat_servo.pwm = packet.param2; // PWM
747  cmd.content.repeat_servo.repeat_count = packet.param3; // count
748  cmd.content.repeat_servo.cycle_time = packet.param4; // time in seconds
749  break;
750 
751  case MAV_CMD_DO_LAND_START: // MAV ID: 189
752  copy_location = true;
753  break;
754 
755  case MAV_CMD_DO_SET_ROI: // MAV ID: 201
756  copy_location = true;
757  cmd.p1 = packet.param1; // 0 = no roi, 1 = next waypoint, 2 = waypoint number, 3 = fixed location, 4 = given target (not supported)
758  break;
759 
760  case MAV_CMD_DO_DIGICAM_CONFIGURE: // MAV ID: 202
761  cmd.content.digicam_configure.shooting_mode = packet.param1;
762  cmd.content.digicam_configure.shutter_speed = packet.param2;
763  cmd.content.digicam_configure.aperture = packet.param3;
764  cmd.content.digicam_configure.ISO = packet.param4;
765  cmd.content.digicam_configure.exposure_type = packet.x;
766  cmd.content.digicam_configure.cmd_id = packet.y;
768  break;
769 
770  case MAV_CMD_DO_DIGICAM_CONTROL: // MAV ID: 203
771  cmd.content.digicam_control.session = packet.param1;
772  cmd.content.digicam_control.zoom_pos = packet.param2;
773  cmd.content.digicam_control.zoom_step = packet.param3;
774  cmd.content.digicam_control.focus_lock = packet.param4;
775  cmd.content.digicam_control.shooting_cmd = packet.x;
776  cmd.content.digicam_control.cmd_id = packet.y;
777  break;
778 
779  case MAV_CMD_DO_MOUNT_CONTROL: // MAV ID: 205
780  cmd.content.mount_control.pitch = packet.param1;
781  cmd.content.mount_control.roll = packet.param2;
782  cmd.content.mount_control.yaw = packet.param3;
783  break;
784 
785  case MAV_CMD_DO_SET_CAM_TRIGG_DIST: // MAV ID: 206
786  cmd.content.cam_trigg_dist.meters = packet.param1; // distance between camera shots in meters
787  break;
788 
789  case MAV_CMD_DO_FENCE_ENABLE: // MAV ID: 207
790  cmd.p1 = packet.param1; // action 0=disable, 1=enable
791  break;
792 
793  case MAV_CMD_DO_PARACHUTE: // MAV ID: 208
794  cmd.p1 = packet.param1; // action 0=disable, 1=enable, 2=release. See PARACHUTE_ACTION enum
795  break;
796 
797  case MAV_CMD_DO_INVERTED_FLIGHT: // MAV ID: 210
798  cmd.p1 = packet.param1; // normal=0 inverted=1
799  break;
800 
801  case MAV_CMD_DO_GRIPPER: // MAV ID: 211
802  cmd.content.gripper.num = packet.param1; // gripper number
803  cmd.content.gripper.action = packet.param2; // action 0=release, 1=grab. See GRIPPER_ACTION enum
804  break;
805 
806  case MAV_CMD_DO_GUIDED_LIMITS: // MAV ID: 222
807  cmd.p1 = packet.param1; // max time in seconds the external controller will be allowed to control the vehicle
808  cmd.content.guided_limits.alt_min = packet.param2; // min alt below which the command will be aborted. 0 for no lower alt limit
809  cmd.content.guided_limits.alt_max = packet.param3; // max alt above which the command will be aborted. 0 for no upper alt limit
810  cmd.content.guided_limits.horiz_max = packet.param4;// max horizontal distance the vehicle can move before the command will be aborted. 0 for no horizontal limit
811  break;
812 
813  case MAV_CMD_DO_AUTOTUNE_ENABLE: // MAV ID: 211
814  cmd.p1 = packet.param1; // disable=0 enable=1
815  break;
816 
817  case MAV_CMD_NAV_ALTITUDE_WAIT: // MAV ID: 83
818  cmd.content.altitude_wait.altitude = packet.param1;
819  cmd.content.altitude_wait.descent_rate = packet.param2;
820  cmd.content.altitude_wait.wiggle_time = packet.param3;
821  break;
822 
823  case MAV_CMD_NAV_VTOL_TAKEOFF:
824  copy_location = true;
825  break;
826 
827  case MAV_CMD_NAV_VTOL_LAND:
828  copy_location = true;
829  break;
830 
831  case MAV_CMD_DO_VTOL_TRANSITION:
832  cmd.content.do_vtol_transition.target_state = packet.param1;
833  break;
834 
835  case MAV_CMD_DO_SET_REVERSE:
836  cmd.p1 = packet.param1; // 0 = forward, 1 = reverse
837  break;
838 
839  case MAV_CMD_DO_ENGINE_CONTROL:
840  cmd.content.do_engine_control.start_control = (packet.param1>0);
841  cmd.content.do_engine_control.cold_start = (packet.param2>0);
842  cmd.content.do_engine_control.height_delay_cm = packet.param3*100;
843  break;
844 
845  case MAV_CMD_NAV_PAYLOAD_PLACE:
846  cmd.p1 = packet.param1*100; // copy max-descend parameter (m->cm)
847  copy_location = true;
848  break;
849 
850  case MAV_CMD_NAV_SET_YAW_SPEED:
851  cmd.content.set_yaw_speed.angle_deg = packet.param1; // target angle in degrees
852  cmd.content.set_yaw_speed.speed = packet.param2; // speed in meters/second
853  cmd.content.set_yaw_speed.relative_angle = packet.param3; // 0 = absolute angle, 1 = relative angle
854  break;
855 
856  case MAV_CMD_DO_WINCH: // MAV ID: 42600
857  cmd.content.winch.num = packet.param1; // winch number
858  cmd.content.winch.action = packet.param2; // action (0 = relax, 1 = length control, 2 = rate control). See WINCH_ACTION enum
859  cmd.content.winch.release_length = packet.param3; // cable distance to unwind in meters, negative numbers to wind in cable
860  cmd.content.winch.release_rate = packet.param4; // release rate in meters/second
861  break;
862 
863  default:
864  // unrecognised command
865  return MAV_MISSION_UNSUPPORTED;
866  }
867 
868  // copy location from mavlink to command
869  if (copy_location || copy_alt) {
870 
871  // sanity check location
872  if (copy_location) {
873  if (!check_lat(packet.x)) {
874  return MAV_MISSION_INVALID_PARAM5_X;
875  }
876  if (!check_lng(packet.y)) {
877  return MAV_MISSION_INVALID_PARAM6_Y;
878  }
879  }
880  if (isnan(packet.z) || fabsf(packet.z) >= LOCATION_ALT_MAX_M) {
881  return MAV_MISSION_INVALID_PARAM7;
882  }
883 
884  if (copy_location) {
885  cmd.content.location.lat = packet.x;
886  cmd.content.location.lng = packet.y;
887  }
888 
889  cmd.content.location.alt = packet.z * 100.0f; // convert packet's alt (m) to cmd alt (cm)
890 
891  switch (packet.frame) {
892 
893  case MAV_FRAME_MISSION:
894  case MAV_FRAME_GLOBAL:
896  break;
897 
898  case MAV_FRAME_GLOBAL_RELATIVE_ALT:
900  break;
901 
902 #if AP_TERRAIN_AVAILABLE
903  case MAV_FRAME_GLOBAL_TERRAIN_ALT:
904  // we mark it as a relative altitude, as it doesn't have
905  // home alt added
907  // mark altitude as above terrain, not above home
909  break;
910 #endif
911 
912  default:
913  return MAV_MISSION_UNSUPPORTED_FRAME;
914  }
915  }
916 
917  // if we got this far then it must have been successful
918  return MAV_MISSION_ACCEPTED;
919 }
920 
921 // converts a mission_item to mission_item_int and returns a mission_command
922 MAV_MISSION_RESULT AP_Mission::mavlink_to_mission_cmd(const mavlink_mission_item_t& packet, AP_Mission::Mission_Command& cmd)
923 {
924  mavlink_mission_item_int_t mav_cmd = {};
925 
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;
938 
939  /*
940  the strategy for handling both MISSION_ITEM and MISSION_ITEM_INT
941  is to pass the lat/lng in MISSION_ITEM_INT straight through, and
942  for MISSION_ITEM multiply by 1e7 here. We need an exception for
943  any commands which use the x and y fields not as
944  latitude/longitude.
945  */
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;
951  break;
952 
953  default:
954  // all other commands use x and y as lat/lon. We need to
955  // multiply by 1e7 to convert to int32_t
956  if (!check_lat(packet.x)) {
957  return MAV_MISSION_INVALID_PARAM5_X;
958  }
959  if (!check_lng(packet.y)) {
960  return MAV_MISSION_INVALID_PARAM6_Y;
961  }
962  mav_cmd.x = packet.x * 1.0e7f;
963  mav_cmd.y = packet.y * 1.0e7f;
964  break;
965  }
966 
967  MAV_MISSION_RESULT ans = mavlink_int_to_mission_cmd(mav_cmd, cmd);
968 
969  return ans;
970 }
971 
972 // converts a Mission_Command to mission_item_int and returns a mission_item
973 bool AP_Mission::mission_cmd_to_mavlink(const AP_Mission::Mission_Command& cmd, mavlink_mission_item_t& packet)
974 {
975  mavlink_mission_item_int_t mav_cmd = {};
976 
977  bool ans = mission_cmd_to_mavlink_int(cmd, (mavlink_mission_item_int_t&)mav_cmd);
978 
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;
991 
992  /*
993  the strategy for handling both MISSION_ITEM and MISSION_ITEM_INT
994  is to pass the lat/lng in MISSION_ITEM_INT straight through, and
995  for MISSION_ITEM multiply by 1e-7 here. We need an exception for
996  any commands which use the x and y fields not as
997  latitude/longitude.
998  */
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;
1004  break;
1005 
1006  default:
1007  // all other commands use x and y as lat/lon. We need to
1008  // multiply by 1e-7 to convert to int32_t
1009  packet.x = mav_cmd.x * 1.0e-7f;
1010  packet.y = mav_cmd.y * 1.0e-7f;
1011  break;
1012  }
1013 
1014  return ans;
1015 }
1016 
1017 // mavlink_cmd_long_to_mission_cmd - converts a mavlink cmd long to an AP_Mission::Mission_Command object which can be stored to eeprom
1018 // return MAV_MISSION_ACCEPTED on success, MAV_MISSION_RESULT error on failure
1019 MAV_MISSION_RESULT AP_Mission::mavlink_cmd_long_to_mission_cmd(const mavlink_command_long_t& packet, AP_Mission::Mission_Command& cmd)
1020 {
1021  mavlink_mission_item_t miss_item = {0};
1022 
1023  miss_item.param1 = packet.param1;
1024  miss_item.param2 = packet.param2;
1025  miss_item.param3 = packet.param3;
1026  miss_item.param4 = packet.param4;
1027 
1028  miss_item.command = packet.command;
1029  miss_item.target_system = packet.target_system;
1030  miss_item.target_component = packet.target_component;
1031 
1032  return mavlink_to_mission_cmd(miss_item, cmd);
1033 }
1034 
1035 // mission_cmd_to_mavlink - converts an AP_Mission::Mission_Command object to a mavlink message which can be sent to the GCS
1036 // return true on success, false on failure
1037 bool AP_Mission::mission_cmd_to_mavlink_int(const AP_Mission::Mission_Command& cmd, mavlink_mission_item_int_t& packet)
1038 {
1039  bool copy_location = false;
1040  bool copy_alt = false;
1041 
1042  // command's position in mission list and mavlink id
1043  packet.seq = cmd.index;
1044  packet.command = cmd.id;
1045 
1046  // set defaults
1047  packet.current = 0; // 1 if we are passing back the mission command that is currently being executed
1048  packet.param1 = 0;
1049  packet.param2 = 0;
1050  packet.param3 = 0;
1051  packet.param4 = 0;
1052  packet.autocontinue = 1;
1053 
1054  // command specific conversions from mission command to mavlink packet
1055  switch (cmd.id) {
1056  case 0:
1057  // this is reserved for 16 bit command IDs
1058  return false;
1059 
1060  case MAV_CMD_NAV_WAYPOINT: // MAV ID: 16
1061  copy_location = true;
1062 #if APM_BUILD_TYPE(APM_BUILD_ArduPlane)
1063  // acceptance radius in meters
1064 
1065  packet.param2 = LOWBYTE(cmd.p1); // param 2 is acceptance radius in meters is held in low p1
1066  packet.param3 = HIGHBYTE(cmd.p1); // param 3 is pass by distance in meters is held in high p1
1067 #else
1068  // delay at waypoint in seconds
1069  packet.param1 = cmd.p1;
1070 #endif
1071  break;
1072 
1073  case MAV_CMD_NAV_LOITER_UNLIM: // MAV ID: 17
1074  copy_location = true;
1075  packet.param3 = (float)cmd.p1;
1076  if (cmd.content.location.flags.loiter_ccw) {
1077  packet.param3 *= -1;
1078  }
1079  break;
1080 
1081  case MAV_CMD_NAV_LOITER_TURNS: // MAV ID: 18
1082  copy_location = true;
1083  packet.param1 = LOWBYTE(cmd.p1); // number of times to circle is held in low byte of p1
1084  packet.param3 = HIGHBYTE(cmd.p1); // radius is held in high byte of p1
1085  if (cmd.content.location.flags.loiter_ccw) {
1086  packet.param3 = -packet.param3;
1087  }
1088  packet.param4 = cmd.content.location.flags.loiter_xtrack; // 0 to xtrack from center of waypoint, 1 to xtrack from tangent exit location
1089  break;
1090 
1091  case MAV_CMD_NAV_LOITER_TIME: // MAV ID: 19
1092  copy_location = true;
1093  packet.param1 = cmd.p1; // loiter time in seconds
1094  if (cmd.content.location.flags.loiter_ccw) {
1095  packet.param3 = -1;
1096  } else {
1097  packet.param3 = 1;
1098  }
1099  packet.param4 = cmd.content.location.flags.loiter_xtrack; // 0 to xtrack from center of waypoint, 1 to xtrack from tangent exit location
1100  break;
1101 
1102  case MAV_CMD_NAV_RETURN_TO_LAUNCH: // MAV ID: 20
1103  break;
1104 
1105  case MAV_CMD_NAV_LAND: // MAV ID: 21
1106  copy_location = true;
1107  packet.param1 = cmd.p1; // abort target altitude(m) (plane only)
1108  packet.param4 = cmd.content.location.flags.loiter_ccw ? -1 : 1; // yaw direction, (plane deepstall only)
1109  break;
1110 
1111  case MAV_CMD_NAV_TAKEOFF: // MAV ID: 22
1112  copy_location = true; // only altitude is used
1113  packet.param1 = cmd.p1; // minimum pitch (plane only)
1114  break;
1115 
1116  case MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT: // MAV ID: 30
1117  copy_location = true; // lat/lng used for heading lock
1118  packet.param1 = cmd.p1; // Climb/Descend
1119  // 0 = Neutral, cmd complete at +/- 5 of indicated alt.
1120  // 1 = Climb, cmd complete at or above indicated alt.
1121  // 2 = Descend, cmd complete at or below indicated alt.
1122  break;
1123 
1124  case MAV_CMD_NAV_LOITER_TO_ALT: // MAV ID: 31
1125  copy_location = true;
1126  packet.param2 = cmd.p1; // loiter radius(m)
1127  if (cmd.content.location.flags.loiter_ccw) {
1128  packet.param2 = -packet.param2;
1129  }
1130  packet.param4 = cmd.content.location.flags.loiter_xtrack; // 0 to xtrack from center of waypoint, 1 to xtrack from tangent exit location
1131  break;
1132 
1133  case MAV_CMD_NAV_SPLINE_WAYPOINT: // MAV ID: 82
1134  copy_location = true;
1135  packet.param1 = cmd.p1; // delay at waypoint in seconds
1136  break;
1137 
1138  case MAV_CMD_NAV_GUIDED_ENABLE: // MAV ID: 92
1139  packet.param1 = cmd.p1; // on/off. >0.5 means "on", hand-over control to external controller
1140  break;
1141 
1142  case MAV_CMD_NAV_DELAY: // MAV ID: 94
1143  packet.param1 = cmd.content.nav_delay.seconds; // delay in seconds
1144  packet.param2 = cmd.content.nav_delay.hour_utc; // absolute time's day of week (utc)
1145  packet.param3 = cmd.content.nav_delay.min_utc; // absolute time's hour (utc)
1146  packet.param4 = cmd.content.nav_delay.sec_utc; // absolute time's min (utc)
1147  break;
1148 
1149  case MAV_CMD_CONDITION_DELAY: // MAV ID: 112
1150  packet.param1 = cmd.content.delay.seconds; // delay in seconds
1151  break;
1152 
1153  case MAV_CMD_CONDITION_DISTANCE: // MAV ID: 114
1154  packet.param1 = cmd.content.distance.meters; // distance in meters from next waypoint
1155  break;
1156 
1157  case MAV_CMD_CONDITION_YAW: // MAV ID: 115
1158  packet.param1 = cmd.content.yaw.angle_deg; // target angle in degrees
1159  packet.param2 = cmd.content.yaw.turn_rate_dps; // 0 = use default turn rate otherwise specific turn rate in deg/sec
1160  packet.param3 = cmd.content.yaw.direction; // -1 = ccw, +1 = cw
1161  packet.param4 = cmd.content.yaw.relative_angle; // 0 = absolute angle provided, 1 = relative angle provided
1162  break;
1163 
1164  case MAV_CMD_DO_SET_MODE: // MAV ID: 176
1165  packet.param1 = cmd.p1; // set flight mode identifier
1166  break;
1167 
1168  case MAV_CMD_DO_JUMP: // MAV ID: 177
1169  packet.param1 = cmd.content.jump.target; // jump-to command number
1170  packet.param2 = cmd.content.jump.num_times; // repeat count
1171  break;
1172 
1173  case MAV_CMD_DO_CHANGE_SPEED: // MAV ID: 178
1174  packet.param1 = cmd.content.speed.speed_type; // 0 = airspeed, 1 = ground speed
1175  packet.param2 = cmd.content.speed.target_ms; // speed in m/s
1176  packet.param3 = cmd.content.speed.throttle_pct; // throttle as a percentage from 0 ~ 100%
1177  break;
1178 
1179  case MAV_CMD_DO_SET_HOME: // MAV ID: 179
1180  copy_location = true;
1181  packet.param1 = cmd.p1; // p1=0 means use current location, p=1 means use provided location
1182  break;
1183 
1184  case MAV_CMD_DO_SET_RELAY: // MAV ID: 181
1185  packet.param1 = cmd.content.relay.num; // relay number
1186  packet.param2 = cmd.content.relay.state; // 0:off, 1:on
1187  break;
1188 
1189  case MAV_CMD_DO_REPEAT_RELAY: // MAV ID: 182
1190  packet.param1 = cmd.content.repeat_relay.num; // relay number
1191  packet.param2 = cmd.content.repeat_relay.repeat_count; // count
1192  packet.param3 = cmd.content.repeat_relay.cycle_time; // time in seconds
1193  break;
1194 
1195  case MAV_CMD_DO_SET_SERVO: // MAV ID: 183
1196  packet.param1 = cmd.content.servo.channel; // channel
1197  packet.param2 = cmd.content.servo.pwm; // PWM
1198  break;
1199 
1200  case MAV_CMD_DO_REPEAT_SERVO: // MAV ID: 184
1201  packet.param1 = cmd.content.repeat_servo.channel; // channel
1202  packet.param2 = cmd.content.repeat_servo.pwm; // PWM
1203  packet.param3 = cmd.content.repeat_servo.repeat_count; // count
1204  packet.param4 = cmd.content.repeat_servo.cycle_time; // time in milliseconds converted to seconds
1205  break;
1206 
1207  case MAV_CMD_DO_LAND_START: // MAV ID: 189
1208  copy_location = true;
1209  break;
1210 
1211  case MAV_CMD_DO_SET_ROI: // MAV ID: 201
1212  copy_location = true;
1213  packet.param1 = cmd.p1; // 0 = no roi, 1 = next waypoint, 2 = waypoint number, 3 = fixed location, 4 = given target (not supported)
1214  break;
1215 
1216  case MAV_CMD_DO_DIGICAM_CONFIGURE: // MAV ID: 202
1217  packet.param1 = cmd.content.digicam_configure.shooting_mode;
1218  packet.param2 = cmd.content.digicam_configure.shutter_speed;
1219  packet.param3 = cmd.content.digicam_configure.aperture;
1220  packet.param4 = cmd.content.digicam_configure.ISO;
1221  packet.x = cmd.content.digicam_configure.exposure_type;
1222  packet.y = cmd.content.digicam_configure.cmd_id;
1224  break;
1225 
1226  case MAV_CMD_DO_DIGICAM_CONTROL: // MAV ID: 203
1227  packet.param1 = cmd.content.digicam_control.session;
1228  packet.param2 = cmd.content.digicam_control.zoom_pos;
1229  packet.param3 = cmd.content.digicam_control.zoom_step;
1230  packet.param4 = cmd.content.digicam_control.focus_lock;
1231  packet.x = cmd.content.digicam_control.shooting_cmd;
1232  packet.y = cmd.content.digicam_control.cmd_id;
1233  break;
1234 
1235  case MAV_CMD_DO_MOUNT_CONTROL: // MAV ID: 205
1236  packet.param1 = cmd.content.mount_control.pitch;
1237  packet.param2 = cmd.content.mount_control.roll;
1238  packet.param3 = cmd.content.mount_control.yaw;
1239  break;
1240 
1241  case MAV_CMD_DO_SET_CAM_TRIGG_DIST: // MAV ID: 206
1242  packet.param1 = cmd.content.cam_trigg_dist.meters; // distance between camera shots in meters
1243  break;
1244 
1245  case MAV_CMD_DO_FENCE_ENABLE: // MAV ID: 207
1246  packet.param1 = cmd.p1; // action 0=disable, 1=enable
1247  break;
1248 
1249  case MAV_CMD_DO_PARACHUTE: // MAV ID: 208
1250  packet.param1 = cmd.p1; // action 0=disable, 1=enable, 2=release. See PARACHUTE_ACTION enum
1251  break;
1252 
1253  case MAV_CMD_DO_INVERTED_FLIGHT: // MAV ID: 210
1254  packet.param1 = cmd.p1; // normal=0 inverted=1
1255  break;
1256 
1257  case MAV_CMD_DO_GRIPPER: // MAV ID: 211
1258  packet.param1 = cmd.content.gripper.num; // gripper number
1259  packet.param2 = cmd.content.gripper.action; // action 0=release, 1=grab. See GRIPPER_ACTION enum
1260  break;
1261 
1262  case MAV_CMD_DO_GUIDED_LIMITS: // MAV ID: 222
1263  packet.param1 = cmd.p1; // max time in seconds the external controller will be allowed to control the vehicle
1264  packet.param2 = cmd.content.guided_limits.alt_min; // min alt below which the command will be aborted. 0 for no lower alt limit
1265  packet.param3 = cmd.content.guided_limits.alt_max; // max alt above which the command will be aborted. 0 for no upper alt limit
1266  packet.param4 = cmd.content.guided_limits.horiz_max;// max horizontal distance the vehicle can move before the command will be aborted. 0 for no horizontal limit
1267  break;
1268 
1269  case MAV_CMD_DO_AUTOTUNE_ENABLE:
1270  packet.param1 = cmd.p1; // disable=0 enable=1
1271  break;
1272 
1273  case MAV_CMD_DO_SET_REVERSE:
1274  packet.param1 = cmd.p1; // 0 = forward, 1 = reverse
1275  break;
1276 
1277  case MAV_CMD_NAV_ALTITUDE_WAIT: // MAV ID: 83
1278  packet.param1 = cmd.content.altitude_wait.altitude;
1279  packet.param2 = cmd.content.altitude_wait.descent_rate;
1280  packet.param3 = cmd.content.altitude_wait.wiggle_time;
1281  break;
1282 
1283  case MAV_CMD_NAV_VTOL_TAKEOFF:
1284  copy_location = true;
1285  break;
1286 
1287  case MAV_CMD_NAV_VTOL_LAND:
1288  copy_location = true;
1289  break;
1290 
1291  case MAV_CMD_DO_VTOL_TRANSITION:
1292  packet.param1 = cmd.content.do_vtol_transition.target_state;
1293  break;
1294 
1295  case MAV_CMD_DO_ENGINE_CONTROL:
1296  packet.param1 = cmd.content.do_engine_control.start_control?1:0;
1297  packet.param2 = cmd.content.do_engine_control.cold_start?1:0;
1298  packet.param3 = cmd.content.do_engine_control.height_delay_cm*0.01f;
1299  break;
1300 
1301  case MAV_CMD_NAV_PAYLOAD_PLACE:
1302  copy_location = true;
1303  packet.param1 = cmd.p1/100.0f; // copy max-descend parameter (m->cm)
1304  break;
1305 
1306  case MAV_CMD_NAV_SET_YAW_SPEED:
1307  packet.param1 = cmd.content.set_yaw_speed.angle_deg; // target angle in degrees
1308  packet.param2 = cmd.content.set_yaw_speed.speed; // speed in meters/second
1309  packet.param3 = cmd.content.set_yaw_speed.relative_angle; // 0 = absolute angle, 1 = relative angle
1310  break;
1311 
1312  case MAV_CMD_DO_WINCH:
1313  packet.param1 = cmd.content.winch.num; // winch number
1314  packet.param2 = cmd.content.winch.action; // action (0 = relax, 1 = length control, 2 = rate control). See WINCH_ACTION enum
1315  packet.param3 = cmd.content.winch.release_length; // cable distance to unwind in meters, negative numbers to wind in cable
1316  packet.param4 = cmd.content.winch.release_rate; // release rate in meters/second
1317  break;
1318 
1319  default:
1320  // unrecognised command
1321  return false;
1322  }
1323 
1324  // copy location from mavlink to command
1325  if (copy_location) {
1326  packet.x = cmd.content.location.lat;
1327  packet.y = cmd.content.location.lng;
1328  }
1329  if (copy_location || copy_alt) {
1330  packet.z = cmd.content.location.alt / 100.0f; // cmd alt in cm to m
1331  if (cmd.content.location.flags.relative_alt) {
1332  packet.frame = MAV_FRAME_GLOBAL_RELATIVE_ALT;
1333  }else{
1334  packet.frame = MAV_FRAME_GLOBAL;
1335  }
1336 #if AP_TERRAIN_AVAILABLE
1337  if (cmd.content.location.flags.terrain_alt) {
1338  // this is a above-terrain altitude
1339  if (!cmd.content.location.flags.relative_alt) {
1340  // refuse to return non-relative terrain mission
1341  // items. Internally we do have these, and they
1342  // have home.alt added, but we should never be
1343  // returning them to the GCS, as the GCS doesn't know
1344  // our home.alt, so it would have no way to properly
1345  // interpret it
1346  return false;
1347  }
1348  packet.z = cmd.content.location.alt * 0.01f;
1349  packet.frame = MAV_FRAME_GLOBAL_TERRAIN_ALT;
1350  }
1351 #else
1352  // don't ever return terrain mission items if no terrain support
1353  if (cmd.content.location.flags.terrain_alt) {
1354  return false;
1355  }
1356 #endif
1357  }
1358 
1359  // if we got this far then it must have been successful
1360  return true;
1361 }
1362 
1366 
1369 {
1370  // flag mission as complete
1372 
1373  // callback to main program's mission complete function
1375 }
1376 
1380 // returns true if command is advanced, false if failed (i.e. mission completed)
1382 {
1383  Mission_Command cmd;
1384  uint16_t cmd_index;
1385 
1386  // exit immediately if we're not running
1387  if (_flags.state != MISSION_RUNNING) {
1388  return false;
1389  }
1390 
1391  // exit immediately if current nav command has not completed
1392  if (_flags.nav_cmd_loaded) {
1393  return false;
1394  }
1395 
1396  // stop the current running do command
1398  _flags.do_cmd_loaded = false;
1399  _flags.do_cmd_all_done = false;
1400 
1401  // get starting point for search
1402  cmd_index = _nav_cmd.index;
1403  if (cmd_index == AP_MISSION_CMD_INDEX_NONE) {
1404  // start from beginning of the mission command list
1405  cmd_index = AP_MISSION_FIRST_REAL_COMMAND;
1406  }else{
1407  // start from one position past the current nav command
1408  cmd_index++;
1409  }
1410 
1411  // avoid endless loops
1412  uint8_t max_loops = 255;
1413 
1414  // search until we find next nav command or reach end of command list
1415  while (!_flags.nav_cmd_loaded) {
1416  // get next command
1417  if (!get_next_cmd(cmd_index, cmd, true)) {
1418  return false;
1419  }
1420 
1421  // check if navigation or "do" command
1422  if (is_nav_cmd(cmd)) {
1423  // save previous nav command index
1426  // save separate previous nav command index if it contains lat,long,alt
1427  if (!(cmd.content.location.lat == 0 && cmd.content.location.lng == 0)) {
1429  }
1430  // set current navigation command and start it
1431  _nav_cmd = cmd;
1432  _flags.nav_cmd_loaded = true;
1434  }else{
1435  // set current do command and start it (if not already set)
1436  if (!_flags.do_cmd_loaded) {
1437  _do_cmd = cmd;
1438  _flags.do_cmd_loaded = true;
1440  } else {
1441  // protect against endless loops of do-commands
1442  if (max_loops-- == 0) {
1443  return false;
1444  }
1445  }
1446  }
1447  // move onto next command
1448  cmd_index = cmd.index+1;
1449  }
1450 
1451  // if we have not found a do command then set flag to show there are no do-commands to be run before nav command completes
1452  if (!_flags.do_cmd_loaded) {
1453  _flags.do_cmd_all_done = true;
1454  }
1455 
1456  // if we got this far we must have successfully advanced the nav command
1457  return true;
1458 }
1459 
1463 {
1464  Mission_Command cmd;
1465  uint16_t cmd_index;
1466 
1467  // exit immediately if we're not running or we've completed all possible "do" commands
1469  return;
1470  }
1471 
1472  // get starting point for search
1473  cmd_index = _do_cmd.index;
1474  if (cmd_index == AP_MISSION_CMD_INDEX_NONE) {
1475  cmd_index = AP_MISSION_FIRST_REAL_COMMAND;
1476  }else{
1477  // start from one position past the current do command
1478  cmd_index++;
1479  }
1480 
1481  // check if we've reached end of mission
1482  if (cmd_index >= (unsigned)_cmd_total) {
1483  // set flag to stop unnecessarily searching for do commands
1484  _flags.do_cmd_all_done = true;
1485  return;
1486  }
1487 
1488  // find next do command
1489  if (get_next_do_cmd(cmd_index, cmd)) {
1490  // set current do command and start it
1491  _do_cmd = cmd;
1492  _flags.do_cmd_loaded = true;
1494  }else{
1495  // set flag to stop unnecessarily searching for do commands
1496  _flags.do_cmd_all_done = true;
1497  }
1498 }
1499 
1504 bool AP_Mission::get_next_cmd(uint16_t start_index, Mission_Command& cmd, bool increment_jump_num_times_if_found)
1505 {
1506  uint16_t cmd_index = start_index;
1507  Mission_Command temp_cmd;
1508  uint16_t jump_index = AP_MISSION_CMD_INDEX_NONE;
1509 
1510  // search until the end of the mission command list
1511  uint8_t max_loops = 64;
1512  while(cmd_index < (unsigned)_cmd_total) {
1513  // load the next command
1514  if (!read_cmd_from_storage(cmd_index, temp_cmd)) {
1515  // this should never happen because of check above but just in case
1516  return false;
1517  }
1518 
1519  // check for do-jump command
1520  if (temp_cmd.id == MAV_CMD_DO_JUMP) {
1521 
1522  if (max_loops-- == 0) {
1523  return false;
1524  }
1525 
1526  // check for invalid target
1527  if ((temp_cmd.content.jump.target >= (unsigned)_cmd_total) || (temp_cmd.content.jump.target == 0)) {
1528  // To-Do: log an error?
1529  return false;
1530  }
1531 
1532  // check for endless loops
1533  if (!increment_jump_num_times_if_found && jump_index == cmd_index) {
1534  // we have somehow reached this jump command twice and there is no chance it will complete
1535  // To-Do: log an error?
1536  return false;
1537  }
1538 
1539  // record this command so we can check for endless loops
1540  if (jump_index == AP_MISSION_CMD_INDEX_NONE) {
1541  jump_index = cmd_index;
1542  }
1543 
1544  // check if jump command is 'repeat forever'
1546  // continue searching from jump target
1547  cmd_index = temp_cmd.content.jump.target;
1548  }else{
1549  // get number of times jump command has already been run
1550  int16_t jump_times_run = get_jump_times_run(temp_cmd);
1551  if (jump_times_run < temp_cmd.content.jump.num_times) {
1552  // update the record of the number of times run
1553  if (increment_jump_num_times_if_found) {
1554  increment_jump_times_run(temp_cmd);
1555  }
1556  // continue searching from jump target
1557  cmd_index = temp_cmd.content.jump.target;
1558  }else{
1559  // jump has been run specified number of times so move search to next command in mission
1560  cmd_index++;
1561  }
1562  }
1563  }else{
1564  // this is a non-jump command so return it
1565  cmd = temp_cmd;
1566  return true;
1567  }
1568  }
1569 
1570  // if we got this far we did not find a navigation command
1571  return false;
1572 }
1573 
1578 bool AP_Mission::get_next_do_cmd(uint16_t start_index, Mission_Command& cmd)
1579 {
1580  Mission_Command temp_cmd;
1581 
1582  // check we have not passed the end of the mission list
1583  if (start_index >= (unsigned)_cmd_total) {
1584  return false;
1585  }
1586 
1587  // get next command
1588  if (!get_next_cmd(start_index, temp_cmd, false)) {
1589  // no more commands so return failure
1590  return false;
1591  }else if (is_nav_cmd(temp_cmd)) {
1592  // if it's a "navigation" command then return false because we do not progress past nav commands
1593  return false;
1594  }else{
1595  // this must be a "do" or "conditional" and is not a do-jump command so return it
1596  cmd = temp_cmd;
1597  return true;
1598  }
1599 }
1600 
1604 
1605 // init_jump_tracking - initialise jump_tracking variables
1607 {
1608  for(uint8_t i=0; i<AP_MISSION_MAX_NUM_DO_JUMP_COMMANDS; i++) {
1611  }
1612 }
1613 
1616 {
1617  // exit immediately if cmd is not a do-jump command or target is invalid
1618  if ((cmd.id != MAV_CMD_DO_JUMP) || (cmd.content.jump.target >= (unsigned)_cmd_total) || (cmd.content.jump.target == 0)) {
1619  // To-Do: log an error?
1621  }
1622 
1623  // search through jump_tracking array for this cmd
1624  for (uint8_t i=0; i<AP_MISSION_MAX_NUM_DO_JUMP_COMMANDS; i++) {
1625  if (_jump_tracking[i].index == cmd.index) {
1626  return _jump_tracking[i].num_times_run;
1627  }else if(_jump_tracking[i].index == AP_MISSION_CMD_INDEX_NONE) {
1628  // we've searched through all known jump commands and haven't found it so allocate new space in _jump_tracking array
1629  _jump_tracking[i].index = cmd.index;
1631  return 0;
1632  }
1633  }
1634 
1635  // if we've gotten this far then the _jump_tracking array must be full
1636  // To-Do: log an error?
1638 }
1639 
1642 {
1643  // exit immediately if cmd is not a do-jump command
1644  if (cmd.id != MAV_CMD_DO_JUMP) {
1645  // To-Do: log an error?
1646  return;
1647  }
1648 
1649  // search through jump_tracking array for this cmd
1650  for (uint8_t i=0; i<AP_MISSION_MAX_NUM_DO_JUMP_COMMANDS; i++) {
1651  if (_jump_tracking[i].index == cmd.index) {
1653  return;
1654  }else if(_jump_tracking[i].index == AP_MISSION_CMD_INDEX_NONE) {
1655  // we've searched through all known jump commands and haven't found it so allocate new space in _jump_tracking array
1656  _jump_tracking[i].index = cmd.index;
1658  return;
1659  }
1660  }
1661 
1662  // if we've gotten this far then the _jump_tracking array must be full
1663  // To-Do: log an error
1664  return;
1665 }
1666 
1667 // check_eeprom_version - checks version of missions stored in eeprom matches this library
1668 // command list will be cleared if they do not match
1670 {
1671  uint32_t eeprom_version = _storage.read_uint32(0);
1672 
1673  // if eeprom version does not match, clear the command list and update the eeprom version
1674  if (eeprom_version != AP_MISSION_EEPROM_VERSION) {
1675  if (clear()) {
1677  }
1678  }
1679 }
1680 
1681 /*
1682  return total number of commands that can fit in storage space
1683  */
1684 uint16_t AP_Mission::num_commands_max(void) const
1685 {
1686  // -4 to remove space for eeprom version number
1687  return (_storage.size() - 4) / AP_MISSION_EEPROM_COMMAND_SIZE;
1688 }
1689 
1690 // find the nearest landing sequence starting point (DO_LAND_START) and
1691 // return its index. Returns 0 if no appropriate DO_LAND_START point can
1692 // be found.
1694 {
1695  struct Location current_loc;
1696 
1697  if (!_ahrs.get_position(current_loc)) {
1698  return 0;
1699  }
1700 
1701  uint16_t landing_start_index = 0;
1702  float min_distance = -1;
1703 
1704  // Go through mission looking for nearest landing start command
1705  for (uint16_t i = 0; i < num_commands(); i++) {
1706  Mission_Command tmp;
1707  if (!read_cmd_from_storage(i, tmp)) {
1708  continue;
1709  }
1710  if (tmp.id == MAV_CMD_DO_LAND_START) {
1711  float tmp_distance = get_distance(tmp.content.location, current_loc);
1712  if (min_distance < 0 || tmp_distance < min_distance) {
1713  min_distance = tmp_distance;
1714  landing_start_index = i;
1715  }
1716  }
1717  }
1718 
1719  return landing_start_index;
1720 }
1721 
1722 /*
1723  find the nearest landing sequence starting point (DO_LAND_START) and
1724  switch to that mission item. Returns false if no DO_LAND_START
1725  available.
1726  */
1728 {
1729  uint16_t land_idx = get_landing_sequence_start();
1730  if (land_idx != 0 && set_current_cmd(land_idx)) {
1731 
1732  //if the mission has ended it has to be restarted
1734  resume();
1735  }
1736 
1737  gcs().send_text(MAV_SEVERITY_INFO, "Landing sequence start");
1738  return true;
1739  }
1740 
1741  gcs().send_text(MAV_SEVERITY_WARNING, "Unable to start landing sequence");
1742  return false;
1743 }
1744 
1746  switch(id) {
1747  case MAV_CMD_NAV_WAYPOINT:
1748  return "WP";
1749  case MAV_CMD_NAV_RETURN_TO_LAUNCH:
1750  return "RTL";
1751  case MAV_CMD_NAV_LOITER_UNLIM:
1752  return "LoitUnlim";
1753  case MAV_CMD_NAV_LOITER_TIME:
1754  return "LoitTime";
1755  case MAV_CMD_NAV_SET_YAW_SPEED:
1756  return "SetYawSpd";
1757  case MAV_CMD_CONDITION_DELAY:
1758  return "CondDelay";
1759  case MAV_CMD_CONDITION_DISTANCE:
1760  return "CondDist";
1761  case MAV_CMD_DO_CHANGE_SPEED:
1762  return "ChangeSpeed";
1763  case MAV_CMD_DO_SET_HOME:
1764  return "SetHome";
1765  case MAV_CMD_DO_SET_SERVO:
1766  return "SetServo";
1767  case MAV_CMD_DO_SET_RELAY:
1768  return "SetRelay";
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:
1774  return "CtrlVideo";
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:
1782  return "SetROI";
1783  case MAV_CMD_DO_SET_REVERSE:
1784  return "SetReverse";
1785  default:
1786  return "?";
1787  }
1788 }
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
#define AP_MISSION_JUMP_TIMES_MAX
Definition: AP_Mission.h:34
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
Definition: AP_Mission.h:224
Repeat_Servo_Command repeat_servo
Definition: AP_Mission.h:221
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)
void write_uint16(uint16_t loc, uint16_t value) const
virtual bool get_position(struct Location &loc) const =0
struct Mission_Command _do_cmd
Definition: AP_Mission.h:541
Interface definition for the various Ground Control System.
Object managing Mission.
Definition: AP_Mission.h:45
void start()
Definition: AP_Mission.cpp:65
uint16_t read_uint16(uint16_t loc) const
const struct Location & get_home(void) const
Definition: AP_AHRS.h:435
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
#define AP_GROUPINFO(name, idx, clazz, element, def)
Definition: AP_Param.h:102
uint16_t num_commands() const
Definition: AP_Mission.h:330
#define AP_MISSION_OPTIONS_DEFAULT
Definition: AP_Mission.h:40
float get_distance(const struct Location &loc1, const struct Location &loc2)
Definition: location.cpp:36
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&#39;s or infinite
Definition: AP_Mission.cpp:533
#define HIGHBYTE(i)
Definition: AP_Common.h:72
Digicam_Control digicam_control
Definition: AP_Mission.h:230
bool check_lng(float lng)
Definition: location.cpp:219
Conditional_Delay_Command delay
Definition: AP_Mission.h:200
Repeat_Relay_Command repeat_relay
Definition: AP_Mission.h:215
GCS & gcs()
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
void reset()
reset - reset mission to the first command
Definition: AP_Mission.cpp:160
void check_eeprom_version()
void write_byte(uint16_t loc, uint8_t value) const
int32_t lat
param 3 - Latitude * 10**7
Definition: AP_Common.h:143
#define MIN(a, b)
Definition: usb_conf.h:215
int32_t get_bearing_cd(const struct Location &loc1, const struct Location &loc2)
Definition: location.cpp:56
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
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
const char * type() const
Set_Relay_Command relay
Definition: AP_Mission.h:212
int32_t alt
param 2 - Altitude in centimeters (meters * 100) see LOCATION_ALT_MAX_M
Definition: AP_Common.h:142
Gripper_Command gripper
Definition: AP_Mission.h:236
#define AP_MISSION_RESTART_DEFAULT
Definition: AP_Mission.h:38
#define f(i)
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()
uint32_t millis()
Definition: system.cpp:157
#define AP_MISSION_JUMP_REPEAT_FOREVER
Definition: AP_Mission.h:30
Handles the MAVLINK command mission stack. Reads and writes mission to storage.
#define AP_MISSION_EEPROM_COMMAND_SIZE
Definition: AP_Mission.h:26
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()
#define AP_MISSION_MASK_MISSION_CLEAR
Definition: AP_Mission.h:41
Altitude_Wait altitude_wait
Definition: AP_Mission.h:242
uint16_t _prev_nav_cmd_id
Definition: AP_Mission.h:542
void send_text(MAV_SEVERITY severity, const char *fmt,...)
Definition: GCS.cpp:8
struct Mission_Command _nav_cmd
Definition: AP_Mission.h:540
bool read_block(void *dst, uint16_t src, size_t n) const
void resume()
Definition: AP_Mission.cpp:86
Location_Option_Flags flags
options bitmask (1<<0 = relative altitude)
Definition: AP_Common.h:135
Set_Yaw_Speed set_yaw_speed
Definition: AP_Mission.h:254
uint32_t read_uint32(uint16_t loc) const
void update()
Definition: AP_Mission.cpp:206
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
#define LOWBYTE(i)
Definition: AP_Common.h:71
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
#define AP_MISSION_EEPROM_VERSION
Definition: AP_Mission.h:25
void write_uint32(uint16_t loc, uint32_t value) const
mission_complete_fn_t _mission_complete_fn
Definition: AP_Mission.h:537
bool check_lat(float lat)
Definition: location.cpp:215
AP_Int16 _options
Definition: AP_Mission.h:532
int32_t lng
param 4 - Longitude * 10**7
Definition: AP_Common.h:144
uint16_t _prev_nav_cmd_index
Definition: AP_Mission.h:543
uint8_t bytes[12]
Definition: AP_Mission.h:264
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
bool write_block(uint16_t dst, const void *src, size_t n) const
Set_Servo_Command servo
Definition: AP_Mission.h:218
bool get_next_do_cmd(uint16_t start_index, Mission_Command &cmd)
#define AP_MISSION_FIRST_REAL_COMMAND
Definition: AP_Mission.h:36
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
bool is_negative(const T fVal1)
Definition: AP_Math.h:61
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
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 ...
#define LOCATION_ALT_MAX_M
Definition: AP_Common.h:62
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
#define AP_GROUPEND
Definition: AP_Param.h:121
bool get_next_cmd(uint16_t start_index, Mission_Command &cmd, bool increment_jump_num_times_if_found)
uint8_t options
Definition: AP_Common.h:136
Winch_Command winch
Definition: AP_Mission.h:257
bool write_cmd_to_storage(uint16_t index, Mission_Command &cmd)
Definition: AP_Mission.cpp:494