AP_HAL_SITL: update parameter with using command line speedup option

This commit is contained in:
Pierre Kancir 2018-08-27 11:40:23 +02:00 committed by Peter Barker
parent 36d8ef1971
commit 7d9c947b9b

View File

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