AP_RangeFinder_BLPing.cpp 8.9 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292
  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. #include <AP_HAL/AP_HAL.h>
  14. #include <AP_SerialManager/AP_SerialManager.h>
  15. #include <GCS_MAVLink/GCS.h>
  16. #include "AP_RangeFinder_BLPing.h"
  17. #define BLPING_TIMEOUT_MS 500 // sensor timeout after 0.5 sec
  18. #define BLPING_INIT_RATE_MS 1000 // initialise sensor at no more than 1hz
  19. #define BLPING_FRAME_HEADER1 0x42 // header first byte ('B')
  20. #define BLPING_FRAME_HEADER2 0x52 // header second byte ('R')
  21. #define BLPING_SRC_ID 0 // vehicle's source id
  22. #define BLPING_DEST_ID 1 // sensor's id
  23. #define BLPING_MSGID_ACK 1
  24. #define BLPING_MSGID_NACK 2
  25. #define BLPING_MSGID_SET_PING_INTERVAL 1004
  26. #define BLPING_MSGID_GET_DEVICE_ID 1201
  27. #define BLDPIN_MSGID_DISTANCE_SIMPLE 1211
  28. #define BLPING_MSGID_CONTINUOUS_START 1400
  29. // Protocol implemented by this sensor can be found here: https://github.com/bluerobotics/ping-protocol
  30. //
  31. // Byte Type Name Description
  32. // --------------------------------------------------------------------------------------------------------------
  33. // 0 uint8_t start1 'B'
  34. // 1 uint8_t start2 'R'
  35. // 2-3 uint16_t payload_length number of bytes in payload (low byte, high byte)
  36. // 4-5 uint16_t message id message id (low byte, high byte)
  37. // 6 uint8_t src_device_id id of device sending the message
  38. // 7 uint8_t dst_device_id id of device of the intended recipient
  39. // 8-n uint8_t[] payload message payload
  40. // (n+1)-(n+2) uint16_t checksum the sum of all the non-checksum bytes in the message (low byte, high byte)
  41. /*
  42. The constructor also initialises the rangefinder. Note that this
  43. constructor is not called until detect() returns true, so we
  44. already know that we should setup the rangefinder
  45. */
  46. AP_RangeFinder_BLPing::AP_RangeFinder_BLPing(RangeFinder::RangeFinder_State &_state,
  47. AP_RangeFinder_Params &_params,
  48. uint8_t serial_instance) :
  49. AP_RangeFinder_Backend(_state, _params)
  50. {
  51. const AP_SerialManager &serial_manager = AP::serialmanager();
  52. uart = serial_manager.find_serial(AP_SerialManager::SerialProtocol_Rangefinder, serial_instance);
  53. if (uart != nullptr) {
  54. uart->begin(serial_manager.find_baudrate(AP_SerialManager::SerialProtocol_Rangefinder, serial_instance));
  55. }
  56. }
  57. // detect if a serial port has been setup to accept rangefinder input
  58. bool AP_RangeFinder_BLPing::detect(uint8_t serial_instance)
  59. {
  60. return AP::serialmanager().find_serial(AP_SerialManager::SerialProtocol_Rangefinder, serial_instance) != nullptr;
  61. }
  62. /*
  63. update the state of the sensor
  64. */
  65. void AP_RangeFinder_BLPing::update(void)
  66. {
  67. if (uart == nullptr) {
  68. return;
  69. }
  70. const uint32_t now = AP_HAL::millis();
  71. if (get_reading(state.distance_cm)) {
  72. // update range_valid state based on distance measured
  73. state.last_reading_ms = now;
  74. update_status();
  75. } else if (now - state.last_reading_ms > BLPING_TIMEOUT_MS) {
  76. set_status(RangeFinder::RangeFinder_NoData);
  77. // initialise sensor if no distances recently
  78. if (now - last_init_ms > BLPING_INIT_RATE_MS) {
  79. last_init_ms = now;
  80. init_sensor();
  81. }
  82. }
  83. }
  84. void AP_RangeFinder_BLPing::init_sensor()
  85. {
  86. // request distance from sensor
  87. send_message(BLDPIN_MSGID_DISTANCE_SIMPLE, nullptr, 0);
  88. }
  89. // send message to sensor
  90. void AP_RangeFinder_BLPing::send_message(uint16_t msgid, const uint8_t *payload, uint16_t payload_len)
  91. {
  92. if (uart == nullptr) {
  93. return;
  94. }
  95. // check for sufficient space in outgoing buffer
  96. if (uart->txspace() < payload_len + 10U) {
  97. return;
  98. }
  99. // write header
  100. uart->write((uint8_t)BLPING_FRAME_HEADER1);
  101. uart->write((uint8_t)BLPING_FRAME_HEADER2);
  102. uint16_t crc = BLPING_FRAME_HEADER1 + BLPING_FRAME_HEADER2;
  103. // write payload length
  104. uart->write(LOWBYTE(payload_len));
  105. uart->write(HIGHBYTE(payload_len));
  106. crc += LOWBYTE(payload_len) + HIGHBYTE(payload_len);
  107. // msgid
  108. uart->write(LOWBYTE(msgid));
  109. uart->write(HIGHBYTE(msgid));
  110. crc += LOWBYTE(msgid) + HIGHBYTE(msgid);
  111. // src dev id
  112. uart->write((uint8_t)BLPING_SRC_ID);
  113. crc += BLPING_SRC_ID;
  114. // destination dev id
  115. uart->write((uint8_t)BLPING_DEST_ID);
  116. crc += BLPING_DEST_ID;
  117. // payload
  118. if (payload != nullptr) {
  119. for (uint16_t i = 0; i<payload_len; i++) {
  120. uart->write(payload[i]);
  121. crc += payload[i];
  122. }
  123. }
  124. // checksum
  125. uart->write(LOWBYTE(crc));
  126. uart->write(HIGHBYTE(crc));
  127. }
  128. // distance returned in reading_cm, signal_ok is set to true if sensor reports a strong signal
  129. bool AP_RangeFinder_BLPing::get_reading(uint16_t &reading_cm)
  130. {
  131. if (uart == nullptr) {
  132. return false;
  133. }
  134. float sum_cm = 0;
  135. uint16_t count = 0;
  136. // read any available lines from the lidar
  137. int16_t nbytes = uart->available();
  138. while (nbytes-- > 0) {
  139. const int16_t b = uart->read();
  140. if (b < 0) {
  141. break;
  142. }
  143. if (parse_byte(b)) {
  144. count++;
  145. sum_cm += distance_cm;
  146. }
  147. }
  148. if (count > 0) {
  149. // return average distance of readings
  150. reading_cm = sum_cm / count;
  151. // request another distance
  152. send_message(BLDPIN_MSGID_DISTANCE_SIMPLE, nullptr, 0);
  153. return true;
  154. }
  155. // no readings so return false
  156. return false;
  157. }
  158. // process one byte received on serial port
  159. // returns true if a distance message has been successfully parsed
  160. // state is stored in msg structure
  161. bool AP_RangeFinder_BLPing::parse_byte(uint8_t b)
  162. {
  163. bool got_distance = false;
  164. // process byte depending upon current state
  165. switch (msg.state) {
  166. case ParseState::HEADER1:
  167. if (b == BLPING_FRAME_HEADER1) {
  168. msg.crc_expected = BLPING_FRAME_HEADER1;
  169. msg.state = ParseState::HEADER2;
  170. }
  171. break;
  172. case ParseState::HEADER2:
  173. if (b == BLPING_FRAME_HEADER2) {
  174. msg.crc_expected += BLPING_FRAME_HEADER2;
  175. msg.state = ParseState::LEN_L;
  176. } else {
  177. msg.state = ParseState::HEADER1;
  178. }
  179. break;
  180. case ParseState::LEN_L:
  181. msg.payload_len = b;
  182. msg.crc_expected += b;
  183. msg.state = ParseState::LEN_H;
  184. break;
  185. case ParseState::LEN_H:
  186. msg.payload_len |= ((uint16_t)b << 8);
  187. msg.payload_recv = 0;
  188. msg.crc_expected += b;
  189. msg.state = ParseState::MSG_ID_L;
  190. break;
  191. case ParseState::MSG_ID_L:
  192. msg.msgid = b;
  193. msg.crc_expected += b;
  194. msg.state = ParseState::MSG_ID_H;
  195. break;
  196. case ParseState::MSG_ID_H:
  197. msg.msgid |= ((uint16_t)b << 8);
  198. msg.crc_expected += b;
  199. msg.state = ParseState::SRC_ID;
  200. break;
  201. case ParseState::SRC_ID:
  202. msg.crc_expected += b;
  203. msg.state = ParseState::DST_ID;
  204. break;
  205. case ParseState::DST_ID:
  206. msg.crc_expected += b;
  207. msg.state = ParseState::PAYLOAD;
  208. break;
  209. case ParseState::PAYLOAD:
  210. if (msg.payload_recv < msg.payload_len) {
  211. if (msg.payload_recv < ARRAY_SIZE(msg.payload)) {
  212. msg.payload[msg.payload_recv] = b;
  213. }
  214. msg.payload_recv++;
  215. msg.crc_expected += b;
  216. }
  217. if (msg.payload_recv == msg.payload_len) {
  218. msg.state = ParseState::CRC_L;
  219. }
  220. break;
  221. case ParseState::CRC_L:
  222. msg.crc = b;
  223. msg.state = ParseState::CRC_H;
  224. break;
  225. case ParseState::CRC_H:
  226. msg.crc |= ((uint16_t)b << 8);
  227. msg.state = ParseState::HEADER1;
  228. if (msg.crc_expected == msg.crc) {
  229. // process payload
  230. switch (msg.msgid) {
  231. case BLPING_MSGID_ACK:
  232. case BLPING_MSGID_NACK:
  233. // ignore
  234. break;
  235. case BLDPIN_MSGID_DISTANCE_SIMPLE:
  236. const uint32_t dist_mm = (uint32_t)msg.payload[0] | (uint32_t)msg.payload[1] << 8 | (uint32_t)msg.payload[2] << 16 | (uint32_t)msg.payload[3] << 24;
  237. distance_cm = dist_mm / 10;
  238. got_distance = true;
  239. break;
  240. }
  241. }
  242. break;
  243. }
  244. return got_distance;
  245. }