APM:Libraries
AP_RangeFinder_NMEA.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 <ctype.h>
20 #include "AP_RangeFinder_NMEA.h"
21 
22 extern const AP_HAL::HAL& hal;
23 
24 // constructor initialises the rangefinder
25 // Note this is called after detect() returns true, so we
26 // already know that we should setup the rangefinder
29  uint8_t serial_instance) :
30  AP_RangeFinder_Backend(_state),
31  _distance_m(-1.0f)
32 {
33  uart = serial_manager.find_serial(AP_SerialManager::SerialProtocol_Rangefinder, serial_instance);
34  if (uart != nullptr) {
35  uart->begin(serial_manager.find_baudrate(AP_SerialManager::SerialProtocol_Rangefinder, serial_instance));
36  }
37 }
38 
39 // detect if a NMEA rangefinder by looking to see if the user has configured it
41 {
42  return serial_manager.find_serial(AP_SerialManager::SerialProtocol_Rangefinder, serial_instance) != nullptr;
43 }
44 
45 // update the state of the sensor
47 {
48  uint32_t now = AP_HAL::millis();
50  // update range_valid state based on distance measured
51  _last_reading_ms = now;
52  update_status();
53  } else if ((now - _last_reading_ms) > 3000) {
55  }
56 }
57 
58 // return last value measured by sensor
59 bool AP_RangeFinder_NMEA::get_reading(uint16_t &reading_cm)
60 {
61  if (uart == nullptr) {
62  return false;
63  }
64 
65  // read any available lines from the lidar
66  float sum = 0.0f;
67  uint16_t count = 0;
68  int16_t nbytes = uart->available();
69  while (nbytes-- > 0) {
70  char c = uart->read();
71  if (decode(c)) {
72  sum += _distance_m;
73  count++;
74  }
75  }
76 
77  // return false on failure
78  if (count == 0) {
79  return false;
80  }
81 
82  // return average of all measurements
83  reading_cm = 100.0f * sum / count;
84  return true;
85 }
86 
87 // add a single character to the buffer and attempt to decode
88 // returns true if a complete sentence was successfully decoded
90 {
91  switch (c) {
92  case ',':
93  // end of a term, add to checksum
94  _checksum ^= c;
96  case '\r':
97  case '\n':
98  case '*':
99  {
100  // null terminate and decode latest term
101  _term[_term_offset] = 0;
102  bool valid_sentence = decode_latest_term();
103 
104  // move onto next term
105  _term_number++;
106  _term_offset = 0;
107  _term_is_checksum = (c == '*');
108  return valid_sentence;
109  }
110 
111  case '$': // sentence begin
113  _term_number = 0;
114  _term_offset = 0;
115  _checksum = 0;
116  _term_is_checksum = false;
117  _distance_m = -1.0f;
118  return false;
119  }
120 
121  // ordinary characters are added to term
122  if (_term_offset < sizeof(_term) - 1)
123  _term[_term_offset++] = c;
124  if (!_term_is_checksum)
125  _checksum ^= c;
126 
127  return false;
128 }
129 
130 // decode the most recently consumed term
131 // returns true if new sentence has just passed checksum test and is validated
133 {
134  // handle the last term in a message
135  if (_term_is_checksum) {
136  uint8_t checksum = 16 * char_to_hex(_term[0]) + char_to_hex(_term[1]);
137  return ((checksum == _checksum) &&
140  }
141 
142  // the first term determines the sentence type
143  if (_term_number == 0) {
144  // the first two letters of the NMEA term are the talker ID.
145  // we accept any two characters here.
146  if (_term[0] < 'A' || _term[0] > 'Z' ||
147  _term[1] < 'A' || _term[1] > 'Z') {
149  return false;
150  }
151  const char *term_type = &_term[2];
152  if (strcmp(term_type, "DBT") == 0) {
154  } else if (strcmp(term_type, "DPT") == 0) {
156  } else {
158  }
159  return false;
160  }
161 
162  if (_sentence_type == SONAR_DBT) {
163  // parse DBT messages
164  if (_term_number == 3) {
165  _distance_m = atof(_term);
166  }
167  } else if (_sentence_type == SONAR_DPT) {
168  // parse DPT messages
169  if (_term_number == 1) {
170  _distance_m = atof(_term);
171  }
172  }
173 
174  return false;
175 }
176 
177 // return the numeric value of an ascii hex character
179 {
180  if (a >= 'A' && a <= 'F')
181  return a - 'A' + 10;
182  else if (a >= 'a' && a <= 'f')
183  return a - 'a' + 10;
184  else
185  return a - '0';
186 }
static AP_SerialManager serial_manager
Definition: AHRS_Test.cpp:24
#define FALLTHROUGH
Definition: AP_Common.h:50
virtual void begin(uint32_t baud)=0
uint32_t find_baudrate(enum SerialProtocol protocol, uint8_t instance) const
void update(void) override
sentence_types _sentence_type
bool get_reading(uint16_t &reading_cm)
static int16_t char_to_hex(char a)
#define f(i)
AP_HAL::UARTDriver * uart
uint32_t millis()
Definition: system.cpp:157
AP_RangeFinder_NMEA(RangeFinder::RangeFinder_State &_state, AP_SerialManager &serial_manager, uint8_t serial_instance)
virtual int16_t read()=0
static bool detect(AP_SerialManager &serial_manager, uint8_t serial_instance)
virtual uint32_t available()=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
bool is_negative(const T fVal1)
Definition: AP_Math.h:61
void set_status(RangeFinder::RangeFinder_Status status)
RangeFinder::RangeFinder_State & state
AP_HAL::UARTDriver * find_serial(enum SerialProtocol protocol, uint8_t instance) const