mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
AP_Generator: atof to strtof
This commit is contained in:
parent
17e8ea0136
commit
34f5b800b6
@ -77,12 +77,12 @@ void AP_Generator_IE_2400::decode_latest_term()
|
|||||||
switch (_term_number) {
|
switch (_term_number) {
|
||||||
case 1:
|
case 1:
|
||||||
// Float
|
// Float
|
||||||
_parsed.tank_bar = atof(_term);
|
_parsed.tank_bar = strtof(_term, NULL);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case 2:
|
case 2:
|
||||||
// Float
|
// Float
|
||||||
_parsed.battery_volt = atof(_term);
|
_parsed.battery_volt = strtof(_term, NULL);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case 3:
|
case 3:
|
||||||
|
@ -61,7 +61,7 @@ void AP_Generator_IE_650_800::decode_latest_term()
|
|||||||
|
|
||||||
switch (_term_number) {
|
switch (_term_number) {
|
||||||
case 1:
|
case 1:
|
||||||
_parsed.tank_pct = atof(_term);
|
_parsed.tank_pct = strtof(_term, NULL);
|
||||||
// Out of range values
|
// Out of range values
|
||||||
if (_parsed.tank_pct > 100.0f || _parsed.tank_pct < 0.0f) {
|
if (_parsed.tank_pct > 100.0f || _parsed.tank_pct < 0.0f) {
|
||||||
_data_valid = false;
|
_data_valid = false;
|
||||||
@ -69,7 +69,7 @@ void AP_Generator_IE_650_800::decode_latest_term()
|
|||||||
break;
|
break;
|
||||||
|
|
||||||
case 2:
|
case 2:
|
||||||
_parsed.battery_pct = atof(_term);
|
_parsed.battery_pct = strtof(_term, NULL);
|
||||||
// Out of range values
|
// Out of range values
|
||||||
if (_parsed.battery_pct > 100.0f || _parsed.battery_pct < 0.0f) {
|
if (_parsed.battery_pct > 100.0f || _parsed.battery_pct < 0.0f) {
|
||||||
_data_valid = false;
|
_data_valid = false;
|
||||||
|
Loading…
Reference in New Issue
Block a user