SITL: make fg view optional

This commit is contained in:
Pierre Kancir 2016-09-21 19:02:15 +02:00 committed by Andrew Tridgell
parent bfbb275577
commit 59c84c637e
3 changed files with 11 additions and 3 deletions

View File

@ -97,9 +97,12 @@ void SITL_State::_sitl_setup(const char *home_str)
gimbal = new SITL::Gimbal(_sitl->state); gimbal = new SITL::Gimbal(_sitl->state);
} }
if (_use_fg_view) {
fg_socket.connect("127.0.0.1", 5503); fg_socket.connect("127.0.0.1", 5503);
} }
}
if (_synthetic_clock_mode) { if (_synthetic_clock_mode) {
// start with non-zero clock // start with non-zero clock
hal.scheduler->stop_clock(1); hal.scheduler->stop_clock(1);
@ -295,7 +298,7 @@ void SITL_State::_fdm_input_local(void)
adsb->update(); adsb->update();
} }
if (_sitl) { if (_sitl && _use_fg_view) {
_output_to_flightgear(); _output_to_flightgear();
} }

View File

@ -169,6 +169,7 @@ private:
bool _synthetic_clock_mode; bool _synthetic_clock_mode;
bool _use_rtscts; bool _use_rtscts;
bool _use_fg_view;
const char *_fdm_address; const char *_fdm_address;

View File

@ -132,6 +132,7 @@ void SITL_State::_parse_command_line(int argc, char * const argv[])
_simin_port = 5501; _simin_port = 5501;
_fdm_address = "127.0.0.1"; _fdm_address = "127.0.0.1";
_client_address = nullptr; _client_address = nullptr;
_use_fg_view = false;
_instance = 0; _instance = 0;
enum long_options { enum long_options {
@ -145,6 +146,7 @@ void SITL_State::_parse_command_line(int argc, char * const argv[])
CMDLINE_UARTE, CMDLINE_UARTE,
CMDLINE_UARTF, CMDLINE_UARTF,
CMDLINE_RTSCTS, CMDLINE_RTSCTS,
CMDLINE_FGVIEW,
CMDLINE_DEFAULTS CMDLINE_DEFAULTS
}; };
@ -170,6 +172,7 @@ void SITL_State::_parse_command_line(int argc, char * const argv[])
{"autotest-dir", true, 0, CMDLINE_AUTOTESTDIR}, {"autotest-dir", true, 0, CMDLINE_AUTOTESTDIR},
{"defaults", true, 0, CMDLINE_DEFAULTS}, {"defaults", true, 0, CMDLINE_DEFAULTS},
{"rtscts", false, 0, CMDLINE_RTSCTS}, {"rtscts", false, 0, CMDLINE_RTSCTS},
{"fgview", false, 0, CMDLINE_FGVIEW},
{0, false, 0, 0} {0, false, 0, 0}
}; };
@ -240,7 +243,8 @@ void SITL_State::_parse_command_line(int argc, char * const argv[])
case CMDLINE_UARTF: case CMDLINE_UARTF:
_uart_path[opt - CMDLINE_UARTA] = gopt.optarg; _uart_path[opt - CMDLINE_UARTA] = gopt.optarg;
break; break;
case CMDLINE_FGVIEW:
_use_fg_view = true;
default: default:
_usage(); _usage();
exit(1); exit(1);