mirror of https://github.com/ArduPilot/ardupilot
AP_RangeFinder: use single precision string to float
This commit is contained in:
parent
092c20b3a7
commit
5898dc757c
|
@ -67,7 +67,7 @@ bool AP_RangeFinder_LightWareSerial::get_reading(uint16_t &reading_cm)
|
||||||
char c = uart->read();
|
char c = uart->read();
|
||||||
if (c == '\r') {
|
if (c == '\r') {
|
||||||
linebuf[linebuf_len] = 0;
|
linebuf[linebuf_len] = 0;
|
||||||
const float dist = (float)atof(linebuf);
|
const float dist = strtof(linebuf, NULL);
|
||||||
if (!is_negative(dist)) {
|
if (!is_negative(dist)) {
|
||||||
sum += dist;
|
sum += dist;
|
||||||
valid_count++;
|
valid_count++;
|
||||||
|
|
|
@ -170,12 +170,12 @@ bool AP_RangeFinder_NMEA::decode_latest_term()
|
||||||
if (_sentence_type == SONAR_DBT) {
|
if (_sentence_type == SONAR_DBT) {
|
||||||
// parse DBT messages
|
// parse DBT messages
|
||||||
if (_term_number == 3) {
|
if (_term_number == 3) {
|
||||||
_distance_m = atof(_term);
|
_distance_m = strtof(_term, NULL);
|
||||||
}
|
}
|
||||||
} else if (_sentence_type == SONAR_DPT) {
|
} else if (_sentence_type == SONAR_DPT) {
|
||||||
// parse DPT messages
|
// parse DPT messages
|
||||||
if (_term_number == 1) {
|
if (_term_number == 1) {
|
||||||
_distance_m = atof(_term);
|
_distance_m = strtof(_term, NULL);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -108,7 +108,7 @@ bool AP_RangeFinder_Wasp::get_reading(uint16_t &reading_cm) {
|
||||||
if (isalpha(linebuf[0])) {
|
if (isalpha(linebuf[0])) {
|
||||||
parse_response();
|
parse_response();
|
||||||
} else {
|
} else {
|
||||||
float read_value = (float)atof(linebuf);
|
float read_value = strtof(linebuf, NULL);
|
||||||
if (read_value > 0) {
|
if (read_value > 0) {
|
||||||
sum += read_value;
|
sum += read_value;
|
||||||
count++;
|
count++;
|
||||||
|
|
Loading…
Reference in New Issue