Browse Source

AP_HAL_SITL: re-use unused FDM address option for FG view IP address

mission-4.1.18
Francisco Ferreira 7 years ago
parent
commit
06c41bc768
No known key found for this signature in database
GPG Key ID: F63C20A6773E787E
  1. 2
      libraries/AP_HAL_SITL/SITL_State.cpp
  2. 2
      libraries/AP_HAL_SITL/SITL_State.h
  3. 10
      libraries/AP_HAL_SITL/SITL_cmdline.cpp

2
libraries/AP_HAL_SITL/SITL_State.cpp

@ -93,7 +93,7 @@ void SITL_State::_sitl_setup(const char *home_str) @@ -93,7 +93,7 @@ void SITL_State::_sitl_setup(const char *home_str)
}
if (_use_fg_view) {
fg_socket.connect("127.0.0.1", _fg_view_port);
fg_socket.connect(_fg_address, _fg_view_port);
}
fprintf(stdout, "Using Irlock at port : %d\n", _irlock_port);

2
libraries/AP_HAL_SITL/SITL_State.h

@ -169,7 +169,7 @@ private: @@ -169,7 +169,7 @@ private:
bool _use_rtscts;
bool _use_fg_view;
const char *_fdm_address;
const char *_fg_address;
// delay buffer variables
static const uint8_t mag_buffer_length = 250;

10
libraries/AP_HAL_SITL/SITL_cmdline.cpp

@ -54,9 +54,9 @@ void SITL_State::_usage(void) @@ -54,9 +54,9 @@ void SITL_State::_usage(void)
"\t--synthetic-clock|-S set synthetic clock mode\n"
"\t--home|-O HOME set home location (lat,lng,alt,yaw)\n"
"\t--model|-M MODEL set simulation model\n"
"\t--fdm|-F ADDRESS set FDM address, defaults to 127.0.0.1\n"
"\t--gimbal enable simulated MAVLink gimbal\n"
"\t--fg|-F ADDRESS set Flight Gear view address, defaults to 127.0.0.1\n"
"\t--disable-fgview disable Flight Gear view\n"
"\t--gimbal enable simulated MAVLink gimbal\n"
"\t--autotest-dir DIR set directory for additional files\n"
"\t--defaults path set path to defaults file\n"
"\t--uartA device set device string for UARTA\n"
@ -135,7 +135,7 @@ void SITL_State::_parse_command_line(int argc, char * const argv[]) @@ -135,7 +135,7 @@ void SITL_State::_parse_command_line(int argc, char * const argv[])
const char *model_str = nullptr;
_use_fg_view = true;
char *autotest_dir = nullptr;
_fdm_address = "127.0.0.1";
_fg_address = "127.0.0.1";
const int BASE_PORT = 5760;
const int RCIN_PORT = 5501;
@ -184,7 +184,7 @@ void SITL_State::_parse_command_line(int argc, char * const argv[]) @@ -184,7 +184,7 @@ void SITL_State::_parse_command_line(int argc, char * const argv[])
{"synthetic-clock", false, 0, 'S'},
{"home", true, 0, 'O'},
{"model", true, 0, 'M'},
{"fdm", false, 0, 'F'},
{"fg", true, 0, 'F'},
{"gimbal", false, 0, CMDLINE_GIMBAL},
{"disable-fgview", false, 0, CMDLINE_FGVIEW},
{"autotest-dir", true, 0, CMDLINE_AUTOTESTDIR},
@ -269,7 +269,7 @@ void SITL_State::_parse_command_line(int argc, char * const argv[]) @@ -269,7 +269,7 @@ void SITL_State::_parse_command_line(int argc, char * const argv[])
model_str = gopt.optarg;
break;
case 'F':
_fdm_address = gopt.optarg;
_fg_address = gopt.optarg;
break;
case CMDLINE_GIMBAL:
enable_gimbal = true;

Loading…
Cancel
Save