From 59c84c637e693ecc6ba0e4a3c934492f8b6bd7de Mon Sep 17 00:00:00 2001 From: Pierre Kancir Date: Wed, 21 Sep 2016 19:02:15 +0200 Subject: [PATCH] SITL: make fg view optional --- libraries/AP_HAL_SITL/SITL_State.cpp | 7 +++++-- libraries/AP_HAL_SITL/SITL_State.h | 1 + libraries/AP_HAL_SITL/SITL_cmdline.cpp | 6 +++++- 3 files changed, 11 insertions(+), 3 deletions(-) diff --git a/libraries/AP_HAL_SITL/SITL_State.cpp b/libraries/AP_HAL_SITL/SITL_State.cpp index d2359f7aeb..03ba66933d 100644 --- a/libraries/AP_HAL_SITL/SITL_State.cpp +++ b/libraries/AP_HAL_SITL/SITL_State.cpp @@ -97,7 +97,10 @@ void SITL_State::_sitl_setup(const char *home_str) gimbal = new SITL::Gimbal(_sitl->state); } - fg_socket.connect("127.0.0.1", 5503); + if (_use_fg_view) { + fg_socket.connect("127.0.0.1", 5503); + } + } if (_synthetic_clock_mode) { @@ -295,7 +298,7 @@ void SITL_State::_fdm_input_local(void) adsb->update(); } - if (_sitl) { + if (_sitl && _use_fg_view) { _output_to_flightgear(); } diff --git a/libraries/AP_HAL_SITL/SITL_State.h b/libraries/AP_HAL_SITL/SITL_State.h index 1689d87418..a35274a9fd 100644 --- a/libraries/AP_HAL_SITL/SITL_State.h +++ b/libraries/AP_HAL_SITL/SITL_State.h @@ -169,6 +169,7 @@ private: bool _synthetic_clock_mode; bool _use_rtscts; + bool _use_fg_view; const char *_fdm_address; diff --git a/libraries/AP_HAL_SITL/SITL_cmdline.cpp b/libraries/AP_HAL_SITL/SITL_cmdline.cpp index 21d21bbb1f..6ba6a79b29 100644 --- a/libraries/AP_HAL_SITL/SITL_cmdline.cpp +++ b/libraries/AP_HAL_SITL/SITL_cmdline.cpp @@ -132,6 +132,7 @@ void SITL_State::_parse_command_line(int argc, char * const argv[]) _simin_port = 5501; _fdm_address = "127.0.0.1"; _client_address = nullptr; + _use_fg_view = false; _instance = 0; enum long_options { @@ -145,6 +146,7 @@ void SITL_State::_parse_command_line(int argc, char * const argv[]) CMDLINE_UARTE, CMDLINE_UARTF, CMDLINE_RTSCTS, + CMDLINE_FGVIEW, CMDLINE_DEFAULTS }; @@ -170,6 +172,7 @@ void SITL_State::_parse_command_line(int argc, char * const argv[]) {"autotest-dir", true, 0, CMDLINE_AUTOTESTDIR}, {"defaults", true, 0, CMDLINE_DEFAULTS}, {"rtscts", false, 0, CMDLINE_RTSCTS}, + {"fgview", false, 0, CMDLINE_FGVIEW}, {0, false, 0, 0} }; @@ -240,7 +243,8 @@ void SITL_State::_parse_command_line(int argc, char * const argv[]) case CMDLINE_UARTF: _uart_path[opt - CMDLINE_UARTA] = gopt.optarg; break; - + case CMDLINE_FGVIEW: + _use_fg_view = true; default: _usage(); exit(1);