From c7fce7568e5447b6f12013a57139942c902a9b4d Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 27 Oct 2019 22:51:45 +1100 Subject: [PATCH] AP_Proximity: use strtof instead of atof we don't need double precision --- libraries/AP_Proximity/AP_Proximity_LightWareSF40C.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_Proximity/AP_Proximity_LightWareSF40C.cpp b/libraries/AP_Proximity/AP_Proximity_LightWareSF40C.cpp index 9f44882b4e..9fc1e3cf64 100644 --- a/libraries/AP_Proximity/AP_Proximity_LightWareSF40C.cpp +++ b/libraries/AP_Proximity/AP_Proximity_LightWareSF40C.cpp @@ -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;