mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_SITL: compiler warning: float to double promotion
- replace atof() with strtof() for the correct return time
This commit is contained in:
parent
d9b2ef43fa
commit
48ae0d645d
|
@ -32,7 +32,7 @@ void SITL_State::_set_param_default(const char *parm)
|
|||
printf("Please specify parameter as NAME=VALUE");
|
||||
exit(1);
|
||||
}
|
||||
float value = atof(p+1);
|
||||
float value = strtof(p+1, NULL);
|
||||
*p = 0;
|
||||
enum ap_var_type var_type;
|
||||
AP_Param *vp = AP_Param::find(pdup, &var_type);
|
||||
|
|
|
@ -176,7 +176,7 @@ void SITL_State::_parse_command_line(int argc, char * const argv[])
|
|||
model_str = gopt.optarg;
|
||||
break;
|
||||
case 's':
|
||||
speedup = atof(gopt.optarg);
|
||||
speedup = strtof(gopt.optarg, NULL);
|
||||
break;
|
||||
case 'F':
|
||||
_fdm_address = gopt.optarg;
|
||||
|
|
Loading…
Reference in New Issue