AP_HAL_SITL: remove unused code

This commit is contained in:
Francisco Ferreira 2018-06-17 02:38:21 +01:00
parent f984e5e31d
commit 46868409ec
No known key found for this signature in database
GPG Key ID: F63C20A6773E787E
3 changed files with 2 additions and 31 deletions

View File

@ -66,9 +66,6 @@ void SITL_State::_sitl_setup(const char *home_str)
#if !defined(__CYGWIN__) && !defined(__CYGWIN64__)
_parent_pid = getppid();
#endif
_rcout_addr.sin_family = AF_INET;
_rcout_addr.sin_port = htons(_rcout_port);
inet_pton(AF_INET, _fdm_address, &_rcout_addr.sin_addr);
#ifndef HIL_MODE
_setup_fdm();

View File

@ -70,9 +70,6 @@ public:
uint16_t voltage2_pin_value; // pin 15
uint16_t current2_pin_value; // pin 14
// return TCP client address for uartC
const char *get_client_address(void) const { return _client_address; }
// paths for UART devices
const char *_uart_path[6] {
"tcp:0:wait",
@ -149,7 +146,6 @@ private:
uint16_t _framerate;
uint8_t _instance;
uint16_t _base_port;
struct sockaddr_in _rcout_addr;
pid_t _parent_pid;
uint32_t _update_count;
@ -163,7 +159,6 @@ private:
SocketAPM _sitl_rc_in{true};
SITL::SITL *_sitl;
uint16_t _rcout_port;
uint16_t _rcin_port;
uint16_t _fg_view_port;
uint16_t _irlock_port;
@ -220,9 +215,6 @@ private:
// output socket for flightgear viewing
SocketAPM fg_socket{true};
// TCP address to connect uartC to
const char *_client_address;
const char *defaults_path = HAL_PARAM_DEFAULTS_PATH;
const char *_home_str;

View File

@ -55,7 +55,6 @@ void SITL_State::_usage(void)
"\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--client ADDRESS TCP address to connect uartC to\n" NOT USED
"\t--gimbal enable simulated MAVLink gimbal\n"
"\t--disable-fgview disable Flight Gear view\n"
"\t--autotest-dir DIR set directory for additional files\n"
@ -69,7 +68,6 @@ void SITL_State::_usage(void)
"\t--rtscts enable rtscts on serial ports (default false)\n"
"\t--base-port PORT set port num for base port(default 5670) must be before -I option\n"
"\t--rc-in-port PORT set port num for rc in\n"
"\t--rc-out-port PORT set port num for rc out\n"
"\t--sim-address ADDR set address string for simulator\n"
"\t--sim-port-in PORT set port num for simulator in\n"
"\t--sim-port-out PORT set port num for simulator out\n"
@ -135,18 +133,15 @@ void SITL_State::_parse_command_line(int argc, char * const argv[])
// default to CMAC
const char *home_str = "-35.363261,149.165230,584,353";
const char *model_str = nullptr;
_client_address = nullptr;
_use_fg_view = true;
char *autotest_dir = nullptr;
_fdm_address = "127.0.0.1";
const int BASE_PORT = 5760;
const int RCIN_PORT = 5501;
const int RCOUT_PORT = 5502;
const int FG_VIEW_PORT = 5503;
_base_port = BASE_PORT;
_rcin_port = RCIN_PORT;
_rcout_port = RCOUT_PORT;
_fg_view_port = FG_VIEW_PORT;
const int SIM_IN_PORT = 9003;
@ -158,8 +153,7 @@ void SITL_State::_parse_command_line(int argc, char * const argv[])
_irlock_port = IRLOCK_PORT;
enum long_options {
CMDLINE_CLIENT = 0,
CMDLINE_GIMBAL,
CMDLINE_GIMBAL = 1,
CMDLINE_FGVIEW,
CMDLINE_AUTOTESTDIR,
CMDLINE_DEFAULTS,
@ -172,8 +166,7 @@ void SITL_State::_parse_command_line(int argc, char * const argv[])
CMDLINE_RTSCTS,
CMDLINE_BASE_PORT,
CMDLINE_RCIN_PORT,
CMDLINE_RCOUT_PORT,
CMDLINE_SIM_ADDRESS,
CMDLINE_SIM_ADDRESS = 15,
CMDLINE_SIM_PORT_IN,
CMDLINE_SIM_PORT_OUT,
CMDLINE_IRLOCK_PORT,
@ -192,7 +185,6 @@ void SITL_State::_parse_command_line(int argc, char * const argv[])
{"home", true, 0, 'O'},
{"model", true, 0, 'M'},
{"fdm", false, 0, 'F'},
{"client", true, 0, CMDLINE_CLIENT},
{"gimbal", false, 0, CMDLINE_GIMBAL},
{"disable-fgview", false, 0, CMDLINE_FGVIEW},
{"autotest-dir", true, 0, CMDLINE_AUTOTESTDIR},
@ -206,7 +198,6 @@ void SITL_State::_parse_command_line(int argc, char * const argv[])
{"rtscts", false, 0, CMDLINE_RTSCTS},
{"base-port", true, 0, CMDLINE_BASE_PORT},
{"rc-in-port", true, 0, CMDLINE_RCIN_PORT},
{"rc-out-port", true, 0, CMDLINE_RCOUT_PORT},
{"sim-address", true, 0, CMDLINE_SIM_ADDRESS},
{"sim-port-in", true, 0, CMDLINE_SIM_PORT_IN},
{"sim-port-out", true, 0, CMDLINE_SIM_PORT_OUT},
@ -248,9 +239,6 @@ void SITL_State::_parse_command_line(int argc, char * const argv[])
if (_base_port == BASE_PORT) {
_base_port += _instance * 10;
}
if (_rcout_port == RCOUT_PORT) {
_rcout_port += _instance * 10;
}
if (_rcin_port == RCIN_PORT) {
_rcin_port += _instance * 10;
}
@ -283,9 +271,6 @@ void SITL_State::_parse_command_line(int argc, char * const argv[])
case 'F':
_fdm_address = gopt.optarg;
break;
case CMDLINE_CLIENT:
_client_address = gopt.optarg;
break;
case CMDLINE_GIMBAL:
enable_gimbal = true;
break;
@ -315,9 +300,6 @@ void SITL_State::_parse_command_line(int argc, char * const argv[])
case CMDLINE_RCIN_PORT:
_rcin_port = atoi(gopt.optarg);
break;
case CMDLINE_RCOUT_PORT:
_rcout_port = atoi(gopt.optarg);
break;
case CMDLINE_SIM_ADDRESS:
_simulator_address = gopt.optarg;
break;