From 11df612c04c670ca1bb62a0fce2ff4a534f52b53 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 3 May 2015 17:48:20 +1000 Subject: [PATCH] HAL_SITL: added a table of simulator constructors --- libraries/AP_HAL_AVR_SITL/SITL_State.cpp | 27 ++++++++++++++++++++---- 1 file changed, 23 insertions(+), 4 deletions(-) diff --git a/libraries/AP_HAL_AVR_SITL/SITL_State.cpp b/libraries/AP_HAL_AVR_SITL/SITL_State.cpp index 932f4833ef..e920468fa7 100644 --- a/libraries/AP_HAL_AVR_SITL/SITL_State.cpp +++ b/libraries/AP_HAL_AVR_SITL/SITL_State.cpp @@ -22,6 +22,7 @@ #include #include +#include #ifdef __CYGWIN__ #include @@ -71,6 +72,19 @@ void SITL_State::_usage(void) fprintf(stdout, "\t-M MODEL set simulation model\n"); } +static const struct { + const char *name; + Aircraft *(*constructor)(const char *home_str, const char *frame_str); +} model_constructors[] = { + { "+", MultiCopter::create }, + { "x", MultiCopter::create }, + { "hexa", MultiCopter::create }, + { "hexax", MultiCopter::create }, + { "octa", MultiCopter::create }, + { "octa-quad", MultiCopter::create }, + { "heli", Helicopter::create } +}; + void SITL_State::_parse_command_line(int argc, char * const argv[]) { int opt; @@ -134,10 +148,15 @@ void SITL_State::_parse_command_line(int argc, char * const argv[]) } if (model_str && home_str) { - sitl_model = new MultiCopter(home_str, model_str); - sitl_model->set_speedup(speedup); - _synthetic_clock_mode = true; - printf("Started model %s at %s at speed %.1f\n", model_str, home_str, speedup); + for (uint8_t i=0; iset_speedup(speedup); + _synthetic_clock_mode = true; + printf("Started model %s at %s at speed %.1f\n", model_str, home_str, speedup); + break; + } + } } fprintf(stdout, "Starting sketch '%s'\n", SKETCH);