AP_Beacon_Marvelmind.cpp 17 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405
  1. /*
  2. This program is free software: you can redistribute it and/or modify
  3. it under the terms of the GNU General Public License as published by
  4. the Free Software Foundation, either version 3 of the License, or
  5. (at your option) any later version.
  6. This program is distributed in the hope that it will be useful,
  7. but WITHOUT ANY WARRANTY; without even the implied warranty of
  8. MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  9. GNU General Public License for more details.
  10. You should have received a copy of the GNU General Public License
  11. along with this program. If not, see <http://www.gnu.org/licenses/>.
  12. */
  13. /*
  14. Original C Code by Marvelmind (https://github.com/MarvelmindRobotics/marvelmind.c)
  15. Adapted into Ardupilot by Karthik Desai, Amilcar Lucas
  16. April 2017
  17. */
  18. #include <AP_HAL/AP_HAL.h>
  19. #include <AP_Math/crc.h>
  20. #include "AP_Beacon_Marvelmind.h"
  21. #define AP_BEACON_MARVELMIND_POSITION_DATAGRAM_ID 0x0001
  22. #define AP_BEACON_MARVELMIND_POSITIONS_DATAGRAM_ID 0x0002
  23. #define AP_BEACON_MARVELMIND_DISTANCES_DATAGRAM_ID 0x0004
  24. #define AP_BEACON_MARVELMIND_POSITION_DATAGRAM_HIGHRES_ID 0x0011
  25. #define AP_BEACON_MARVELMIND_POSITIONS_DATAGRAM_HIGHRES_ID 0x0012
  26. extern const AP_HAL::HAL& hal;
  27. #define MM_DEBUG_LEVEL 0
  28. #if MM_DEBUG_LEVEL
  29. #include <GCS_MAVLink/GCS.h>
  30. #define Debug(level, fmt, args ...) do { if (level <= MM_DEBUG_LEVEL) { gcs().send_text(MAV_SEVERITY_INFO, fmt, ## args); } } while (0)
  31. #else
  32. #define Debug(level, fmt, args ...)
  33. #endif
  34. AP_Beacon_Marvelmind::AP_Beacon_Marvelmind(AP_Beacon &frontend, AP_SerialManager &serial_manager) :
  35. AP_Beacon_Backend(frontend)
  36. {
  37. uart = serial_manager.find_serial(AP_SerialManager::SerialProtocol_Beacon, 0);
  38. if (uart != nullptr) {
  39. uart->begin(serial_manager.find_baudrate(AP_SerialManager::SerialProtocol_Beacon, 0));
  40. last_update_ms = 0;
  41. parse_state = RECV_HDR; // current state of receive data
  42. num_bytes_in_block_received = 0; // bytes received
  43. data_id = 0;
  44. hedge._have_new_values = false;
  45. hedge.positions_beacons.num_beacons = 0;
  46. hedge.positions_beacons.updated = false;
  47. }
  48. }
  49. void AP_Beacon_Marvelmind::process_position_datagram()
  50. {
  51. hedge.cur_position.address = input_buffer[16];
  52. hedge.cur_position.timestamp = input_buffer[5]
  53. | (((uint32_t) input_buffer[6]) << 8)
  54. | (((uint32_t) input_buffer[7]) << 16)
  55. | (((uint32_t) input_buffer[8]) << 24);
  56. const int16_t vx = input_buffer[9] | (((uint16_t) input_buffer[10]) << 8);
  57. hedge.cur_position.x__mm = vx * 10; // centimeters -> millimeters
  58. const int16_t vy = input_buffer[11] | (((uint16_t) input_buffer[12]) << 8);
  59. hedge.cur_position.y__mm = vy * 10; // centimeters -> millimeters
  60. const int16_t vz = input_buffer[13] | (((uint16_t) input_buffer[14]) << 8);
  61. hedge.cur_position.z__mm = vz * 10; // centimeters -> millimeters
  62. hedge.cur_position.high_resolution = false;
  63. hedge._have_new_values = true;
  64. }
  65. void AP_Beacon_Marvelmind::process_position_highres_datagram()
  66. {
  67. hedge.cur_position.address = input_buffer[22];
  68. hedge.cur_position.timestamp = input_buffer[5]
  69. | (((uint32_t) input_buffer[6]) << 8)
  70. | (((uint32_t) input_buffer[7]) << 16)
  71. | (((uint32_t) input_buffer[8]) << 24);
  72. hedge.cur_position.x__mm = input_buffer[9] | (((uint32_t) input_buffer[10]) << 8)
  73. | (((uint32_t) input_buffer[11]) << 16)
  74. | (((uint32_t) input_buffer[12]) << 24);
  75. hedge.cur_position.y__mm = input_buffer[13] | (((uint32_t) input_buffer[14]) << 8)
  76. | (((uint32_t) input_buffer[15]) << 16)
  77. | (((uint32_t) input_buffer[16]) << 24);
  78. hedge.cur_position.z__mm = input_buffer[17] | (((uint32_t) input_buffer[18]) << 8)
  79. | (((uint32_t) input_buffer[19]) << 16)
  80. | (((uint32_t) input_buffer[20]) << 24);
  81. hedge.cur_position.high_resolution = true;
  82. hedge._have_new_values = true;
  83. }
  84. AP_Beacon_Marvelmind::StationaryBeaconPosition* AP_Beacon_Marvelmind::get_or_alloc_beacon(uint8_t address)
  85. {
  86. const uint8_t n_used = hedge.positions_beacons.num_beacons;
  87. for (uint8_t i = 0; i < n_used; i++) {
  88. if (hedge.positions_beacons.beacons[i].address == address) {
  89. return &hedge.positions_beacons.beacons[i];
  90. }
  91. }
  92. if (n_used >= AP_BEACON_MAX_BEACONS) {
  93. return nullptr;
  94. }
  95. hedge.positions_beacons.num_beacons = (n_used + 1);
  96. return &hedge.positions_beacons.beacons[n_used];
  97. }
  98. void AP_Beacon_Marvelmind::process_beacons_positions_datagram()
  99. {
  100. const uint8_t n = input_buffer[5]; // number of beacons in packet
  101. StationaryBeaconPosition *stationary_beacon;
  102. if ((1 + n * 8) != input_buffer[4]) {
  103. Debug(1, "beacon pos lo pkt size %d != %d", input_buffer[4], (1 + n * 8));
  104. return; // incorrect size
  105. }
  106. for (uint8_t i = 0; i < n; i++) {
  107. const uint8_t ofs = 6 + i * 8;
  108. const uint8_t address = input_buffer[ofs];
  109. const int16_t x = input_buffer[ofs + 1]
  110. | (((uint16_t) input_buffer[ofs + 2]) << 8);
  111. const int16_t y = input_buffer[ofs + 3]
  112. | (((uint16_t) input_buffer[ofs + 4]) << 8);
  113. const int16_t z = input_buffer[ofs + 5]
  114. | (((uint16_t) input_buffer[ofs + 6]) << 8);
  115. stationary_beacon = get_or_alloc_beacon(address);
  116. if (stationary_beacon != nullptr) {
  117. stationary_beacon->address = address; //The instance and the address are the same
  118. stationary_beacon->x__mm = x * 10; // centimeters -> millimeters
  119. stationary_beacon->y__mm = y * 10; // centimeters -> millimeters
  120. stationary_beacon->z__mm = z * 10; // centimeters -> millimeters
  121. stationary_beacon->high_resolution = false;
  122. hedge.positions_beacons.updated = true;
  123. }
  124. }
  125. order_stationary_beacons();
  126. }
  127. void AP_Beacon_Marvelmind::process_beacons_positions_highres_datagram()
  128. {
  129. const uint8_t n = input_buffer[5]; // number of beacons in packet
  130. StationaryBeaconPosition *stationary_beacon;
  131. if ((1 + n * 14) != input_buffer[4]) {
  132. Debug(1, "beacon pos hi pkt size %d != %d", input_buffer[4], (1 + n * 14));
  133. return; // incorrect size
  134. }
  135. for (uint8_t i = 0; i < n; i++) {
  136. const uint8_t ofs = 6 + i * 14;
  137. const uint8_t address = input_buffer[ofs];
  138. const int32_t x = input_buffer[ofs + 1]
  139. | (((uint32_t) input_buffer[ofs + 2]) << 8)
  140. | (((uint32_t) input_buffer[ofs + 3]) << 16)
  141. | (((uint32_t) input_buffer[ofs + 4]) << 24);
  142. const int32_t y = input_buffer[ofs + 5]
  143. | (((uint32_t) input_buffer[ofs + 6]) << 8)
  144. | (((uint32_t) input_buffer[ofs + 7]) << 16)
  145. | (((uint32_t) input_buffer[ofs + 8]) << 24);
  146. const int32_t z = input_buffer[ofs + 9]
  147. | (((uint32_t) input_buffer[ofs + 10]) << 8)
  148. | (((uint32_t) input_buffer[ofs + 11]) << 16)
  149. | (((uint32_t) input_buffer[ofs + 12]) << 24);
  150. stationary_beacon = get_or_alloc_beacon(address);
  151. if (stationary_beacon != nullptr) {
  152. stationary_beacon->address = address; //The instance and the address are the same
  153. stationary_beacon->x__mm = x; // millimeters
  154. stationary_beacon->y__mm = y; // millimeters
  155. stationary_beacon->z__mm = z; // millimeters
  156. stationary_beacon->high_resolution = true;
  157. hedge.positions_beacons.updated = true;
  158. }
  159. }
  160. order_stationary_beacons();
  161. }
  162. void AP_Beacon_Marvelmind::process_beacons_distances_datagram()
  163. {
  164. if (32 != input_buffer[4]) {
  165. Debug(1, "beacon dist pkt size %d != 32", input_buffer[4]);
  166. return; // incorrect size
  167. }
  168. bool set = false;
  169. for (uint8_t i = 0; i < hedge.positions_beacons.num_beacons; i++) {
  170. const uint8_t ofs = 6 + i * 6;
  171. const uint8_t address = input_buffer[ofs];
  172. const int8_t instance = find_beacon_instance(address);
  173. if (instance != -1) {
  174. const uint32_t distance = input_buffer[ofs + 1]
  175. | (((uint32_t) input_buffer[ofs + 2]) << 8)
  176. | (((uint32_t) input_buffer[ofs + 3]) << 16)
  177. | (((uint32_t) input_buffer[ofs + 4]) << 24);
  178. hedge.positions_beacons.beacons[instance].distance__m = distance * 0.001f; // millimeters -> meters
  179. set_beacon_distance(instance, hedge.positions_beacons.beacons[instance].distance__m);
  180. set = true;
  181. Debug(2, "Beacon %d is %.2fm", instance, hedge.positions_beacons.beacons[instance].distance__m);
  182. }
  183. }
  184. if (set) {
  185. last_update_ms = AP_HAL::millis();
  186. }
  187. }
  188. int8_t AP_Beacon_Marvelmind::find_beacon_instance(uint8_t address) const
  189. {
  190. for (uint8_t i = 0; i < hedge.positions_beacons.num_beacons; i++) {
  191. if (hedge.positions_beacons.beacons[i].address == address) {
  192. return i;
  193. }
  194. }
  195. return -1;
  196. }
  197. void AP_Beacon_Marvelmind::update(void)
  198. {
  199. if (uart == nullptr) {
  200. return;
  201. }
  202. // read any available characters
  203. int32_t num_bytes_read = uart->available();
  204. uint8_t received_char = 0;
  205. if (num_bytes_read < 0) {
  206. return;
  207. }
  208. while (num_bytes_read-- > 0) {
  209. bool good_byte = false;
  210. received_char = uart->read();
  211. input_buffer[num_bytes_in_block_received] = received_char;
  212. switch (parse_state) {
  213. case RECV_HDR:
  214. switch (num_bytes_in_block_received) {
  215. case 0:
  216. good_byte = (received_char == 0xff);
  217. break;
  218. case 1:
  219. good_byte = (received_char == 0x47);
  220. break;
  221. case 2:
  222. good_byte = true;
  223. break;
  224. case 3:
  225. data_id = (((uint16_t)received_char) << 8) + input_buffer[2];
  226. good_byte = (data_id == AP_BEACON_MARVELMIND_POSITION_DATAGRAM_ID)
  227. || (data_id == AP_BEACON_MARVELMIND_POSITIONS_DATAGRAM_ID)
  228. || (data_id == AP_BEACON_MARVELMIND_DISTANCES_DATAGRAM_ID)
  229. || (data_id == AP_BEACON_MARVELMIND_POSITION_DATAGRAM_HIGHRES_ID)
  230. || (data_id == AP_BEACON_MARVELMIND_POSITIONS_DATAGRAM_HIGHRES_ID);
  231. break;
  232. case 4: {
  233. switch (data_id) {
  234. case AP_BEACON_MARVELMIND_POSITION_DATAGRAM_ID: {
  235. good_byte = (received_char == 0x10);
  236. break;
  237. }
  238. case AP_BEACON_MARVELMIND_DISTANCES_DATAGRAM_ID:
  239. case AP_BEACON_MARVELMIND_POSITIONS_DATAGRAM_ID:
  240. case AP_BEACON_MARVELMIND_POSITIONS_DATAGRAM_HIGHRES_ID:
  241. good_byte = true;
  242. break;
  243. case AP_BEACON_MARVELMIND_POSITION_DATAGRAM_HIGHRES_ID: {
  244. good_byte = (received_char == 0x16);
  245. break;
  246. }
  247. }
  248. if (good_byte) {
  249. parse_state = RECV_DGRAM;
  250. }
  251. break;
  252. }
  253. }
  254. if (good_byte) {
  255. // correct header byte
  256. num_bytes_in_block_received++;
  257. } else {
  258. // ...or incorrect
  259. parse_state = RECV_HDR;
  260. num_bytes_in_block_received = 0;
  261. }
  262. break;
  263. case RECV_DGRAM:
  264. num_bytes_in_block_received++;
  265. if (num_bytes_in_block_received >= 7 + input_buffer[4]) {
  266. // parse dgram
  267. uint16_t block_crc = calc_crc_modbus(input_buffer, num_bytes_in_block_received);
  268. if (block_crc == 0) {
  269. switch (data_id) {
  270. case AP_BEACON_MARVELMIND_POSITION_DATAGRAM_ID:
  271. {
  272. // add to position_buffer
  273. process_position_datagram();
  274. vehicle_position_initialized = true;
  275. set_stationary_beacons_positions();
  276. break;
  277. }
  278. case AP_BEACON_MARVELMIND_POSITIONS_DATAGRAM_ID:
  279. {
  280. process_beacons_positions_datagram();
  281. beacon_position_initialized = true;
  282. set_stationary_beacons_positions();
  283. break;
  284. }
  285. case AP_BEACON_MARVELMIND_DISTANCES_DATAGRAM_ID:
  286. {
  287. process_beacons_distances_datagram();
  288. break;
  289. }
  290. case AP_BEACON_MARVELMIND_POSITION_DATAGRAM_HIGHRES_ID:
  291. {
  292. process_position_highres_datagram();
  293. vehicle_position_initialized = true;
  294. set_stationary_beacons_positions();
  295. break;
  296. }
  297. case AP_BEACON_MARVELMIND_POSITIONS_DATAGRAM_HIGHRES_ID:
  298. {
  299. process_beacons_positions_highres_datagram();
  300. beacon_position_initialized = true;
  301. set_stationary_beacons_positions();
  302. break;
  303. }
  304. }
  305. }
  306. // and repeat
  307. parse_state = RECV_HDR;
  308. num_bytes_in_block_received = 0;
  309. }
  310. break;
  311. }
  312. }
  313. }
  314. bool AP_Beacon_Marvelmind::healthy()
  315. {
  316. // healthy if we have parsed a message within the past 300ms
  317. return ((AP_HAL::millis() - last_update_ms) < AP_BEACON_TIMEOUT_MS);
  318. }
  319. void AP_Beacon_Marvelmind::set_stationary_beacons_positions()
  320. {
  321. bool set = false;
  322. if (vehicle_position_initialized && beacon_position_initialized) {
  323. if (hedge._have_new_values) {
  324. vehicle_position_NED__m = Vector3f(hedge.cur_position.y__mm * 0.001f,
  325. hedge.cur_position.x__mm * 0.001f,
  326. -hedge.cur_position.z__mm * 0.001f); //Transform Marvelmind ENU to Ardupilot NED
  327. //TODO: Calculate Accuracy of the received signal. Marvelmind *advertises* +/- 2cms
  328. // But we are conservative here and use 20cm instead (until MM provides us with a proper accuracy value)
  329. set_vehicle_position(vehicle_position_NED__m, 0.2f);
  330. set = true;
  331. Debug(2,
  332. "Hedge is at N%.2f, E%.2f, D%.2f",
  333. vehicle_position_NED__m[0],
  334. vehicle_position_NED__m[1],
  335. vehicle_position_NED__m[2]);
  336. }
  337. hedge._have_new_values = false;
  338. for (uint8_t i = 0; i < hedge.positions_beacons.num_beacons; ++i) {
  339. if (hedge.positions_beacons.updated) {
  340. beacon_position_NED__m[i] = Vector3f(hedge.positions_beacons.beacons[i].y__mm * 0.001f,
  341. hedge.positions_beacons.beacons[i].x__mm * 0.001f,
  342. -hedge.positions_beacons.beacons[i].z__mm * 0.001f); //Transform Marvelmind ENU to Ardupilot NED
  343. set_beacon_position(i, beacon_position_NED__m[i]);
  344. set = true;
  345. Debug(2,
  346. "Beacon %d is at N%.2f, E%.2f, D%.2f",
  347. i,
  348. beacon_position_NED__m[i][0],
  349. beacon_position_NED__m[i][1],
  350. beacon_position_NED__m[i][2]);
  351. }
  352. }
  353. hedge.positions_beacons.updated = false;
  354. }
  355. if (set) {
  356. last_update_ms = AP_HAL::millis();
  357. }
  358. }
  359. void AP_Beacon_Marvelmind::order_stationary_beacons()
  360. {
  361. if (hedge.positions_beacons.updated) {
  362. bool swapped = false;
  363. uint8_t j = hedge.positions_beacons.num_beacons;
  364. do
  365. {
  366. swapped = false;
  367. StationaryBeaconPosition beacon_to_swap;
  368. for (uint8_t i = 1; i < j; i++) {
  369. if (hedge.positions_beacons.beacons[i-1].address > hedge.positions_beacons.beacons[i].address) {
  370. beacon_to_swap = hedge.positions_beacons.beacons[i];
  371. hedge.positions_beacons.beacons[i] = hedge.positions_beacons.beacons[i-1];
  372. hedge.positions_beacons.beacons[i-1] = beacon_to_swap;
  373. swapped = true;
  374. }
  375. }
  376. j--;
  377. } while(swapped);
  378. }
  379. }