diff --git a/libraries/AP_Generator/AP_Generator_IE_2400.cpp b/libraries/AP_Generator/AP_Generator_IE_2400.cpp index 01119f759c..344d86d349 100644 --- a/libraries/AP_Generator/AP_Generator_IE_2400.cpp +++ b/libraries/AP_Generator/AP_Generator_IE_2400.cpp @@ -77,12 +77,12 @@ void AP_Generator_IE_2400::decode_latest_term() switch (_term_number) { case 1: // Float - _parsed.tank_bar = atof(_term); + _parsed.tank_bar = strtof(_term, NULL); break; case 2: // Float - _parsed.battery_volt = atof(_term); + _parsed.battery_volt = strtof(_term, NULL); break; case 3: diff --git a/libraries/AP_Generator/AP_Generator_IE_650_800.cpp b/libraries/AP_Generator/AP_Generator_IE_650_800.cpp index b9319a2c6e..cee3511309 100644 --- a/libraries/AP_Generator/AP_Generator_IE_650_800.cpp +++ b/libraries/AP_Generator/AP_Generator_IE_650_800.cpp @@ -61,7 +61,7 @@ void AP_Generator_IE_650_800::decode_latest_term() switch (_term_number) { case 1: - _parsed.tank_pct = atof(_term); + _parsed.tank_pct = strtof(_term, NULL); // Out of range values if (_parsed.tank_pct > 100.0f || _parsed.tank_pct < 0.0f) { _data_valid = false; @@ -69,7 +69,7 @@ void AP_Generator_IE_650_800::decode_latest_term() break; case 2: - _parsed.battery_pct = atof(_term); + _parsed.battery_pct = strtof(_term, NULL); // Out of range values if (_parsed.battery_pct > 100.0f || _parsed.battery_pct < 0.0f) { _data_valid = false;