AP_Mission_test.cpp 37 KB

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