AP_Proximity_TeraRangerTowerEvo.cpp 6.3 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183
  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_TeraRangerTowerEvo.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_TeraRangerTowerEvo::AP_Proximity_TeraRangerTowerEvo(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. _last_request_sent_ms = AP_HAL::millis();
  35. }
  36. // detect if a TeraRanger Tower proximity sensor is connected by looking for a configured serial port
  37. bool AP_Proximity_TeraRangerTowerEvo::detect(AP_SerialManager &serial_manager)
  38. {
  39. AP_HAL::UARTDriver *uart = nullptr;
  40. uart = serial_manager.find_serial(AP_SerialManager::SerialProtocol_Lidar360, 0);
  41. return uart != nullptr;
  42. }
  43. // update the state of the sensor
  44. void AP_Proximity_TeraRangerTowerEvo::update(void)
  45. {
  46. if (uart == nullptr) {
  47. return;
  48. }
  49. //initialize the sensor
  50. if(_current_init_state != InitState::InitState_Finished)
  51. {
  52. initialise_modes();
  53. }
  54. // process incoming messages
  55. read_sensor_data();
  56. // check for timeout and set health status
  57. if ((_last_distance_received_ms == 0) || (AP_HAL::millis() - _last_distance_received_ms > PROXIMITY_TRTOWER_TIMEOUT_MS)) {
  58. set_status(AP_Proximity::Proximity_NoData);
  59. } else {
  60. set_status(AP_Proximity::Proximity_Good);
  61. }
  62. }
  63. // get maximum and minimum distances (in meters) of primary sensor
  64. float AP_Proximity_TeraRangerTowerEvo::distance_max() const
  65. {
  66. return 60.0f;
  67. }
  68. float AP_Proximity_TeraRangerTowerEvo::distance_min() const
  69. {
  70. return 0.50f;
  71. }
  72. void AP_Proximity_TeraRangerTowerEvo::initialise_modes()
  73. {
  74. if((AP_HAL::millis() - _last_request_sent_ms) < _mode_request_delay) {
  75. return;
  76. }
  77. if (_current_init_state == InitState_Printout) {
  78. set_mode(BINARY_MODE, 4);
  79. } else if (_current_init_state == InitState_Sequence) {
  80. //set tower mode - 4 sensors are triggered at once with 90 deg angle between each sensor
  81. set_mode(TOWER_MODE, 4);
  82. } else if (_current_init_state == InitState_Rate) {
  83. //set update rate of the sensor.
  84. set_mode(REFRESH_100_HZ, 5);
  85. } else if (_current_init_state == InitState_StreamStart) {
  86. set_mode(ACTIVATE_STREAM, 5);
  87. }
  88. }
  89. void AP_Proximity_TeraRangerTowerEvo::set_mode(const uint8_t *c, int length)
  90. {
  91. uart->write(c, length);
  92. _last_request_sent_ms = AP_HAL::millis();
  93. }
  94. // check for replies from sensor, returns true if at least one message was processed
  95. bool AP_Proximity_TeraRangerTowerEvo::read_sensor_data()
  96. {
  97. if (uart == nullptr) {
  98. return false;
  99. }
  100. uint16_t message_count = 0;
  101. int16_t nbytes = uart->available();
  102. if(_current_init_state != InitState_Finished && nbytes == 4) {
  103. //Increment _current_init_state only when we receive 4 ack bytes
  104. switch (_current_init_state) {
  105. case InitState_Printout:
  106. _current_init_state = InitState_Sequence;
  107. break;
  108. case InitState_Sequence:
  109. _current_init_state = InitState_Rate;
  110. break;
  111. case InitState_Rate:
  112. _current_init_state = InitState_StreamStart;
  113. break;
  114. case InitState_StreamStart:
  115. _current_init_state = InitState_Finished;
  116. break;
  117. case InitState_Finished:
  118. break;
  119. }
  120. }
  121. while (nbytes-- > 0) {
  122. char c = uart->read();
  123. if (c == 'T' ) {
  124. buffer_count = 0;
  125. }
  126. buffer[buffer_count++] = c;
  127. // we should always read 19 bytes THxxxxxxxxxxxxxxxxMC
  128. if (buffer_count >= 20){
  129. buffer_count = 0;
  130. //check if message has right CRC
  131. if (crc_crc8(buffer, 19) == buffer[19]){
  132. update_sector_data(0, UINT16_VALUE(buffer[2], buffer[3])); // d1
  133. update_sector_data(45, UINT16_VALUE(buffer[4], buffer[5])); // d2
  134. update_sector_data(90, UINT16_VALUE(buffer[6], buffer[7])); // d3
  135. update_sector_data(135, UINT16_VALUE(buffer[8], buffer[9])); // d4
  136. update_sector_data(180, UINT16_VALUE(buffer[10], buffer[11])); // d5
  137. update_sector_data(225, UINT16_VALUE(buffer[12], buffer[13])); // d6
  138. update_sector_data(270, UINT16_VALUE(buffer[14], buffer[15])); // d7
  139. update_sector_data(315, UINT16_VALUE(buffer[16], buffer[17])); // d8
  140. message_count++;
  141. }
  142. }
  143. }
  144. return (message_count > 0);
  145. }
  146. // process reply
  147. void AP_Proximity_TeraRangerTowerEvo::update_sector_data(int16_t angle_deg, uint16_t distance_cm)
  148. {
  149. uint8_t sector;
  150. if (convert_angle_to_sector(angle_deg, sector)) {
  151. _angle[sector] = angle_deg;
  152. _distance[sector] = ((float) distance_cm) / 1000;
  153. //check for target too far, target too close and sensor not connected
  154. _distance_valid[sector] = distance_cm != 0xffff && distance_cm != 0x0000 && distance_cm != 0x0001;
  155. _last_distance_received_ms = AP_HAL::millis();
  156. // update boundary used for avoidance
  157. update_boundary_for_sector(sector, true);
  158. }
  159. }