AP_RangeFinder_LeddarOne.cpp 7.8 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234
  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_Math/crc.h>
  15. #include "AP_RangeFinder_LeddarOne.h"
  16. #include <AP_SerialManager/AP_SerialManager.h>
  17. extern const AP_HAL::HAL& hal;
  18. /*
  19. The constructor also initialises the rangefinder. Note that this
  20. constructor is not called until detect() returns true, so we
  21. already know that we should setup the rangefinder
  22. */
  23. AP_RangeFinder_LeddarOne::AP_RangeFinder_LeddarOne(RangeFinder::RangeFinder_State &_state,
  24. AP_RangeFinder_Params &_params,
  25. uint8_t serial_instance) :
  26. AP_RangeFinder_Backend(_state, _params)
  27. {
  28. const AP_SerialManager &serial_manager = AP::serialmanager();
  29. uart = serial_manager.find_serial(AP_SerialManager::SerialProtocol_Rangefinder, serial_instance);
  30. if (uart != nullptr) {
  31. uart->begin(serial_manager.find_baudrate(AP_SerialManager::SerialProtocol_Rangefinder, serial_instance));
  32. }
  33. }
  34. /*
  35. detect if a LeddarOne rangefinder is connected. We'll detect by
  36. trying to take a reading on Serial. If we get a result the sensor is
  37. there.
  38. */
  39. bool AP_RangeFinder_LeddarOne::detect(uint8_t serial_instance)
  40. {
  41. return AP::serialmanager().find_serial(AP_SerialManager::SerialProtocol_Rangefinder, serial_instance) != nullptr;
  42. }
  43. // read - return last value measured by sensor
  44. bool AP_RangeFinder_LeddarOne::get_reading(uint16_t &reading_cm)
  45. {
  46. uint8_t number_detections;
  47. LeddarOne_Status leddarone_status;
  48. if (uart == nullptr) {
  49. return false;
  50. }
  51. switch (modbus_status) {
  52. case LEDDARONE_MODBUS_STATE_INIT: {
  53. uint8_t index = 0;
  54. // clear read buffer
  55. uint32_t nbytes = uart->available();
  56. while (nbytes-- > 0) {
  57. uart->read();
  58. if (++index > LEDDARONE_SERIAL_PORT_MAX) {
  59. // LEDDARONE_STATE_ERR_SERIAL_PORT
  60. return false;
  61. }
  62. }
  63. // clear buffer and buffer_len
  64. memset(read_buffer, 0, sizeof(read_buffer));
  65. read_len = 0;
  66. modbus_status = LEDDARONE_MODBUS_STATE_PRE_SEND_REQUEST;
  67. }
  68. // fall through to next state LEDDARONE_MODBUS_STATE_PRE_SEND_REQUEST
  69. // immediately
  70. FALLTHROUGH;
  71. case LEDDARONE_MODBUS_STATE_PRE_SEND_REQUEST:
  72. // send a request message for Modbus function 4
  73. uart->write(send_request_buffer, sizeof(send_request_buffer));
  74. modbus_status = LEDDARONE_MODBUS_STATE_SENT_REQUEST;
  75. last_sending_request_ms = AP_HAL::millis();
  76. FALLTHROUGH;
  77. case LEDDARONE_MODBUS_STATE_SENT_REQUEST:
  78. if (uart->available()) {
  79. // change mod_bus status to read available buffer
  80. modbus_status = LEDDARONE_MODBUS_STATE_AVAILABLE;
  81. last_available_ms = AP_HAL::millis();
  82. } else {
  83. if (AP_HAL::millis() - last_sending_request_ms > 200) {
  84. // reset mod_bus status to read new buffer
  85. // if read_len is zero, send request without initialize
  86. modbus_status = (read_len == 0) ? LEDDARONE_MODBUS_STATE_PRE_SEND_REQUEST : LEDDARONE_MODBUS_STATE_INIT;
  87. }
  88. }
  89. break;
  90. case LEDDARONE_MODBUS_STATE_AVAILABLE:
  91. // parse a response message, set number_detections, detections and sum_distance
  92. leddarone_status = parse_response(number_detections);
  93. if (leddarone_status == LEDDARONE_STATE_OK) {
  94. reading_cm = sum_distance / number_detections;
  95. // reset mod_bus status to read new buffer
  96. modbus_status = LEDDARONE_MODBUS_STATE_INIT;
  97. return true;
  98. }
  99. // if status is not reading buffer, reset mod_bus status to read new buffer
  100. else if (leddarone_status != LEDDARONE_STATE_READING_BUFFER || AP_HAL::millis() - last_available_ms > 200) {
  101. // if read_len is zero, send request without initialize
  102. modbus_status = (read_len == 0) ? LEDDARONE_MODBUS_STATE_PRE_SEND_REQUEST : LEDDARONE_MODBUS_STATE_INIT;
  103. }
  104. break;
  105. }
  106. return false;
  107. }
  108. /*
  109. update the state of the sensor
  110. */
  111. void AP_RangeFinder_LeddarOne::update(void)
  112. {
  113. if (get_reading(state.distance_cm)) {
  114. // update range_valid state based on distance measured
  115. state.last_reading_ms = AP_HAL::millis();
  116. update_status();
  117. } else if (AP_HAL::millis() - state.last_reading_ms > 200) {
  118. set_status(RangeFinder::RangeFinder_NoData);
  119. }
  120. }
  121. /*
  122. CRC16
  123. CRC-16-IBM(x16+x15+x2+1)
  124. */
  125. bool AP_RangeFinder_LeddarOne::CRC16(uint8_t *aBuffer, uint8_t aLength, bool aCheck)
  126. {
  127. uint16_t crc = calc_crc_modbus(aBuffer, aLength);
  128. uint8_t lCRCLo = LOWBYTE(crc);
  129. uint8_t lCRCHi = HIGHBYTE(crc);
  130. if (aCheck) {
  131. return (aBuffer[aLength] == lCRCLo) && (aBuffer[aLength+1] == lCRCHi);
  132. } else {
  133. aBuffer[aLength] = lCRCLo;
  134. aBuffer[aLength+1] = lCRCHi;
  135. return true;
  136. }
  137. }
  138. /*
  139. parse a response message from Modbus
  140. -----------------------------------------------
  141. [ read buffer packet ]
  142. -----------------------------------------------
  143. 0: slave address (LEDDARONE_DEFAULT_ADDRESS)
  144. 1: functions code
  145. 2: byte count
  146. 5-6-3-4: timestamp
  147. 7-8: internal temperature
  148. 9-10: number of detections
  149. 11-12: first distance
  150. 13-14: first amplitude
  151. 15-16: second distance
  152. 17-18: second amplitude
  153. 19-20: third distances
  154. 21-22: third amplitude
  155. 23: CRC Low
  156. 24: CRC High
  157. -----------------------------------------------
  158. */
  159. LeddarOne_Status AP_RangeFinder_LeddarOne::parse_response(uint8_t &number_detections)
  160. {
  161. uint8_t index;
  162. uint8_t index_offset = LEDDARONE_DETECTION_DATA_INDEX_OFFSET;
  163. // read serial
  164. uint32_t nbytes = uart->available();
  165. if (nbytes != 0) {
  166. for (index=read_len; index<nbytes+read_len; index++) {
  167. if (index >= LEDDARONE_READ_BUFFER_SIZE) {
  168. return LEDDARONE_STATE_ERR_BAD_RESPONSE;
  169. }
  170. read_buffer[index] = uart->read();
  171. }
  172. read_len += nbytes;
  173. if (read_len < LEDDARONE_READ_BUFFER_SIZE) {
  174. return LEDDARONE_STATE_READING_BUFFER;
  175. }
  176. }
  177. // lead_len is not 25 byte or function code is not 0x04
  178. if (read_len != LEDDARONE_READ_BUFFER_SIZE || read_buffer[1] != LEDDARONE_MODOBUS_FUNCTION_CODE) {
  179. return LEDDARONE_STATE_ERR_BAD_RESPONSE;
  180. }
  181. // CRC16
  182. if (!CRC16(read_buffer, read_len-2, true)) {
  183. return LEDDARONE_STATE_ERR_BAD_CRC;
  184. }
  185. // number of detections (index:10)
  186. number_detections = read_buffer[LEDDARONE_DETECTION_DATA_NUMBER_INDEX];
  187. // if the number of detection is over or zero , it is false
  188. if (number_detections > LEDDARONE_DETECTIONS_MAX || number_detections == 0) {
  189. return LEDDARONE_STATE_ERR_NUMBER_DETECTIONS;
  190. }
  191. memset(detections, 0, sizeof(detections));
  192. sum_distance = 0;
  193. for (index=0; index<number_detections; index++) {
  194. // construct data word from two bytes and convert mm to cm
  195. detections[index] = (static_cast<uint16_t>(read_buffer[index_offset])*256 + read_buffer[index_offset+1]) / 10;
  196. sum_distance += detections[index];
  197. // add index offset (4) to read next detection data
  198. index_offset += LEDDARONE_DETECTION_DATA_OFFSET;
  199. }
  200. return LEDDARONE_STATE_OK;
  201. }