mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_HAL_SITL: update parameter with using command line speedup option
This commit is contained in:
parent
36d8ef1971
commit
7d9c947b9b
@ -232,6 +232,9 @@ void SITL_State::_parse_command_line(int argc, char * const argv[])
|
||||
break;
|
||||
case 's':
|
||||
speedup = strtof(gopt.optarg, nullptr);
|
||||
char speedup_string[18];
|
||||
snprintf(speedup_string, sizeof(speedup_string), "SIM_SPEEDUP=%s", gopt.optarg);
|
||||
_set_param_default(speedup_string);
|
||||
break;
|
||||
case 'r':
|
||||
_framerate = (unsigned)atoi(gopt.optarg);
|
||||
|
Loading…
Reference in New Issue
Block a user