mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
HAL_SITL: default model for replay
This commit is contained in:
parent
85aa64780c
commit
f966e92d99
@ -272,6 +272,11 @@ void SITL_State::_parse_command_line(int argc, char * const argv[])
|
|||||||
{0, false, 0, 0}
|
{0, false, 0, 0}
|
||||||
};
|
};
|
||||||
|
|
||||||
|
#if APM_BUILD_TYPE(APM_BUILD_Replay)
|
||||||
|
model_str = "quad";
|
||||||
|
HALSITL::UARTDriver::_console = true;
|
||||||
|
#endif
|
||||||
|
|
||||||
if (asprintf(&autotest_dir, SKETCHBOOK "/Tools/autotest") <= 0) {
|
if (asprintf(&autotest_dir, SKETCHBOOK "/Tools/autotest") <= 0) {
|
||||||
AP_HAL::panic("out of memory");
|
AP_HAL::panic("out of memory");
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user