APM:Libraries
AP_Proximity_TeraRangerTower.cpp
Go to the documentation of this file.
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 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 
16 #include <AP_HAL/AP_HAL.h>
19 #include <AP_Math/crc.h>
20 #include <ctype.h>
21 #include <stdio.h>
22 
23 extern const AP_HAL::HAL& hal;
24 
25 /*
26  The constructor also initialises the proximity sensor. Note that this
27  constructor is not called until detect() returns true, so we
28  already know that we should setup the proximity sensor
29 */
33  AP_Proximity_Backend(_frontend, _state)
34 {
36  if (uart != nullptr) {
38  }
39 }
40 
41 // detect if a TeraRanger Tower proximity sensor is connected by looking for a configured serial port
43 {
44  AP_HAL::UARTDriver *uart = nullptr;
46  return uart != nullptr;
47 }
48 
49 // update the state of the sensor
51 {
52  if (uart == nullptr) {
53  return;
54  }
55 
56  // process incoming messages
58 
59  // check for timeout and set health status
62  } else {
64  }
65 }
66 
67 // get maximum and minimum distances (in meters) of primary sensor
69 {
70  return 4.5f;
71 }
73 {
74  return 0.20f;
75 }
76 
77 // check for replies from sensor, returns true if at least one message was processed
79 {
80  if (uart == nullptr) {
81  return false;
82  }
83 
84  uint16_t message_count = 0;
85  int16_t nbytes = uart->available();
86 
87  while (nbytes-- > 0) {
88  char c = uart->read();
89  if (c == 'T' ) {
90  buffer_count = 0;
91  }
92 
93  buffer[buffer_count++] = c;
94 
95  // we should always read 19 bytes THxxxxxxxxxxxxxxxxC
96  if (buffer_count >= 19){
97  buffer_count = 0;
98 
99  // check if message has right CRC
100  if (crc_crc8(buffer, 18) == buffer[18]){
101  uint16_t d1 = process_distance(buffer[2], buffer[3]);
102  uint16_t d2 = process_distance(buffer[4], buffer[5]);
103  uint16_t d3 = process_distance(buffer[6], buffer[7]);
104  uint16_t d4 = process_distance(buffer[8], buffer[9]);
105  uint16_t d5 = process_distance(buffer[10], buffer[11]);
106  uint16_t d6 = process_distance(buffer[12], buffer[13]);
107  uint16_t d7 = process_distance(buffer[14], buffer[15]);
108  uint16_t d8 = process_distance(buffer[16], buffer[17]);
109 
110  update_sector_data(0, d1);
111  update_sector_data(45, d8);
112  update_sector_data(90, d7);
113  update_sector_data(135, d6);
114  update_sector_data(180, d5);
115  update_sector_data(225, d4);
116  update_sector_data(270, d3);
117  update_sector_data(315, d2);
118 
119  message_count++;
120  }
121  }
122  }
123  return (message_count > 0);
124 }
125 
126 uint16_t AP_Proximity_TeraRangerTower::process_distance(uint8_t buf1, uint8_t buf2)
127 {
128  return (buf1 << 8) + buf2;
129 }
130 
131 // process reply
132 void AP_Proximity_TeraRangerTower::update_sector_data(int16_t angle_deg, uint16_t distance_cm)
133 {
134  uint8_t sector;
135  if (convert_angle_to_sector(angle_deg, sector)) {
136  _angle[sector] = angle_deg;
137  _distance[sector] = ((float) distance_cm) / 1000;
138  _distance_valid[sector] = distance_cm != 0xffff;
140  // update boundary used for avoidance
142  }
143 }
static AP_SerialManager serial_manager
Definition: AHRS_Test.cpp:24
bool _distance_valid[PROXIMITY_SECTORS_MAX]
#define PROXIMITY_TRTOWER_TIMEOUT_MS
float _angle[PROXIMITY_SECTORS_MAX]
virtual void begin(uint32_t baud)=0
void update_sector_data(int16_t angle_deg, uint16_t distance_cm)
uint8_t crc_crc8(const uint8_t *p, uint8_t len)
Definition: crc.cpp:50
void set_status(AP_Proximity::Proximity_Status status)
uint16_t process_distance(uint8_t buf1, uint8_t buf2)
uint32_t find_baudrate(enum SerialProtocol protocol, uint8_t instance) const
bool convert_angle_to_sector(float angle_degrees, uint8_t &sector) const
float _distance[PROXIMITY_SECTORS_MAX]
AP_Proximity_TeraRangerTower(AP_Proximity &_frontend, AP_Proximity::Proximity_State &_state, AP_SerialManager &serial_manager)
uint32_t millis()
Definition: system.cpp:157
virtual int16_t read()=0
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
virtual uint32_t available()=0
void update_boundary_for_sector(uint8_t sector)
static bool detect(AP_SerialManager &serial_manager)
AP_HAL::UARTDriver * find_serial(enum SerialProtocol protocol, uint8_t instance) const