|
|
|
@ -62,27 +62,22 @@ bool AP_RangeFinder_NMEA::get_reading(uint16_t &reading_cm)
@@ -62,27 +62,22 @@ bool AP_RangeFinder_NMEA::get_reading(uint16_t &reading_cm)
|
|
|
|
|
if (uart == nullptr) { |
|
|
|
|
return false; |
|
|
|
|
} |
|
|
|
|
bool ret = false; |
|
|
|
|
|
|
|
|
|
// read any available lines from the lidar
|
|
|
|
|
float sum = 0.0f; |
|
|
|
|
uint16_t count = 0; |
|
|
|
|
int16_t nbytes = uart->available(); |
|
|
|
|
while (nbytes-- > 0) { |
|
|
|
|
char c = uart->read(); |
|
|
|
|
uint8_t c = uart->read(); |
|
|
|
|
if (decode(c)) { |
|
|
|
|
sum += _distance_m; |
|
|
|
|
count++; |
|
|
|
|
ret = true; |
|
|
|
|
_sonar_deep = radar_data[1]; |
|
|
|
|
_sonar_voltage = radar_data[5]; |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// return false on failure
|
|
|
|
|
if (count == 0) { |
|
|
|
|
return false; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// return average of all measurements
|
|
|
|
|
reading_cm = 100.0f * sum / count; |
|
|
|
|
return true; |
|
|
|
|
reading_cm = 100.0f * _sonar_deep; |
|
|
|
|
return ret; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// add a single character to the buffer and attempt to decode
|
|
|
|
@ -90,42 +85,24 @@ bool AP_RangeFinder_NMEA::get_reading(uint16_t &reading_cm)
@@ -90,42 +85,24 @@ bool AP_RangeFinder_NMEA::get_reading(uint16_t &reading_cm)
|
|
|
|
|
bool AP_RangeFinder_NMEA::decode(char c) |
|
|
|
|
{ |
|
|
|
|
switch (c) { |
|
|
|
|
case ',': |
|
|
|
|
// end of a term, add to checksum
|
|
|
|
|
_checksum ^= c; |
|
|
|
|
FALLTHROUGH; |
|
|
|
|
case '\r': |
|
|
|
|
// case '\r':
|
|
|
|
|
case '\n': |
|
|
|
|
case '*': |
|
|
|
|
{ |
|
|
|
|
// 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; |
|
|
|
|
decode_step = 0; |
|
|
|
|
memset(_term,0,sizeof(_term)); |
|
|
|
|
return true; |
|
|
|
|
case ' ': |
|
|
|
|
if(decode_step < 8){ |
|
|
|
|
radar_data[decode_step] = atof(_term); |
|
|
|
|
_term_offset = 0; |
|
|
|
|
_checksum = 0; |
|
|
|
|
_term_is_checksum = false; |
|
|
|
|
_distance_m = -1.0f; |
|
|
|
|
return false; |
|
|
|
|
decode_step += 1; |
|
|
|
|
memset(_term,0,sizeof(_term)); |
|
|
|
|
} |
|
|
|
|
break; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// ordinary characters are added to term
|
|
|
|
|
if (_term_offset < sizeof(_term) - 1) { |
|
|
|
|
if (_term_offset < sizeof(_term) - 1) |
|
|
|
|
_term[_term_offset++] = c; |
|
|
|
|
} |
|
|
|
|
if (!_term_is_checksum) { |
|
|
|
|
_checksum ^= c; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
return false; |
|
|
|
|
} |
|
|
|
|