APM:Libraries
AP_Mission_test.cpp
Go to the documentation of this file.
1 /*
2  * Example of AP_Mission Library.
3  * DIYDrones.com
4  */
5 
6 #include <AP_HAL/AP_HAL.h>
8 
10 
11 class MissionTest {
12 public:
13  void setup();
14  void loop();
15 
16 private:
22 
23  // global constants that control how many verify calls must be made for a command before it completes
26  uint8_t num_nav_cmd_runs = 0;
27  uint8_t num_do_cmd_runs = 0;
28 
29  bool start_cmd(const AP_Mission::Mission_Command& cmd);
30  bool verify_cmd(const AP_Mission::Mission_Command& cmd);
31  void mission_complete(void);
32  void run_mission_test();
33  void init_mission();
40  void print_mission();
41  void run_resume_test();
44  void run_replace_cmd_test();
45  void run_max_cmd_test();
46 
51 };
52 
54 
55 // start_cmd - function that is called when new command is started
56 // should return true if command is successfully started
58 {
59  // reset tracking of number of iterations of this command (we simulate all nav commands taking 3 iterations to complete, all do command 1 iteration)
60  if (AP_Mission::is_nav_cmd(cmd)) {
61  num_nav_cmd_runs = 0;
62  hal.console->printf("started cmd #%d id:%d Nav\n",(int)cmd.index,(int)cmd.id);
63  }else{
64  num_do_cmd_runs = 0;
65  hal.console->printf("started cmd #%d id:%d Do\n",(int)cmd.index,(int)cmd.id);
66  }
67 
68  return true;
69 }
70 
71 // verify_mcd - function that is called repeatedly to ensure a command is progressing
72 // should return true once command is completed
74 {
75  if (AP_Mission::is_nav_cmd(cmd)) {
78  hal.console->printf("verified cmd #%d id:%d Nav iteration:%d\n",(int)cmd.index,(int)cmd.id,(int)num_nav_cmd_runs);
79  return false;
80  }else{
81  hal.console->printf("verified cmd #%d id:%d Nav complete!\n",(int)cmd.index,(int)cmd.id);
82  return true;
83  }
84  }else{
87  hal.console->printf("verified cmd #%d id:%d Do iteration:%d\n",(int)cmd.index,(int)cmd.id,(int)num_do_cmd_runs);
88  return false;
89  }else{
90  hal.console->printf("verified cmd #%d id:%d Do complete!\n",(int)cmd.index,(int)cmd.id);
91  return true;
92  }
93  }
94 }
95 
96 // mission_complete - function that is called once the mission completes
98 {
99  hal.console->printf("\nMission Complete!\n");
100 }
101 
102 // run_mission_test - tests the stop and resume feature
104 {
105  // uncomment one of the init_xxx() commands below to run the test
106 
107  init_mission(); // run simple mission with many nav commands and one do-jump
108  //init_mission_no_nav_commands(); // mission should start the first do command but then complete
109  //init_mission_endless_loop(); // mission should ignore the jump that causes the endless loop and complete
110 
111  // mission with a do-jump to the previous command which is a "do" command
112  // ideally we would execute this previous "do" command the number of times specified in the do-jump command but this is tricky so we ignore the do-jump
113  // mission should run the "do" command once and then complete
114  //init_mission_jump_to_nonnav();
115 
116  // mission which starts with do comamnds
117  // first command to execute should be the first do command followed by the first nav command
118  // second do command should execute after 1st do command completes
119  // third do command (which is after 1st nav command) should start after 1st nav command completes
120  //init_mission_starts_with_do_commands();
121 
122  // init_mission_ends_with_do_commands - initialise a mission which ends with do comamnds
123  // a single do command just after nav command will be started but not verified because mission will complete
124  // final do command will not be started
125  //init_mission_ends_with_do_commands();
126 
127  // init_mission_ends_with_jump_command - initialise a mission which ends with a jump comamnd
128  // mission should complete after the do-jump is executed the appropriate number of times
129  //init_mission_ends_with_jump_command();
130 
131  // run_resume_test - tests the stop and resume feature
132  // when mission is resumed, active commands should be started again
133  //run_resume_test();
134 
135  // run_set_current_cmd_test - tests setting the current command while the mission is running
136  //run_set_current_cmd_test();
137 
138  // run_set_current_cmd_while_stopped_test - tests setting the current command while the mission is stopped
139  // when mission is resumed, the mission should start from the modified current cmd
140  //run_set_current_cmd_while_stopped_test();
141 
142  // run_replace_cmd_test - tests replacing a command during a mission
143  //run_replace_cmd_test();
144 
145  // run_max_cmd_test - tests filling the eeprom with commands and then reading them back
146  //run_max_cmd_test();
147 
148  // print current mission
149  print_mission();
150 
151  // start mission
152  hal.console->printf("\nRunning missions\n");
153  mission.start();
154 
155  // update mission forever
156  while(true) {
157  mission.update();
158  }
159 }
160 
161 // init_mission - initialise the mission to hold something
163 {
165 
166  // clear mission
167  mission.clear();
168 
169  // Command #0 : home
170  cmd.id = MAV_CMD_NAV_WAYPOINT;
171  cmd.content.location.options = 0;
172  cmd.p1 = 0;
173  cmd.content.location.alt = 0;
174  cmd.content.location.lat = 12345678;
175  cmd.content.location.lng = 23456789;
176  if (!mission.add_cmd(cmd)) {
177  hal.console->printf("failed to add command\n");
178  }
179 
180  // Command #1 : take-off to 10m
181  cmd.id = MAV_CMD_NAV_TAKEOFF;
182  cmd.content.location.options = 0;
183  cmd.p1 = 0;
184  cmd.content.location.alt = 10;
185  cmd.content.location.lat = 0;
186  cmd.content.location.lng = 0;
187  if (!mission.add_cmd(cmd)) {
188  hal.console->printf("failed to add command\n");
189  }
190 
191  // Command #2 : first waypoint
192  cmd.id = MAV_CMD_NAV_WAYPOINT;
193  cmd.content.location.options = 0;
194  cmd.p1 = 0;
195  cmd.content.location.alt = 11;
196  cmd.content.location.lat = 12345678;
197  cmd.content.location.lng = 23456789;
198  if (!mission.add_cmd(cmd)) {
199  hal.console->printf("failed to add command\n");
200  }
201 
202  // Command #3 : second waypoint
203  cmd.id = MAV_CMD_NAV_WAYPOINT;
204  cmd.p1 = 0;
205  cmd.content.location.lat = 1234567890;
206  cmd.content.location.lng = -1234567890;
207  cmd.content.location.alt = 22;
208  if (!mission.add_cmd(cmd)) {
209  hal.console->printf("failed to add command\n");
210  }
211 
212  // Command #4 : do-jump to first waypoint 3 times
213  cmd.id = MAV_CMD_DO_JUMP;
214  cmd.content.jump.target = 2;
215  cmd.content.jump.num_times = 1;
216  if (!mission.add_cmd(cmd)) {
217  hal.console->printf("failed to add command\n");
218  }
219 
220  // Command #5 : RTL
221  cmd.id = MAV_CMD_NAV_RETURN_TO_LAUNCH;
222  cmd.p1 = 0;
223  cmd.content.location.lat = 0;
224  cmd.content.location.lng = 0;
225  cmd.content.location.alt = 0;
226  if (!mission.add_cmd(cmd)) {
227  hal.console->printf("failed to add command\n");
228  }
229 }
230 
231 // init_mission_no_nav_commands - initialise a mission with no navigation commands
232 // mission should ignore the jump that causes the endless loop and complete
234 {
236 
237  // clear mission
238  mission.clear();
239 
240  // Command #0 : home
241  cmd.id = MAV_CMD_NAV_WAYPOINT;
242  cmd.content.location.options = 0;
243  cmd.p1 = 0;
244  cmd.content.location.alt = 0;
245  cmd.content.location.lat = 12345678;
246  cmd.content.location.lng = 23456789;
247  if (!mission.add_cmd(cmd)) {
248  hal.console->printf("failed to add command\n");
249  }
250 
251  // Command #1 : "do" command
252  cmd.id = MAV_CMD_DO_SET_ROI;
253  cmd.content.location.options = 0;
254  cmd.p1 = 0;
255  cmd.content.location.alt = 11;
256  cmd.content.location.lat = 12345678;
257  cmd.content.location.lng = 23456789;
258  if (!mission.add_cmd(cmd)) {
259  hal.console->printf("failed to add command\n");
260  }
261 
262  // Command #2 : "do" command
263  cmd.id = MAV_CMD_DO_CHANGE_SPEED;
264  cmd.content.location.options = 0;
265  cmd.p1 = 0;
266  cmd.content.location.alt = 0;
267  cmd.content.location.lat = 0;
268  cmd.content.location.lng = 0;
269  if (!mission.add_cmd(cmd)) {
270  hal.console->printf("failed to add command\n");
271  }
272 
273  // Command #3 : "do" command
274  cmd.id = MAV_CMD_DO_SET_SERVO;
275  if (!mission.add_cmd(cmd)) {
276  hal.console->printf("failed to add command\n");
277  }
278 
279  // Command #4 : do-jump to first command 3 times
280  cmd.id = MAV_CMD_DO_JUMP;
281  cmd.content.jump.target = 1;
282  cmd.content.jump.num_times = 1;
283  if (!mission.add_cmd(cmd)) {
284  hal.console->printf("failed to add command\n");
285  }
286 }
287 
288 // init_mission_endless_loop - initialise a mission with a do-jump that causes an endless loop
289 // mission should start the first do command but then complete
291 {
293 
294  // clear mission
295  mission.clear();
296 
297  // Command #0 : home
298  cmd.id = MAV_CMD_NAV_WAYPOINT;
299  cmd.content.location.options = 0;
300  cmd.p1 = 0;
301  cmd.content.location.alt = 0;
302  cmd.content.location.lat = 12345678;
303  cmd.content.location.lng = 23456789;
304  if (!mission.add_cmd(cmd)) {
305  hal.console->printf("failed to add command\n");
306  }
307 
308  // Command #1 : do-jump command to itself
309  cmd.id = MAV_CMD_DO_JUMP;
310  cmd.content.jump.target = 1;
311  cmd.content.jump.num_times = 2;
312  if (!mission.add_cmd(cmd)) {
313  hal.console->printf("failed to add command\n");
314  }
315 
316  // Command #2 : take-off to 10m
317  cmd.id = MAV_CMD_NAV_TAKEOFF;
318  cmd.content.location.options = 0;
319  cmd.p1 = 0;
320  cmd.content.location.alt = 10;
321  cmd.content.location.lat = 0;
322  cmd.content.location.lng = 0;
323  if (!mission.add_cmd(cmd)) {
324  hal.console->printf("failed to add command\n");
325  }
326 
327  // Command #3 : waypoint
328  cmd.id = MAV_CMD_NAV_WAYPOINT;
329  cmd.content.location.options = 0;
330  cmd.p1 = 0;
331  cmd.content.location.alt = 11;
332  cmd.content.location.lat = 12345678;
333  cmd.content.location.lng = 23456789;
334  if (!mission.add_cmd(cmd)) {
335  hal.console->printf("failed to add command\n");
336  }
337 }
338 
339 // init_mission_jump_to_nonnav - initialise a mission with a do-jump to the previous command which is a "do" command
340 // ideally we would execute this previous "do" command the number of times specified in the do-jump command but this is tricky so we ignore the do-jump
341 // mission should run the "do" command once and then complete
343 {
345 
346  // clear mission
347  mission.clear();
348 
349  // Command #0 : home
350  cmd.id = MAV_CMD_NAV_WAYPOINT;
351  cmd.content.location.options = 0;
352  cmd.p1 = 0;
353  cmd.content.location.alt = 0;
354  cmd.content.location.lat = 12345678;
355  cmd.content.location.lng = 23456789;
356  if (!mission.add_cmd(cmd)) {
357  hal.console->printf("failed to add command\n");
358  }
359 
360  // Command #1 : take-off to 10m
361  cmd.id = MAV_CMD_NAV_TAKEOFF;
362  cmd.content.location.options = 0;
363  cmd.p1 = 0;
364  cmd.content.location.alt = 10;
365  cmd.content.location.lat = 0;
366  cmd.content.location.lng = 0;
367  if (!mission.add_cmd(cmd)) {
368  hal.console->printf("failed to add command\n");
369  }
370 
371  // Command #2 : do-roi command
372  cmd.id = MAV_CMD_DO_SET_ROI;
373  cmd.content.location.options = 0;
374  cmd.p1 = 0;
375  cmd.content.location.alt = 11;
376  cmd.content.location.lat = 12345678;
377  cmd.content.location.lng = 23456789;
378  if (!mission.add_cmd(cmd)) {
379  hal.console->printf("failed to add command\n");
380  }
381 
382  // Command #3 : do-jump command to #2
383  cmd.id = MAV_CMD_DO_JUMP;
384  cmd.content.jump.target = 2;
385  cmd.content.jump.num_times = 2;
386  if (!mission.add_cmd(cmd)) {
387  hal.console->printf("failed to add command\n");
388  }
389 
390  // Command #4 : waypoint
391  cmd.id = MAV_CMD_NAV_WAYPOINT;
392  cmd.content.location.options = 0;
393  cmd.p1 = 0;
394  cmd.content.location.alt = 22;
395  cmd.content.location.lat = 12345678;
396  cmd.content.location.lng = 23456789;
397  if (!mission.add_cmd(cmd)) {
398  hal.console->printf("failed to add command\n");
399  }
400 }
401 
402 // init_mission_starts_with_do_commands - initialise a mission which starts with do comamnds
403 // first command to execute should be the first do command followed by the first nav command
404 // second do command should execute after 1st do command completes
405 // third do command (which is after 1st nav command) should start after 1st nav command completes
407 {
409 
410  // clear mission
411  mission.clear();
412 
413  // Command #0 : home
414  cmd.id = MAV_CMD_NAV_WAYPOINT;
415  cmd.content.location.options = 0;
416  cmd.p1 = 0;
417  cmd.content.location.alt = 0;
418  cmd.content.location.lat = 12345678;
419  cmd.content.location.lng = 23456789;
420  if (!mission.add_cmd(cmd)) {
421  hal.console->printf("failed to add command\n");
422  }
423 
424  // Command #1 : First "do" command
425  cmd.id = MAV_CMD_DO_SET_ROI;
426  cmd.content.location.options = 0;
427  cmd.p1 = 0;
428  cmd.content.location.alt = 11;
429  cmd.content.location.lat = 12345678;
430  cmd.content.location.lng = 23456789;
431  if (!mission.add_cmd(cmd)) {
432  hal.console->printf("failed to add command\n");
433  }
434 
435  // Command #2 : Second "do" command
436  cmd.id = MAV_CMD_DO_CHANGE_SPEED;
437  cmd.content.location.options = 0;
438  cmd.p1 = 0;
439  cmd.content.location.alt = 0;
440  cmd.content.location.lat = 0;
441  cmd.content.location.lng = 0;
442  if (!mission.add_cmd(cmd)) {
443  hal.console->printf("failed to add command\n");
444  }
445 
446  // Command #3 : take-off to 10m
447  cmd.id = MAV_CMD_NAV_TAKEOFF;
448  cmd.content.location.options = 0;
449  cmd.p1 = 0;
450  cmd.content.location.alt = 10;
451  cmd.content.location.lat = 0;
452  cmd.content.location.lng = 0;
453  if (!mission.add_cmd(cmd)) {
454  hal.console->printf("failed to add command\n");
455  }
456 
457  // Command #4 : Third "do" command
458  cmd.id = MAV_CMD_DO_SET_ROI;
459  cmd.content.location.options = 0;
460  cmd.p1 = 0;
461  cmd.content.location.alt = 22;
462  cmd.content.location.lat = 12345678;
463  cmd.content.location.lng = 23456789;
464  if (!mission.add_cmd(cmd)) {
465  hal.console->printf("failed to add command\n");
466  }
467 
468  // Command #5 : waypoint
469  cmd.id = MAV_CMD_NAV_WAYPOINT;
470  cmd.content.location.options = 0;
471  cmd.p1 = 0;
472  cmd.content.location.alt = 33;
473  cmd.content.location.lat = 12345678;
474  cmd.content.location.lng = 23456789;
475  if (!mission.add_cmd(cmd)) {
476  hal.console->printf("failed to add command\n");
477  }
478 }
479 
480 // init_mission_ends_with_do_commands - initialise a mission which ends with do comamnds
481 // a single do command just after nav command will be started but not verified because mission will complete
482 // final do command will not be started
484 {
486 
487  // clear mission
488  mission.clear();
489 
490  // Command #0 : home
491  cmd.id = MAV_CMD_NAV_WAYPOINT;
492  cmd.content.location.options = 0;
493  cmd.p1 = 0;
494  cmd.content.location.alt = 0;
495  cmd.content.location.lat = 12345678;
496  cmd.content.location.lng = 23456789;
497  if (!mission.add_cmd(cmd)) {
498  hal.console->printf("failed to add command\n");
499  }
500 
501  // Command #1 : take-off to 10m
502  cmd.id = MAV_CMD_NAV_TAKEOFF;
503  cmd.content.location.options = 0;
504  cmd.p1 = 0;
505  cmd.content.location.alt = 10;
506  cmd.content.location.lat = 0;
507  cmd.content.location.lng = 0;
508  if (!mission.add_cmd(cmd)) {
509  hal.console->printf("failed to add command\n");
510  }
511 
512  // Command #2 : "do" command
513  cmd.id = MAV_CMD_DO_SET_ROI;
514  cmd.content.location.options = 0;
515  cmd.p1 = 0;
516  cmd.content.location.alt = 22;
517  cmd.content.location.lat = 12345678;
518  cmd.content.location.lng = 23456789;
519  if (!mission.add_cmd(cmd)) {
520  hal.console->printf("failed to add command\n");
521  }
522 
523  // Command #3 : waypoint
524  cmd.id = MAV_CMD_NAV_WAYPOINT;
525  cmd.content.location.options = 0;
526  cmd.p1 = 0;
527  cmd.content.location.alt = 33;
528  cmd.content.location.lat = 12345678;
529  cmd.content.location.lng = 23456789;
530  if (!mission.add_cmd(cmd)) {
531  hal.console->printf("failed to add command\n");
532  }
533 
534  // Command #4 : "do" command after last nav command (but not at end of mission)
535  cmd.id = MAV_CMD_DO_CHANGE_SPEED;
536  cmd.content.location.options = 0;
537  cmd.p1 = 0;
538  cmd.content.location.alt = 0;
539  cmd.content.location.lat = 0;
540  cmd.content.location.lng = 0;
541  if (!mission.add_cmd(cmd)) {
542  hal.console->printf("failed to add command\n");
543  }
544 
545  // Command #5 : "do" command at end of mission
546  cmd.id = MAV_CMD_DO_SET_ROI;
547  cmd.content.location.options = 0;
548  cmd.p1 = 0;
549  cmd.content.location.alt = 22;
550  cmd.content.location.lat = 12345678;
551  cmd.content.location.lng = 23456789;
552  if (!mission.add_cmd(cmd)) {
553  hal.console->printf("failed to add command\n");
554  }
555 }
556 
557 // init_mission_ends_with_jump_command - initialise a mission which ends with a jump comamnd
558 // mission should complete after the do-jump is executed the appropriate number of times
560 {
562 
563  // clear mission
564  mission.clear();
565 
566  // Command #0 : home
567  cmd.id = MAV_CMD_NAV_WAYPOINT;
568  cmd.content.location.options = 0;
569  cmd.p1 = 0;
570  cmd.content.location.alt = 0;
571  cmd.content.location.lat = 12345678;
572  cmd.content.location.lng = 23456789;
573  if (!mission.add_cmd(cmd)) {
574  hal.console->printf("failed to add command\n");
575  }
576 
577  // Command #1 : take-off to 10m
578  cmd.id = MAV_CMD_NAV_TAKEOFF;
579  cmd.content.location.options = 0;
580  cmd.p1 = 0;
581  cmd.content.location.alt = 10;
582  cmd.content.location.lat = 0;
583  cmd.content.location.lng = 0;
584  if (!mission.add_cmd(cmd)) {
585  hal.console->printf("failed to add command\n");
586  }
587 
588  // Command #2 : "do" command
589  cmd.id = MAV_CMD_DO_SET_ROI;
590  cmd.content.location.options = 0;
591  cmd.p1 = 0;
592  cmd.content.location.alt = 22;
593  cmd.content.location.lat = 12345678;
594  cmd.content.location.lng = 23456789;
595  if (!mission.add_cmd(cmd)) {
596  hal.console->printf("failed to add command\n");
597  }
598 
599  // Command #3 : waypoint
600  cmd.id = MAV_CMD_NAV_WAYPOINT;
601  cmd.content.location.options = 0;
602  cmd.p1 = 0;
603  cmd.content.location.alt = 33;
604  cmd.content.location.lat = 12345678;
605  cmd.content.location.lng = 23456789;
606  if (!mission.add_cmd(cmd)) {
607  hal.console->printf("failed to add command\n");
608  }
609 
610  // Command #4 : "do" command after last nav command (but not at end of mission)
611  cmd.id = MAV_CMD_DO_CHANGE_SPEED;
612  cmd.content.location.options = 0;
613  cmd.p1 = 0;
614  cmd.content.location.alt = 0;
615  cmd.content.location.lat = 0;
616  cmd.content.location.lng = 0;
617  if (!mission.add_cmd(cmd)) {
618  hal.console->printf("failed to add command\n");
619  }
620 
621  // Command #5 : "do" command at end of mission
622  cmd.id = MAV_CMD_DO_SET_ROI;
623  cmd.content.location.options = 0;
624  cmd.p1 = 0;
625  cmd.content.location.alt = 22;
626  cmd.content.location.lat = 12345678;
627  cmd.content.location.lng = 23456789;
628  if (!mission.add_cmd(cmd)) {
629  hal.console->printf("failed to add command\n");
630  }
631 
632  // Command #6 : do-jump command to #2 two times
633  cmd.id = MAV_CMD_DO_JUMP;
634  cmd.content.jump.target = 3;
635  cmd.content.jump.num_times = 2;
636  if (!mission.add_cmd(cmd)) {
637  hal.console->printf("failed to add command\n");
638  }
639 }
640 
641 // print_mission - print out the entire mission to the console
643 {
645 
646  // check for empty mission
647  if (mission.num_commands() == 0) {
648  hal.console->printf("No Mission!\n");
649  return;
650  }
651 
652  hal.console->printf("Mission: %d commands\n",(int)mission.num_commands());
653 
654  // print each command
655  for(uint16_t i=0; i<mission.num_commands(); i++) {
656  // get next command from eeprom
658 
659  // print command position in list and mavlink id
660  hal.console->printf("Cmd#%d mav-id:%d ", (int)cmd.index, (int)cmd.id);
661 
662  // print whether nav or do command
663  if (AP_Mission::is_nav_cmd(cmd)) {
664  hal.console->printf("Nav ");
665  }else{
666  hal.console->printf("Do ");
667  }
668 
669  // print command contents
670  if (cmd.id == MAV_CMD_DO_JUMP) {
671  hal.console->printf("jump-to:%d num_times:%d\n", (int)cmd.content.jump.target, (int)cmd.content.jump.num_times);
672  }else{
673  hal.console->printf("p1:%d lat:%ld lng:%ld alt:%ld\n",(int)cmd.p1, (long)cmd.content.location.lat, (long)cmd.content.location.lng, (long)cmd.content.location.alt);
674  }
675  }
676  hal.console->printf("--------\n");
677 }
678 
679 // run_resume_test - tests the stop and resume feature
680 // when mission is resumed, active commands should be started again
682 {
684 
685  // create a mission
686 
687  // Command #0 : home
688  cmd.id = MAV_CMD_NAV_WAYPOINT;
689  cmd.content.location.options = 0;
690  cmd.p1 = 0;
691  cmd.content.location.alt = 0;
692  cmd.content.location.lat = 12345678;
693  cmd.content.location.lng = 23456789;
694  if (!mission.add_cmd(cmd)) {
695  hal.console->printf("failed to add command\n");
696  }
697 
698  // Command #1 : take-off to 10m
699  cmd.id = MAV_CMD_NAV_TAKEOFF;
700  cmd.content.location.options = 0;
701  cmd.p1 = 0;
702  cmd.content.location.alt = 10;
703  cmd.content.location.lat = 0;
704  cmd.content.location.lng = 0;
705  if (!mission.add_cmd(cmd)) {
706  hal.console->printf("failed to add command\n");
707  }
708 
709  // Command #2 : first waypoint
710  cmd.id = MAV_CMD_NAV_WAYPOINT;
711  cmd.content.location.options = 0;
712  cmd.p1 = 0;
713  cmd.content.location.alt = 11;
714  cmd.content.location.lat = 12345678;
715  cmd.content.location.lng = 23456789;
716  if (!mission.add_cmd(cmd)) {
717  hal.console->printf("failed to add command\n");
718  }
719 
720  // Command #3 : second waypoint
721  cmd.id = MAV_CMD_NAV_WAYPOINT;
722  cmd.p1 = 0;
723  cmd.content.location.lat = 1234567890;
724  cmd.content.location.lng = -1234567890;
725  cmd.content.location.alt = 22;
726  if (!mission.add_cmd(cmd)) {
727  hal.console->printf("failed to add command\n");
728  }
729 
730  // Command #4 : do command
731  cmd.id = MAV_CMD_DO_SET_ROI;
732  cmd.content.location.options = 0;
733  cmd.p1 = 0;
734  cmd.content.location.alt = 11;
735  cmd.content.location.lat = 12345678;
736  cmd.content.location.lng = 23456789;
737  if (!mission.add_cmd(cmd)) {
738  hal.console->printf("failed to add command\n");
739  }
740 
741  // Command #5 : RTL
742  cmd.id = MAV_CMD_NAV_RETURN_TO_LAUNCH;
743  cmd.p1 = 0;
744  cmd.content.location.lat = 0;
745  cmd.content.location.lng = 0;
746  cmd.content.location.alt = 0;
747  if (!mission.add_cmd(cmd)) {
748  hal.console->printf("failed to add command\n");
749  }
750 
751  // print current mission
752  print_mission();
753 
754  // start mission
755  hal.console->printf("\nRunning missions\n");
756  mission.start();
757 
758  // update the mission for X iterations
759  // set condition to "i<5" to catch mission as cmd #1 (Nav) is running - you should see it restart cmd #1
760  // set condition to "i<7" to catch mission just after cmd #1 (Nav) has completed - you should see it start cmd #2
761  // set condition to "i<11" to catch mission just after cmd #2 (Nav) has completed - you should see it start cmd #3 (Do) and cmd #4 (Nav)
762  for(uint8_t i=0; i<11; i++) {
763  mission.update();
764  }
765 
766  // simulate user pausing the mission
767  hal.console->printf("Stopping mission\n");
768  mission.stop();
769 
770  // update the mission for 5 seconds (nothing should happen)
771  uint32_t start_time = AP_HAL::millis();
772  while(AP_HAL::millis() - start_time < 5000) {
773  mission.update();
774  }
775 
776  // simulate user resuming mission
777  hal.console->printf("Resume mission\n");
778  mission.resume();
779 
780  // update the mission forever
781  while(true) {
782  mission.update();
783  }
784 }
785 
786 // run_set_current_cmd_test - tests setting the current command during a mission
788 {
790 
791  // create a mission
792 
793  // Command #0 : home
794  cmd.id = MAV_CMD_NAV_WAYPOINT;
795  cmd.content.location.options = 0;
796  cmd.p1 = 0;
797  cmd.content.location.alt = 0;
798  cmd.content.location.lat = 12345678;
799  cmd.content.location.lng = 23456789;
800  if (!mission.add_cmd(cmd)) {
801  hal.console->printf("failed to add command\n");
802  }
803 
804  // Command #1 : take-off to 10m
805  cmd.id = MAV_CMD_NAV_TAKEOFF;
806  cmd.content.location.options = 0;
807  cmd.p1 = 0;
808  cmd.content.location.alt = 10;
809  cmd.content.location.lat = 0;
810  cmd.content.location.lng = 0;
811  if (!mission.add_cmd(cmd)) {
812  hal.console->printf("failed to add command\n");
813  }
814 
815  // Command #2 : do command
816  cmd.id = MAV_CMD_DO_SET_ROI;
817  cmd.content.location.options = 0;
818  cmd.p1 = 0;
819  cmd.content.location.alt = 11;
820  cmd.content.location.lat = 12345678;
821  cmd.content.location.lng = 23456789;
822  if (!mission.add_cmd(cmd)) {
823  hal.console->printf("failed to add command\n");
824  }
825 
826  // Command #3 : first waypoint
827  cmd.id = MAV_CMD_NAV_WAYPOINT;
828  cmd.content.location.options = 0;
829  cmd.p1 = 0;
830  cmd.content.location.alt = 11;
831  cmd.content.location.lat = 12345678;
832  cmd.content.location.lng = 23456789;
833  if (!mission.add_cmd(cmd)) {
834  hal.console->printf("failed to add command\n");
835  }
836 
837  // Command #4 : second waypoint
838  cmd.id = MAV_CMD_NAV_WAYPOINT;
839  cmd.p1 = 0;
840  cmd.content.location.lat = 1234567890;
841  cmd.content.location.lng = -1234567890;
842  cmd.content.location.alt = 22;
843  if (!mission.add_cmd(cmd)) {
844  hal.console->printf("failed to add command\n");
845  }
846 
847  // Command #5 : do command
848  cmd.id = MAV_CMD_DO_SET_ROI;
849  cmd.content.location.options = 0;
850  cmd.p1 = 0;
851  cmd.content.location.alt = 11;
852  cmd.content.location.lat = 12345678;
853  cmd.content.location.lng = 23456789;
854  if (!mission.add_cmd(cmd)) {
855  hal.console->printf("failed to add command\n");
856  }
857 
858  // Command #6 : RTL
859  cmd.id = MAV_CMD_NAV_RETURN_TO_LAUNCH;
860  cmd.p1 = 0;
861  cmd.content.location.lat = 0;
862  cmd.content.location.lng = 0;
863  cmd.content.location.alt = 0;
864  if (!mission.add_cmd(cmd)) {
865  hal.console->printf("failed to add command\n");
866  }
867 
868  // print current mission
869  print_mission();
870 
871  // start mission
872  hal.console->printf("\nRunning missions\n");
873  mission.start();
874 
875  // update the mission for X iterations to let it go to about command 3 or 4
876  for(uint8_t i=0; i<11; i++) {
877  mission.update();
878  }
879 
880  // simulate user setting current command to 2
881  hal.console->printf("Setting current command to 2\n");
883 
884  // update the mission forever
885  while(true) {
886  mission.update();
887  }
888 }
889 
890 // run_set_current_cmd_while_stopped_test - tests setting the current command while the mission is stopped
891 // when mission is resumed, the mission should start from the modified current cmd
893 {
895 
896  // create a mission
897 
898  // Command #0 : home
899  cmd.id = MAV_CMD_NAV_WAYPOINT;
900  cmd.content.location.options = 0;
901  cmd.p1 = 0;
902  cmd.content.location.alt = 0;
903  cmd.content.location.lat = 12345678;
904  cmd.content.location.lng = 23456789;
905  if (!mission.add_cmd(cmd)) {
906  hal.console->printf("failed to add command\n");
907  }
908 
909  // Command #1 : take-off to 10m
910  cmd.id = MAV_CMD_NAV_TAKEOFF;
911  cmd.content.location.options = 0;
912  cmd.p1 = 0;
913  cmd.content.location.alt = 10;
914  cmd.content.location.lat = 0;
915  cmd.content.location.lng = 0;
916  if (!mission.add_cmd(cmd)) {
917  hal.console->printf("failed to add command\n");
918  }
919 
920  // Command #2 : do command
921  cmd.id = MAV_CMD_DO_SET_ROI;
922  cmd.content.location.options = 0;
923  cmd.p1 = 0;
924  cmd.content.location.alt = 22;
925  cmd.content.location.lat = 12345678;
926  cmd.content.location.lng = 23456789;
927  if (!mission.add_cmd(cmd)) {
928  hal.console->printf("failed to add command\n");
929  }
930 
931  // Command #3 : first waypoint
932  cmd.id = MAV_CMD_NAV_WAYPOINT;
933  cmd.content.location.options = 0;
934  cmd.p1 = 0;
935  cmd.content.location.alt = 11;
936  cmd.content.location.lat = 12345678;
937  cmd.content.location.lng = 23456789;
938  if (!mission.add_cmd(cmd)) {
939  hal.console->printf("failed to add command\n");
940  }
941 
942  // Command #4 : second waypoint
943  cmd.id = MAV_CMD_NAV_WAYPOINT;
944  cmd.p1 = 0;
945  cmd.content.location.lat = 1234567890;
946  cmd.content.location.lng = -1234567890;
947  cmd.content.location.alt = 22;
948  if (!mission.add_cmd(cmd)) {
949  hal.console->printf("failed to add command\n");
950  }
951 
952  // Command #5 : do command
953  cmd.id = MAV_CMD_DO_SET_ROI;
954  cmd.content.location.options = 0;
955  cmd.p1 = 0;
956  cmd.content.location.alt = 11;
957  cmd.content.location.lat = 12345678;
958  cmd.content.location.lng = 23456789;
959  if (!mission.add_cmd(cmd)) {
960  hal.console->printf("failed to add command\n");
961  }
962 
963  // Command #6 : RTL
964  cmd.id = MAV_CMD_NAV_RETURN_TO_LAUNCH;
965  cmd.p1 = 0;
966  cmd.content.location.lat = 0;
967  cmd.content.location.lng = 0;
968  cmd.content.location.alt = 0;
969  if (!mission.add_cmd(cmd)) {
970  hal.console->printf("failed to add command\n");
971  }
972 
973  // print current mission
974  print_mission();
975 
976  // start mission
977  hal.console->printf("\nRunning missions\n");
978  mission.start();
979 
980  // update the mission for X iterations
981  for(uint8_t i=0; i<11; i++) {
982  mission.update();
983  }
984 
985  // simulate user pausing the mission
986  hal.console->printf("Stopping mission\n");
987  mission.stop();
988 
989  // simulate user setting current command to 2
990  hal.console->printf("Setting current command to 2\n");
992 
993  // update the mission for 2 seconds (nothing should happen)
994  uint32_t start_time = AP_HAL::millis();
995  while(AP_HAL::millis() - start_time < 2000) {
996  mission.update();
997  }
998 
999  // simulate user resuming mission
1000  hal.console->printf("Resume mission\n");
1001  mission.resume();
1002 
1003  // wait for the mission to complete
1005  mission.update();
1006  }
1007 
1008  // pause for two seconds
1009  start_time = AP_HAL::millis();
1010  while(AP_HAL::millis() - start_time < 2000) {
1011  mission.update();
1012  }
1013 
1014  // simulate user setting current command to 2 now that the mission has completed
1015  hal.console->printf("Setting current command to 5\n");
1017 
1018  // simulate user resuming mission
1019  hal.console->printf("Resume mission\n");
1020  mission.resume();
1021 
1022  // keep running the mission forever
1023  while(true) {
1024  mission.update();
1025  }
1026 }
1027 
1028 // run_replace_cmd_test - tests replacing a command during a mission
1030 {
1032 
1033  // create a mission
1034 
1035  // Command #0 : home
1036  cmd.id = MAV_CMD_NAV_WAYPOINT;
1037  cmd.content.location.options = 0;
1038  cmd.p1 = 0;
1039  cmd.content.location.alt = 0;
1040  cmd.content.location.lat = 12345678;
1041  cmd.content.location.lng = 23456789;
1042  if (!mission.add_cmd(cmd)) {
1043  hal.console->printf("failed to add command\n");
1044  }
1045 
1046  // Command #1 : take-off to 10m
1047  cmd.id = MAV_CMD_NAV_TAKEOFF;
1048  cmd.content.location.options = 0;
1049  cmd.p1 = 0;
1050  cmd.content.location.alt = 10;
1051  cmd.content.location.lat = 0;
1052  cmd.content.location.lng = 0;
1053  if (!mission.add_cmd(cmd)) {
1054  hal.console->printf("failed to add command\n");
1055  }
1056 
1057  // Command #2 : do command
1058  cmd.id = MAV_CMD_DO_SET_ROI;
1059  cmd.content.location.options = 0;
1060  cmd.p1 = 0;
1061  cmd.content.location.alt = 11;
1062  cmd.content.location.lat = 12345678;
1063  cmd.content.location.lng = 23456789;
1064  if (!mission.add_cmd(cmd)) {
1065  hal.console->printf("failed to add command\n");
1066  }
1067 
1068  // Command #3 : first waypoint
1069  cmd.id = MAV_CMD_NAV_WAYPOINT;
1070  cmd.content.location.options = 0;
1071  cmd.p1 = 0;
1072  cmd.content.location.alt = 11;
1073  cmd.content.location.lat = 12345678;
1074  cmd.content.location.lng = 23456789;
1075  if (!mission.add_cmd(cmd)) {
1076  hal.console->printf("failed to add command\n");
1077  }
1078 
1079  // Command #4 : second waypoint
1080  cmd.id = MAV_CMD_NAV_WAYPOINT;
1081  cmd.p1 = 0;
1082  cmd.content.location.lat = 1234567890;
1083  cmd.content.location.lng = -1234567890;
1084  cmd.content.location.alt = 22;
1085  if (!mission.add_cmd(cmd)) {
1086  hal.console->printf("failed to add command\n");
1087  }
1088 
1089  // Command #6 : RTL
1090  cmd.id = MAV_CMD_NAV_RETURN_TO_LAUNCH;
1091  cmd.p1 = 0;
1092  cmd.content.location.lat = 0;
1093  cmd.content.location.lng = 0;
1094  cmd.content.location.alt = 0;
1095  if (!mission.add_cmd(cmd)) {
1096  hal.console->printf("failed to add command\n");
1097  }
1098 
1099  // print current mission
1100  print_mission();
1101 
1102  // start mission
1103  hal.console->printf("\nRunning missions\n");
1104  mission.start();
1105 
1106  // update the mission for X iterations to let it go to about command 3 or 4
1107  for(uint8_t i=0; i<9; i++) {
1108  mission.update();
1109  }
1110 
1111  // replace command #4 with a do-command
1112  // Command #4 : do command
1113  cmd.id = MAV_CMD_DO_SET_ROI;
1114  cmd.content.location.options = 0;
1115  cmd.p1 = 0;
1116  cmd.content.location.alt = 11;
1117  cmd.content.location.lat = 12345678;
1118  cmd.content.location.lng = 23456789;
1119  if (!mission.replace_cmd(4, cmd)) {
1120  hal.console->printf("failed to replace command 4\n");
1121  }else{
1122  hal.console->printf("replaced command #4 -------------\n");
1123  // print current mission
1124  print_mission();
1125  }
1126 
1127  // update the mission forever
1128  while(true) {
1129  mission.update();
1130  }
1131 }
1132 
1133 // run_max_cmd_test - tests filling the eeprom with commands and then reading them back
1135 {
1137  uint16_t num_commands = 0;
1138  uint16_t i;
1139  bool failed_to_add = false;
1140  bool failed_to_read = false;
1141  bool success = true;
1142 
1143  // test adding many commands until it fails
1144  while (!failed_to_add) {
1145  // Command #0 : home
1146  cmd.id = MAV_CMD_NAV_WAYPOINT;
1147  cmd.content.location.options = 0;
1148  cmd.p1 = 0;
1149  cmd.content.location.alt = num_commands;
1150  cmd.content.location.lat = 12345678;
1151  cmd.content.location.lng = 23456789;
1152  if (!mission.add_cmd(cmd)) {
1153  hal.console->printf("failed to add command #%u, library says max is %u\n",(unsigned int)num_commands, (unsigned int)mission.num_commands_max());
1154  failed_to_add = true;
1155  }else{
1156  num_commands++;
1157  }
1158  }
1159 
1160  // test retrieving commands
1161  for (i=0; i<num_commands; i++) {
1162  if (!mission.read_cmd_from_storage(i,cmd)) {
1163  hal.console->printf("failed to retrieve command #%u\n",(unsigned int)i);
1164  failed_to_read = true;
1165  break;
1166  }else{
1167  if (cmd.content.location.alt == i) {
1168  hal.console->printf("successfully read command #%u\n",(unsigned int)i);
1169  }else{
1170  hal.console->printf("cmd %u's alt does not match, expected %u but read %u\n",
1171  (unsigned int)i,(unsigned int)i,(unsigned int)cmd.content.location.alt);
1172  }
1173  }
1174  }
1175 
1176  // final success/fail message
1177  if (num_commands != mission.num_commands()) {
1178  hal.console->printf("\nTest failed! Only wrote %u instead of %u commands",(unsigned int)i,(unsigned int)mission.num_commands_max());
1179  success = false;
1180  }
1181  if (failed_to_read) {
1182  hal.console->printf("\nTest failed! Only read %u instead of %u commands",(unsigned int)i,(unsigned int)mission.num_commands_max());
1183  success = false;
1184  }
1185  if (success) {
1186  hal.console->printf("\nTest Passed! wrote and read back %u commands\n\n",(unsigned int)mission.num_commands_max());
1187  }
1188 }
1189 
1190 // setup
1192 {
1193  hal.console->printf("AP_Mission library test\n\n");
1194 
1195  // display basic info about command sizes
1196  hal.console->printf("Max Num Commands: %d\n",(int)mission.num_commands_max());
1197  hal.console->printf("Command size: %d bytes\n",(int)AP_MISSION_EEPROM_COMMAND_SIZE);
1198 }
1199 
1200 // loop
1202 {
1203  // uncomment line below to run one of the mission tests
1204  run_mission_test();
1205 
1206  // uncomment line below to run the mission pause/resume test
1207  //run_resume_test();
1208 
1209  // wait forever
1210  while(true) {
1211  hal.scheduler->delay(1000);
1212  }
1213 }
1214 
1215 void setup(void);
1216 void loop(void);
1217 
1218 void setup(void)
1219 {
1220  missiontest.setup();
1221 }
1222 void loop(void)
1223 {
1224  missiontest.loop();
1225 }
1226 
1227 AP_HAL_MAIN();
struct timespec start_time
Definition: system.cpp:16
Definition: AP_GPS.h:48
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
bool verify_cmd(const AP_Mission::Mission_Command &cmd)
Jump_Command jump
Definition: AP_Mission.h:197
static MissionTest missiontest
AP_HAL::UARTDriver * console
Definition: HAL.h:110
void mission_complete(void)
void run_set_current_cmd_test()
Object managing Mission.
Definition: AP_Mission.h:45
void start()
Definition: AP_Mission.cpp:65
void init_mission_no_nav_commands()
uint16_t num_commands() const
Definition: AP_Mission.h:330
uint8_t num_nav_cmd_runs
void init_mission_ends_with_do_commands()
bool start_cmd(const AP_Mission::Mission_Command &cmd)
bool add_cmd(Mission_Command &cmd)
Definition: AP_Mission.cpp:254
uint8_t num_do_cmd_runs
AP_AHRS_DCM ahrs
int32_t lat
param 3 - Latitude * 10**7
Definition: AP_Common.h:143
void run_mission_test()
bool clear()
Definition: AP_Mission.cpp:175
bool read_cmd_from_storage(uint16_t index, Mission_Command &cmd) const
Definition: AP_Mission.cpp:453
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
virtual void delay(uint16_t ms)=0
virtual void printf(const char *,...) FMT_PRINTF(2
Definition: BetterStream.cpp:5
int32_t alt
param 2 - Altitude in centimeters (meters * 100) see LOCATION_ALT_MAX_M
Definition: AP_Common.h:142
mission_state state() const
status - returns the status of the mission (i.e. Mission_Started, Mission_Complete, Mission_Stopped
Definition: AP_Mission.h:326
uint32_t millis()
Definition: system.cpp:157
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Handles the MAVLINK command mission stack. Reads and writes mission to storage.
void init_mission_endless_loop()
void init_mission_starts_with_do_commands()
#define AP_MISSION_EEPROM_COMMAND_SIZE
Definition: AP_Mission.h:26
void run_resume_test()
AP_InertialSensor ins
bool set_current_cmd(uint16_t index)
Definition: AP_Mission.cpp:339
void run_set_current_cmd_while_stopped_test()
void resume()
Definition: AP_Mission.cpp:86
const HAL & get_HAL()
void update()
Definition: AP_Mission.cpp:206
uint16_t num_commands_max() const
num_commands_max - returns maximum number of commands that can be stored
int32_t lng
param 4 - Longitude * 10**7
Definition: AP_Common.h:144
void init_mission_jump_to_nonnav()
AP_HAL_MAIN()
void run_replace_cmd_test()
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
Definition: functor.h:31
AP_Mission mission
uint8_t verify_do_cmd_iterations_to_complete
uint8_t verify_nav_cmd_iterations_to_complete
AP_HAL::Scheduler * scheduler
Definition: HAL.h:114
uint8_t options
Definition: AP_Common.h:136
void init_mission_ends_with_jump_command()