From 5ea3415a41169ffe9874b4644783e9a06bf32144 Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Mon, 3 Oct 2022 17:52:29 +0100 Subject: [PATCH] AP_HAL_SITL: allow SITL sketches to run allow sketchname to be set --- libraries/AP_HAL_SITL/SITL_cmdline.cpp | 17 +++++++++++------ libraries/AP_HAL_SITL/UARTDriver.cpp | 2 +- 2 files changed, 12 insertions(+), 7 deletions(-) diff --git a/libraries/AP_HAL_SITL/SITL_cmdline.cpp b/libraries/AP_HAL_SITL/SITL_cmdline.cpp index f8e4dbc577..8b80632140 100644 --- a/libraries/AP_HAL_SITL/SITL_cmdline.cpp +++ b/libraries/AP_HAL_SITL/SITL_cmdline.cpp @@ -206,6 +206,7 @@ void SITL_State::_parse_command_line(int argc, char * const argv[]) // default to CMAC const char *home_str = nullptr; const char *model_str = nullptr; + const char *vehicle_str = SKETCH; _use_fg_view = true; char *autotest_dir = nullptr; _fg_address = "127.0.0.1"; @@ -337,6 +338,7 @@ void SITL_State::_parse_command_line(int argc, char * const argv[]) #if STORAGE_USE_FRAM {"set-storage-fram-enabled", true, 0, CMDLINE_SET_STORAGE_FRAM_ENABLED}, #endif + {"vehicle", true, 0, 'v'}, {0, false, 0, 0} }; @@ -361,7 +363,7 @@ void SITL_State::_parse_command_line(int argc, char * const argv[]) bool wiping_storage = false; - GetOptLong gopt(argc, argv, "hwus:r:CI:P:SO:M:F:c:", + GetOptLong gopt(argc, argv, "hwus:r:CI:P:SO:M:F:c:v:", options); while (!is_replay && (opt = gopt.getoption()) != -1) { switch (opt) { @@ -420,6 +422,9 @@ void SITL_State::_parse_command_line(int argc, char * const argv[]) case 'F': _fg_address = gopt.optarg; break; + case 'v': + vehicle_str = gopt.optarg; + break; case CMDLINE_GIMBAL: enable_gimbal = true; break; @@ -590,20 +595,20 @@ void SITL_State::_parse_command_line(int argc, char * const argv[]) hal.set_wipe_storage(wiping_storage); } - fprintf(stdout, "Starting sketch '%s'\n", SKETCH); + fprintf(stdout, "Starting sketch '%s'\n", vehicle_str); - if (strcmp(SKETCH, "ArduCopter") == 0) { + if (strcmp(vehicle_str, "ArduCopter") == 0) { _vehicle = ArduCopter; - } else if (strcmp(SKETCH, "Rover") == 0) { + } else if (strcmp(vehicle_str, "Rover") == 0) { _vehicle = Rover; // set right default throttle for rover (allowing for reverse) pwm_input[2] = 1500; - } else if (strcmp(SKETCH, "ArduSub") == 0) { + } else if (strcmp(vehicle_str, "ArduSub") == 0) { _vehicle = ArduSub; for(uint8_t i = 0; i < 8; i++) { pwm_input[i] = 1500; } - } else if (strcmp(SKETCH, "Blimp") == 0) { + } else if (strcmp(vehicle_str, "Blimp") == 0) { _vehicle = Blimp; for(uint8_t i = 0; i < 8; i++) { pwm_input[i] = 1500; diff --git a/libraries/AP_HAL_SITL/UARTDriver.cpp b/libraries/AP_HAL_SITL/UARTDriver.cpp index 02c3631147..38184208ea 100644 --- a/libraries/AP_HAL_SITL/UARTDriver.cpp +++ b/libraries/AP_HAL_SITL/UARTDriver.cpp @@ -91,7 +91,7 @@ void UARTDriver::begin(uint32_t baud, uint16_t rxSpace, uint16_t txSpace) char *devtype = strtok_r(s, ":", &saveptr); char *args1 = strtok_r(nullptr, ":", &saveptr); char *args2 = strtok_r(nullptr, ":", &saveptr); -#if !defined(HAL_BUILD_AP_PERIPH) +#if APM_BUILD_COPTER_OR_HELI || APM_BUILD_TYPE(APM_BUILD_ArduPlane) if (_portNumber == 2 && AP::sitl()->adsb_plane_count >= 0) { // this is ordinarily port 5762. The ADSB simulation assumed // this port, so if enabled we assume we'll be doing ADSB...