AP_Proximity: use strtof instead of atof

we don't need double precision
This commit is contained in:
Andrew Tridgell 2019-10-27 22:51:45 +11:00
parent 31b0663115
commit c7fce7568e
1 changed files with 2 additions and 2 deletions

View File

@ -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;