SmartRTL_test.h 9.6 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361
  1. #include <vector>
  2. #include <AP_BoardConfig/AP_BoardConfig.h>
  3. #include <AP_HAL/AP_HAL.h>
  4. #include <AP_Math/AP_Math.h>
  5. #include <AP_SmartRTL/AP_SmartRTL.h>
  6. // vectors defined below:
  7. // test_path_before
  8. // test_path_after_adding
  9. // test_path_after_simplifying
  10. // test_path_after_pruning
  11. // test_path_complete
  12. // assume that any point without a comment should be kept
  13. std::vector<Vector3f> test_path_before {
  14. {0.0, 0.0, 0.0},
  15. {3.0, 0.0, 0.0}, // simplified
  16. {3.0, 0.0, 0.0}, // not added
  17. {6.0, 0.0, 0.0}, // simplified
  18. {10.0, 0.0, 0.0},
  19. {10.0, 3.0, 0.0},
  20. {13.0, 3.0, 0.0},
  21. {13.0, 6.0, 0.0},
  22. {16.0, 6.0, 0.0},
  23. {16.0, 6.0, 1.0}, // not added
  24. {16.0, 8.0, 1.0},
  25. {18.0, 8.0, 0.0},
  26. {20.0, 10.0, 0.0},
  27. {20.0, 10.0, 10.0},
  28. {23.0, 10.0, 10.0},
  29. {23.0, 13.0, 10.0},
  30. {26.0, 13.0, 10.0},
  31. {26.0, 16.0, 10.0},
  32. {29.0, 16.0, 10.0},
  33. {29.0, 19.0, 10.0},
  34. {32.0, 19.0, 10.0},
  35. {32.0, 22.0, 10.0},
  36. {35.0, 22.0, 10.0},
  37. {35.0, 25.0, 10.0},
  38. {38.0, 25.0, 10.0},
  39. {38.0, 28.0, 10.0},
  40. {41.0, 28.0, 10.0},
  41. {41.0, 31.0, 10.0},
  42. {44.0, 31.0, 10.0},
  43. {44.0, 34.0, 10.0},
  44. {47.0, 34.0, 10.0},
  45. {47.0, 37.0, 10.0},
  46. {51.0, 37.0, 10.0},
  47. {51.0, 41.0, 10.0},
  48. {54.0, 41.0, 10.0},
  49. {54.0, 44.0, 10.0},
  50. {57.0, 44.0, 10.0},
  51. {57.0, 47.0, 10.0},
  52. {60.0, 47.0, 10.0},
  53. {60.0, 40.0, 10.0},
  54. {63.0, 40.0, 10.0},
  55. {63.0, 43.0, 10.0},
  56. {66.0, 43.0, 10.0},
  57. {66.0, 46.0, 10.0},
  58. {69.0, 46.0, 10.0},
  59. {69.0, 49.0, 10.0},
  60. {72.0, 49.0, 10.0},
  61. {72.0, 52.0, 10.0},
  62. {75.0, 52.0, 10.0},
  63. {75.0, 55.0, 10.0},
  64. {100.0, 100.0, 100.0}, // pruned
  65. {103.0, 100.0, 100.0}, // pruned
  66. {106.0, 103.0, 100.0}, // pruned
  67. {103.0, 106.0, 100.0}, // pruned
  68. {100.0, 103.0, 100.0}, // pruned
  69. {103.0, 100.0, 100.0}, // pruned
  70. {200.0, 200.0, 200.0},
  71. {203.0, 200.0, 200.0},
  72. {203.0, 203.0, 200.0},
  73. {206.0, 203.0, 200.0},
  74. {206.0, 206.0, 200.0},
  75. {209.0, 206.0, 200.0},
  76. {209.0, 209.0, 200.0},
  77. {212.0, 209.0, 200.0},
  78. {212.0, 212.0, 200.0},
  79. {220.0, 220.0, 200.0},
  80. {223.0, 220.0, 200.0}, // pruned
  81. {226.0, 223.0, 200.0}, // pruned
  82. {223.0, 226.0, 200.0}, // pruned
  83. {220.0, 223.0, 200.0}, // pruned
  84. {223.0, 220.0, 201.0}, // pruned
  85. {226.0, 223.0, 200.0}, // pruned
  86. {223.0, 226.0, 200.0}, // pruned
  87. {220.0, 223.0, 200.0}, // pruned
  88. {223.0, 220.0, 199.0}, // pruned
  89. {229.0, 220.0, 200.0},
  90. {300.0, 300.0, 300.0},
  91. {305.0, 300.0, 300.0}, // simplified, pruned
  92. {310.0, 300.0, 300.0}, // simplified, pruned
  93. {315.0, 300.5, 300.0}, // simplified, pruned
  94. {320.0, 299.5, 300.0}, // simplified, pruned
  95. {325.0, 300.5, 300.0}, // simplified, pruned
  96. {330.0, 299.5, 300.0}, // simplified, pruned
  97. {335.0, 300.5, 300.0}, // simplified, pruned
  98. {340.0, 299.5, 300.0}, // simplified, pruned
  99. {345.0, 300.5, 300.0}, // simplified, pruned
  100. {350.0, 300.0, 300.0}, // pruned
  101. {350.0, 300.0, 400.0}, // pruned
  102. {345.0, 300.5, 400.0}, // simplified, pruned
  103. {340.0, 299.5, 400.0}, // simplified, pruned
  104. {335.0, 300.5, 400.0}, // simplified, pruned
  105. {330.0, 299.5, 400.0}, // simplified, pruned
  106. {325.0, 300.5, 400.0}, // simplified, pruned
  107. {320.0, 299.5, 400.0}, // simplified, pruned
  108. {315.0, 300.5, 400.0}, // simplified, pruned
  109. {310.0, 300.0, 400.0}, // simplified, pruned
  110. {305.0, 300.0, 400.0}, // pruned
  111. {300.0, 300.0, 295.0},
  112. };
  113. std::vector<Vector3f> test_path_after_adding {
  114. {0.0, 0.0, 0.0}, // 0
  115. {3.0, 0.0, 0.0},
  116. {6.0, 0.0, 0.0},
  117. {10.0, 0.0, 0.0},
  118. {10.0, 3.0, 0.0},
  119. {13.0, 3.0, 0.0},
  120. {13.0, 6.0, 0.0},
  121. {16.0, 6.0, 0.0},
  122. {16.0, 8.0, 1.0},
  123. {18.0, 8.0, 0.0},
  124. {20.0, 10.0, 0.0}, // 10
  125. {20.0, 10.0, 10.0},
  126. {23.0, 10.0, 10.0},
  127. {23.0, 13.0, 10.0},
  128. {26.0, 13.0, 10.0},
  129. {26.0, 16.0, 10.0},
  130. {29.0, 16.0, 10.0},
  131. {29.0, 19.0, 10.0},
  132. {32.0, 19.0, 10.0},
  133. {32.0, 22.0, 10.0},
  134. {35.0, 22.0, 10.0}, // 20
  135. {35.0, 25.0, 10.0},
  136. {38.0, 25.0, 10.0},
  137. {38.0, 28.0, 10.0},
  138. {41.0, 28.0, 10.0},
  139. {41.0, 31.0, 10.0},
  140. {44.0, 31.0, 10.0},
  141. {44.0, 34.0, 10.0},
  142. {47.0, 34.0, 10.0},
  143. {47.0, 37.0, 10.0},
  144. {51.0, 37.0, 10.0}, // 30
  145. {51.0, 41.0, 10.0},
  146. {54.0, 41.0, 10.0},
  147. {54.0, 44.0, 10.0},
  148. {57.0, 44.0, 10.0},
  149. {57.0, 47.0, 10.0},
  150. {60.0, 47.0, 10.0},
  151. {60.0, 40.0, 10.0},
  152. {63.0, 40.0, 10.0},
  153. {63.0, 43.0, 10.0},
  154. {66.0, 43.0, 10.0}, // 40
  155. {66.0, 46.0, 10.0},
  156. {69.0, 46.0, 10.0},
  157. {69.0, 49.0, 10.0},
  158. {72.0, 49.0, 10.0},
  159. {72.0, 52.0, 10.0},
  160. {75.0, 52.0, 10.0},
  161. {75.0, 55.0, 10.0},
  162. {100.0, 100.0, 100.0},
  163. {103.0, 100.0, 100.0},
  164. {106.0, 103.0, 100.0}, // 50
  165. {103.0, 106.0, 100.0},
  166. {100.0, 103.0, 100.0},
  167. {103.0, 100.0, 100.0},
  168. {200.0, 200.0, 200.0},
  169. {203.0, 200.0, 200.0},
  170. {203.0, 203.0, 200.0},
  171. {206.0, 203.0, 200.0},
  172. {206.0, 206.0, 200.0},
  173. {209.0, 206.0, 200.0},
  174. {209.0, 209.0, 200.0}, // 60
  175. {212.0, 209.0, 200.0},
  176. {212.0, 212.0, 200.0},
  177. {220.0, 220.0, 200.0},
  178. {223.0, 220.0, 200.0},
  179. {226.0, 223.0, 200.0},
  180. {223.0, 226.0, 200.0},
  181. {220.0, 223.0, 200.0},
  182. {223.0, 220.0, 201.0},
  183. {226.0, 223.0, 200.0},
  184. {223.0, 226.0, 200.0}, // 70
  185. {220.0, 223.0, 200.0},
  186. {223.0, 220.0, 199.0},
  187. {229.0, 220.0, 200.0},
  188. {300.0, 300.0, 300.0},
  189. {305.0, 300.0, 300.0},
  190. {310.0, 300.0, 300.0},
  191. {315.0, 300.5, 300.0},
  192. {320.0, 299.5, 300.0},
  193. {325.0, 300.5, 300.0},
  194. {330.0, 299.5, 300.0}, // 80
  195. {335.0, 300.5, 300.0},
  196. {340.0, 299.5, 300.0},
  197. {345.0, 300.5, 300.0},
  198. {350.0, 300.0, 300.0},
  199. {350.0, 300.0, 400.0},
  200. {345.0, 300.5, 400.0},
  201. {340.0, 299.5, 400.0},
  202. {335.0, 300.5, 400.0},
  203. {330.0, 299.5, 400.0},
  204. {325.0, 300.5, 400.0}, // 90
  205. {320.0, 299.5, 400.0},
  206. {315.0, 300.5, 400.0},
  207. {310.0, 300.0, 400.0},
  208. {305.0, 300.0, 400.0},
  209. {300.0, 300.0, 295.0},
  210. };
  211. std::vector<Vector3f> test_path_after_simplifying {
  212. {0.0, 0.0, 0.0}, // 0
  213. {10.0, 0.0, 0.0},
  214. {10.0, 3.0, 0.0},
  215. {13.0, 3.0, 0.0},
  216. {13.0, 6.0, 0.0},
  217. {16.0, 6.0, 0.0},
  218. {16.0, 8.0, 1.0},
  219. {18.0, 8.0, 0.0},
  220. {20.0, 10.0, 0.0},
  221. {20.0, 10.0, 10.0},
  222. {23.0, 10.0, 10.0}, // 10
  223. {23.0, 13.0, 10.0},
  224. {26.0, 13.0, 10.0},
  225. {26.0, 16.0, 10.0},
  226. {29.0, 16.0, 10.0},
  227. {29.0, 19.0, 10.0},
  228. {32.0, 19.0, 10.0},
  229. {32.0, 22.0, 10.0},
  230. {35.0, 22.0, 10.0},
  231. {35.0, 25.0, 10.0},
  232. {38.0, 25.0, 10.0}, // 20
  233. {38.0, 28.0, 10.0},
  234. {41.0, 28.0, 10.0},
  235. {41.0, 31.0, 10.0},
  236. {44.0, 31.0, 10.0},
  237. {44.0, 34.0, 10.0},
  238. {47.0, 34.0, 10.0},
  239. {47.0, 37.0, 10.0},
  240. {51.0, 37.0, 10.0},
  241. {51.0, 41.0, 10.0},
  242. {54.0, 41.0, 10.0}, // 30
  243. {54.0, 44.0, 10.0},
  244. {57.0, 44.0, 10.0},
  245. {57.0, 47.0, 10.0},
  246. {60.0, 47.0, 10.0},
  247. {60.0, 40.0, 10.0},
  248. {63.0, 40.0, 10.0},
  249. {63.0, 43.0, 10.0},
  250. {66.0, 43.0, 10.0},
  251. {66.0, 46.0, 10.0},
  252. {69.0, 46.0, 10.0}, // 40
  253. {69.0, 49.0, 10.0},
  254. {72.0, 49.0, 10.0},
  255. {72.0, 52.0, 10.0},
  256. {75.0, 52.0, 10.0},
  257. {75.0, 55.0, 10.0},
  258. {100.0, 100.0, 100.0},
  259. {103.0, 100.0, 100.0},
  260. {106.0, 103.0, 100.0},
  261. {103.0, 106.0, 100.0},
  262. {100.0, 103.0, 100.0}, // 50
  263. {103.0, 100.0, 100.0},
  264. {200.0, 200.0, 200.0},
  265. {203.0, 200.0, 200.0},
  266. {203.0, 203.0, 200.0},
  267. {206.0, 203.0, 200.0},
  268. {206.0, 206.0, 200.0},
  269. {209.0, 206.0, 200.0},
  270. {209.0, 209.0, 200.0},
  271. {212.0, 209.0, 200.0},
  272. {212.0, 212.0, 200.0}, // 60
  273. {220.0, 220.0, 200.0},
  274. {223.0, 220.0, 200.0},
  275. {226.0, 223.0, 200.0},
  276. {223.0, 226.0, 200.0},
  277. {220.0, 223.0, 200.0},
  278. {223.0, 220.0, 201.0},
  279. {226.0, 223.0, 200.0},
  280. {223.0, 226.0, 200.0},
  281. {220.0, 223.0, 200.0},
  282. {223.0, 220.0, 199.0}, // 70
  283. {229.0, 220.0, 200.0},
  284. {300.0, 300.0, 300.0},
  285. {350.0, 300.0, 300.0},
  286. {350.0, 300.0, 400.0},
  287. {305.0, 300.0, 400.0},
  288. {300.0, 300.0, 295.0},
  289. };
  290. std::vector<Vector3f> test_path_complete {
  291. {0.0, 0.0, 0.0}, // 0
  292. {10.0, 0.0, 0.0},
  293. {10.0, 3.0, 0.0},
  294. {13.0, 3.0, 0.0},
  295. {13.0, 6.0, 0.0},
  296. {16.0, 6.0, 0.0},
  297. {16.0, 8.0, 1.0},
  298. {18.0, 8.0, 0.0},
  299. {20.0, 10.0, 0.0},
  300. {20.0, 10.0, 10.0},
  301. {23.0, 10.0, 10.0}, // 10
  302. {23.0, 13.0, 10.0},
  303. {26.0, 13.0, 10.0},
  304. {26.0, 16.0, 10.0},
  305. {29.0, 16.0, 10.0},
  306. {29.0, 19.0, 10.0},
  307. {32.0, 19.0, 10.0},
  308. {32.0, 22.0, 10.0},
  309. {35.0, 22.0, 10.0},
  310. {35.0, 25.0, 10.0},
  311. {38.0, 25.0, 10.0}, // 20
  312. {38.0, 28.0, 10.0},
  313. {41.0, 28.0, 10.0},
  314. {41.0, 31.0, 10.0},
  315. {44.0, 31.0, 10.0},
  316. {44.0, 34.0, 10.0},
  317. {47.0, 34.0, 10.0},
  318. {47.0, 37.0, 10.0},
  319. {51.0, 37.0, 10.0},
  320. {51.0, 41.0, 10.0},
  321. {54.0, 41.0, 10.0}, // 30
  322. {54.0, 44.0, 10.0},
  323. {57.0, 44.0, 10.0},
  324. {57.0, 47.0, 10.0},
  325. {60.0, 47.0, 10.0},
  326. {60.0, 40.0, 10.0},
  327. {63.0, 40.0, 10.0},
  328. {63.0, 43.0, 10.0},
  329. {66.0, 43.0, 10.0},
  330. {66.0, 46.0, 10.0},
  331. {69.0, 46.0, 10.0}, // 40
  332. {69.0, 49.0, 10.0},
  333. {72.0, 49.0, 10.0},
  334. {72.0, 52.0, 10.0},
  335. {75.0, 52.0, 10.0},
  336. {75.0, 55.0, 10.0},
  337. {100.0, 100.0, 100.0},
  338. {103.0, 100.0, 100.0},
  339. {103.0, 100.0, 100.0},
  340. {200.0, 200.0, 200.0},
  341. {203.0, 200.0, 200.0}, // 50
  342. {203.0, 203.0, 200.0},
  343. {206.0, 203.0, 200.0},
  344. {206.0, 206.0, 200.0},
  345. {209.0, 206.0, 200.0},
  346. {209.0, 209.0, 200.0},
  347. {212.0, 209.0, 200.0},
  348. {212.0, 212.0, 200.0},
  349. {220.0, 220.0, 200.0},
  350. {223.0, 220.0, 200.0},
  351. {223.2368474, 220.0789542, 199.5263052}, // 60
  352. {229.0, 220.0, 200.0},
  353. {300.1223662, 300.0, 300.0696305},
  354. {300.0, 300.0, 295.0},
  355. };