2018-05-14 02:03:08 -03:00
|
|
|
/*
|
|
|
|
This program is free software: you can redistribute it and/or modify
|
|
|
|
it under the terms of the GNU General Public License as published by
|
|
|
|
the Free Software Foundation, either version 3 of the License, or
|
|
|
|
(at your option) any later version.
|
|
|
|
|
|
|
|
This program is distributed in the hope that it will be useful,
|
|
|
|
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
|
|
|
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
|
|
|
GNU General Public License for more details.
|
|
|
|
|
|
|
|
You should have received a copy of the GNU General Public License
|
|
|
|
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
|
|
|
*/
|
|
|
|
|
2019-11-01 03:19:39 -03:00
|
|
|
#include "AP_RangeFinder_NMEA.h"
|
|
|
|
|
2022-03-12 06:37:29 -04:00
|
|
|
#if AP_RANGEFINDER_NMEA_ENABLED
|
|
|
|
|
2018-05-14 02:03:08 -03:00
|
|
|
#include <AP_HAL/AP_HAL.h>
|
|
|
|
#include <ctype.h>
|
|
|
|
|
|
|
|
extern const AP_HAL::HAL& hal;
|
|
|
|
|
|
|
|
// return last value measured by sensor
|
2021-10-18 02:45:33 -03:00
|
|
|
bool AP_RangeFinder_NMEA::get_reading(float &reading_m)
|
2018-05-14 02:03:08 -03:00
|
|
|
{
|
|
|
|
if (uart == nullptr) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
// read any available lines from the lidar
|
|
|
|
float sum = 0.0f;
|
|
|
|
uint16_t count = 0;
|
2023-11-28 18:16:22 -04:00
|
|
|
for (auto i=0; i<8192; i++) {
|
|
|
|
uint8_t c;
|
|
|
|
if (!uart->read(c)) {
|
|
|
|
break;
|
|
|
|
}
|
2018-05-14 02:03:08 -03:00
|
|
|
if (decode(c)) {
|
|
|
|
sum += _distance_m;
|
|
|
|
count++;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
// return false on failure
|
|
|
|
if (count == 0) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
// return average of all measurements
|
2021-10-18 02:45:33 -03:00
|
|
|
reading_m = sum / count;
|
2018-05-14 02:03:08 -03:00
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
2021-04-13 05:07:06 -03:00
|
|
|
// get temperature reading
|
2021-09-29 14:45:33 -03:00
|
|
|
bool AP_RangeFinder_NMEA::get_temp(float &temp) const
|
2021-04-13 05:07:06 -03:00
|
|
|
{
|
|
|
|
uint32_t now_ms = AP_HAL::millis();
|
|
|
|
if ((_temp_readtime_ms == 0) || ((now_ms - _temp_readtime_ms) > read_timeout_ms())) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
temp = _temp;
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
2018-05-14 02:03:08 -03:00
|
|
|
// add a single character to the buffer and attempt to decode
|
2021-04-13 05:07:06 -03:00
|
|
|
// returns true if a distance was successfully decoded
|
2018-05-14 02:03:08 -03:00
|
|
|
bool AP_RangeFinder_NMEA::decode(char c)
|
|
|
|
{
|
|
|
|
switch (c) {
|
|
|
|
case ',':
|
|
|
|
// end of a term, add to checksum
|
|
|
|
_checksum ^= c;
|
|
|
|
FALLTHROUGH;
|
|
|
|
case '\r':
|
|
|
|
case '\n':
|
|
|
|
case '*':
|
|
|
|
{
|
2020-07-20 19:33:39 -03:00
|
|
|
if (_sentence_done) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
2018-05-14 02:03:08 -03:00
|
|
|
// null terminate and decode latest term
|
|
|
|
_term[_term_offset] = 0;
|
|
|
|
bool valid_sentence = decode_latest_term();
|
|
|
|
|
|
|
|
// move onto next term
|
|
|
|
_term_number++;
|
|
|
|
_term_offset = 0;
|
|
|
|
_term_is_checksum = (c == '*');
|
|
|
|
return valid_sentence;
|
|
|
|
}
|
|
|
|
|
|
|
|
case '$': // sentence begin
|
|
|
|
_sentence_type = SONAR_UNKNOWN;
|
|
|
|
_term_number = 0;
|
|
|
|
_term_offset = 0;
|
|
|
|
_checksum = 0;
|
|
|
|
_term_is_checksum = false;
|
|
|
|
_distance_m = -1.0f;
|
2020-07-20 19:33:39 -03:00
|
|
|
_sentence_done = false;
|
2018-05-14 02:03:08 -03:00
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
// ordinary characters are added to term
|
2019-08-22 16:04:17 -03:00
|
|
|
if (_term_offset < sizeof(_term) - 1) {
|
2018-05-14 02:03:08 -03:00
|
|
|
_term[_term_offset++] = c;
|
2019-08-22 16:04:17 -03:00
|
|
|
}
|
|
|
|
if (!_term_is_checksum) {
|
2018-05-14 02:03:08 -03:00
|
|
|
_checksum ^= c;
|
2019-08-22 16:04:17 -03:00
|
|
|
}
|
2018-05-14 02:03:08 -03:00
|
|
|
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
// decode the most recently consumed term
|
2021-04-13 05:07:06 -03:00
|
|
|
// returns true if new distance sentence has just passed checksum test and is validated
|
2018-05-14 02:03:08 -03:00
|
|
|
bool AP_RangeFinder_NMEA::decode_latest_term()
|
|
|
|
{
|
|
|
|
// handle the last term in a message
|
|
|
|
if (_term_is_checksum) {
|
2020-07-20 19:33:39 -03:00
|
|
|
_sentence_done = true;
|
2019-07-12 05:52:38 -03:00
|
|
|
uint8_t nibble_high = 0;
|
|
|
|
uint8_t nibble_low = 0;
|
|
|
|
if (!hex_to_uint8(_term[0], nibble_high) || !hex_to_uint8(_term[1], nibble_low)) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
const uint8_t checksum = (nibble_high << 4u) | nibble_low;
|
2021-04-13 05:07:06 -03:00
|
|
|
if (checksum == _checksum) {
|
2021-10-15 09:04:22 -03:00
|
|
|
if ((_sentence_type == SONAR_DBT || _sentence_type == SONAR_DPT || _sentence_type == SONAR_HDED) && !is_negative(_distance_m)) {
|
2021-04-13 05:07:06 -03:00
|
|
|
// return true if distance is valid
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
if (_sentence_type == SONAR_MTW) {
|
|
|
|
_temp = _temp_unvalidated;
|
|
|
|
_temp_readtime_ms = AP_HAL::millis();
|
|
|
|
// return false because this is not a distance
|
|
|
|
// temperature is accessed via separate accessor
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
return false;
|
2018-05-14 02:03:08 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
// the first term determines the sentence type
|
|
|
|
if (_term_number == 0) {
|
|
|
|
// the first two letters of the NMEA term are the talker ID.
|
|
|
|
// we accept any two characters here.
|
|
|
|
if (_term[0] < 'A' || _term[0] > 'Z' ||
|
|
|
|
_term[1] < 'A' || _term[1] > 'Z') {
|
|
|
|
_sentence_type = SONAR_UNKNOWN;
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
const char *term_type = &_term[2];
|
|
|
|
if (strcmp(term_type, "DBT") == 0) {
|
|
|
|
_sentence_type = SONAR_DBT;
|
|
|
|
} else if (strcmp(term_type, "DPT") == 0) {
|
|
|
|
_sentence_type = SONAR_DPT;
|
2021-04-13 05:07:06 -03:00
|
|
|
} else if (strcmp(term_type, "MTW") == 0) {
|
|
|
|
_sentence_type = SONAR_MTW;
|
2021-10-15 09:04:22 -03:00
|
|
|
} else if (strcmp(term_type, "ED") == 0) {
|
|
|
|
_sentence_type = SONAR_HDED;
|
2018-05-14 02:03:08 -03:00
|
|
|
} else {
|
|
|
|
_sentence_type = SONAR_UNKNOWN;
|
|
|
|
}
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
if (_sentence_type == SONAR_DBT) {
|
|
|
|
// parse DBT messages
|
|
|
|
if (_term_number == 3) {
|
2019-10-27 08:47:51 -03:00
|
|
|
_distance_m = strtof(_term, NULL);
|
2018-05-14 02:03:08 -03:00
|
|
|
}
|
|
|
|
} else if (_sentence_type == SONAR_DPT) {
|
|
|
|
// parse DPT messages
|
|
|
|
if (_term_number == 1) {
|
2019-10-27 08:47:51 -03:00
|
|
|
_distance_m = strtof(_term, NULL);
|
2018-05-14 02:03:08 -03:00
|
|
|
}
|
2021-04-13 05:07:06 -03:00
|
|
|
} else if (_sentence_type == SONAR_MTW) {
|
|
|
|
// parse MTW (mean water temperature) messages
|
|
|
|
if (_term_number == 1) {
|
|
|
|
_temp_unvalidated = strtof(_term, NULL);
|
|
|
|
}
|
2021-10-15 09:04:22 -03:00
|
|
|
} else if (_sentence_type == SONAR_HDED) {
|
|
|
|
// parse HDED (Hondex custom message)
|
|
|
|
if (_term_number == 4) {
|
|
|
|
_distance_m = strtof(_term, NULL);
|
|
|
|
}
|
2018-05-14 02:03:08 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
return false;
|
|
|
|
}
|
2022-03-12 06:37:29 -04:00
|
|
|
|
|
|
|
#endif // AP_RANGEFINDER_NMEA_ENABLED
|