From 6a862c6e249f4e5297daf2b892665911ad7114a1 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 20 Feb 2018 12:33:14 +1100 Subject: [PATCH] SITL: make home location parsing verbose Given we don't fail to start SITL if the home location fails to parse, we should at least make the user very aware that their home location string is bad. This commit makes failures verbose, and outputs the parsed location values rather than regurgitating the location string the user supplied; it was very misleading in that the location could simply fail to parse and thus be unused. --- libraries/AP_HAL_SITL/SITL_cmdline.cpp | 2 +- libraries/SITL/SIM_Aircraft.cpp | 15 ++++++++++++++- 2 files changed, 15 insertions(+), 2 deletions(-) diff --git a/libraries/AP_HAL_SITL/SITL_cmdline.cpp b/libraries/AP_HAL_SITL/SITL_cmdline.cpp index 8c7e9daddc..998b9232e5 100644 --- a/libraries/AP_HAL_SITL/SITL_cmdline.cpp +++ b/libraries/AP_HAL_SITL/SITL_cmdline.cpp @@ -343,13 +343,13 @@ void SITL_State::_parse_command_line(int argc, char * const argv[]) for (uint8_t i=0; i < ARRAY_SIZE(model_constructors); i++) { if (strncasecmp(model_constructors[i].name, model_str, strlen(model_constructors[i].name)) == 0) { + printf("Creating model %s at speed %.1f\n", model_str, speedup); sitl_model = model_constructors[i].constructor(home_str, model_str); sitl_model->set_interface_ports(_simulator_address, _simulator_port_in, _simulator_port_out); sitl_model->set_speedup(speedup); sitl_model->set_instance(_instance); sitl_model->set_autotest_dir(autotest_dir); _synthetic_clock_mode = true; - printf("Started model %s at %s at speed %.1f\n", model_str, home_str, speedup); break; } } diff --git a/libraries/SITL/SIM_Aircraft.cpp b/libraries/SITL/SIM_Aircraft.cpp index 7c2e363fd2..1d8264a0f2 100644 --- a/libraries/SITL/SIM_Aircraft.cpp +++ b/libraries/SITL/SIM_Aircraft.cpp @@ -62,7 +62,15 @@ Aircraft::Aircraft(const char *home_str, const char *frame_str) : { // make the SIM_* variables available to simulator backends sitl = (SITL *)AP_Param::find_object("SIM_"); - parse_home(home_str, home, home_yaw); + + if (!parse_home(home_str, home, home_yaw)) { + ::printf("Failed to parse home string (%s). Should be LAT,LON,ALT,HDG e.g. 37.4003371,-122.0800351,0,353\n", home_str); + } + ::printf("Home: %f %f alt=%fm hdg=%f\n", + home.lat*1e-7, + home.lng*1e-7, + home.alt*0.01, + home_yaw); location = home; ground_level = home.alt * 0.01f; @@ -90,26 +98,31 @@ bool Aircraft::parse_home(const char *home_str, Location &loc, float &yaw_degree char *s = strdup(home_str); if (!s) { free(s); + ::printf("No home string supplied\n"); return false; } char *lat_s = strtok_r(s, ",", &saveptr); if (!lat_s) { free(s); + ::printf("Failed to parse latitude\n"); return false; } char *lon_s = strtok_r(nullptr, ",", &saveptr); if (!lon_s) { free(s); + ::printf("Failed to parse longitude\n"); return false; } char *alt_s = strtok_r(nullptr, ",", &saveptr); if (!alt_s) { free(s); + ::printf("Failed to parse altitude\n"); return false; } char *yaw_s = strtok_r(nullptr, ",", &saveptr); if (!yaw_s) { free(s); + ::printf("Failed to parse yaw\n"); return false; }