Browse Source

AP_Proximity: use strtof instead of atof

we don't need double precision
c415-sdk
Andrew Tridgell 5 years ago
parent
commit
c7fce7568e
  1. 4
      libraries/AP_Proximity/AP_Proximity_LightWareSF40C.cpp

4
libraries/AP_Proximity/AP_Proximity_LightWareSF40C.cpp

@ -408,8 +408,8 @@ bool AP_Proximity_LightWareSF40C::process_reply() @@ -408,8 +408,8 @@ bool AP_Proximity_LightWareSF40C::process_reply()
case RequestType_DistanceMeasurement:
{
float angle_deg = (float)atof(element_buf[0]);
float distance_m = (float)atof(element_buf[1]);
float angle_deg = strtof(element_buf[0], NULL);
float distance_m = strtof(element_buf[1], NULL);
uint8_t sector;
if (convert_angle_to_sector(angle_deg, sector)) {
_angle[sector] = angle_deg;

Loading…
Cancel
Save