AP_Proximity_TeraRangerTower.cpp 4.5 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129
  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_Proximity_TeraRangerTower.h"
  15. #include <AP_SerialManager/AP_SerialManager.h>
  16. #include <AP_Math/crc.h>
  17. #include <ctype.h>
  18. #include <stdio.h>
  19. extern const AP_HAL::HAL& hal;
  20. /*
  21. The constructor also initialises the proximity sensor. Note that this
  22. constructor is not called until detect() returns true, so we
  23. already know that we should setup the proximity sensor
  24. */
  25. AP_Proximity_TeraRangerTower::AP_Proximity_TeraRangerTower(AP_Proximity &_frontend,
  26. AP_Proximity::Proximity_State &_state,
  27. AP_SerialManager &serial_manager) :
  28. AP_Proximity_Backend(_frontend, _state)
  29. {
  30. uart = serial_manager.find_serial(AP_SerialManager::SerialProtocol_Lidar360, 0);
  31. if (uart != nullptr) {
  32. uart->begin(serial_manager.find_baudrate(AP_SerialManager::SerialProtocol_Lidar360, 0));
  33. }
  34. }
  35. // detect if a TeraRanger Tower proximity sensor is connected by looking for a configured serial port
  36. bool AP_Proximity_TeraRangerTower::detect(AP_SerialManager &serial_manager)
  37. {
  38. AP_HAL::UARTDriver *uart = nullptr;
  39. uart = serial_manager.find_serial(AP_SerialManager::SerialProtocol_Lidar360, 0);
  40. return uart != nullptr;
  41. }
  42. // update the state of the sensor
  43. void AP_Proximity_TeraRangerTower::update(void)
  44. {
  45. if (uart == nullptr) {
  46. return;
  47. }
  48. // process incoming messages
  49. read_sensor_data();
  50. // check for timeout and set health status
  51. if ((_last_distance_received_ms == 0) || (AP_HAL::millis() - _last_distance_received_ms > PROXIMITY_TRTOWER_TIMEOUT_MS)) {
  52. set_status(AP_Proximity::Proximity_NoData);
  53. } else {
  54. set_status(AP_Proximity::Proximity_Good);
  55. }
  56. }
  57. // get maximum and minimum distances (in meters) of primary sensor
  58. float AP_Proximity_TeraRangerTower::distance_max() const
  59. {
  60. return 4.5f;
  61. }
  62. float AP_Proximity_TeraRangerTower::distance_min() const
  63. {
  64. return 0.20f;
  65. }
  66. // check for replies from sensor, returns true if at least one message was processed
  67. bool AP_Proximity_TeraRangerTower::read_sensor_data()
  68. {
  69. if (uart == nullptr) {
  70. return false;
  71. }
  72. uint16_t message_count = 0;
  73. int16_t nbytes = uart->available();
  74. while (nbytes-- > 0) {
  75. char c = uart->read();
  76. if (c == 'T' ) {
  77. buffer_count = 0;
  78. }
  79. buffer[buffer_count++] = c;
  80. // we should always read 19 bytes THxxxxxxxxxxxxxxxxC
  81. if (buffer_count >= 19){
  82. buffer_count = 0;
  83. // check if message has right CRC
  84. if (crc_crc8(buffer, 18) == buffer[18]){
  85. update_sector_data(0, UINT16_VALUE(buffer[2], buffer[3])); // d1
  86. update_sector_data(45, UINT16_VALUE(buffer[16], buffer[17])); // d8
  87. update_sector_data(90, UINT16_VALUE(buffer[14], buffer[15])); // d7
  88. update_sector_data(135, UINT16_VALUE(buffer[12], buffer[13])); // d6
  89. update_sector_data(180, UINT16_VALUE(buffer[10], buffer[11])); // d5
  90. update_sector_data(225, UINT16_VALUE(buffer[8], buffer[9])); // d4
  91. update_sector_data(270, UINT16_VALUE(buffer[6], buffer[7])); // d3
  92. update_sector_data(315, UINT16_VALUE(buffer[4], buffer[5])); // d2
  93. message_count++;
  94. }
  95. }
  96. }
  97. return (message_count > 0);
  98. }
  99. // process reply
  100. void AP_Proximity_TeraRangerTower::update_sector_data(int16_t angle_deg, uint16_t distance_cm)
  101. {
  102. uint8_t sector;
  103. if (convert_angle_to_sector(angle_deg, sector)) {
  104. _angle[sector] = angle_deg;
  105. _distance[sector] = ((float) distance_cm) / 1000;
  106. _distance_valid[sector] = distance_cm != 0xffff;
  107. _last_distance_received_ms = AP_HAL::millis();
  108. // update boundary used for avoidance
  109. update_boundary_for_sector(sector, true);
  110. }
  111. }