mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-07 00:13:59 -04:00
AP_HAL_SITL: eliminate internal legacy UART ordering/references
Legacy command line arguments are kept to avoid breaking users. The vestigial `_tcp_client_addr` variable is removed. Serial port status messages are updated to a slightly different format to clarify the numbering scheme being used and prompt any external consumers to update.
This commit is contained in:
parent
f34034584f
commit
9044632315
@ -53,16 +53,16 @@ static DSP dspDriver;
|
||||
static Empty::OpticalFlow emptyOpticalFlow;
|
||||
static Empty::Flash emptyFlash;
|
||||
|
||||
static UARTDriver sitlUart0Driver(0, &sitlState);
|
||||
static UARTDriver sitlUart1Driver(1, &sitlState);
|
||||
static UARTDriver sitlUart2Driver(2, &sitlState);
|
||||
static UARTDriver sitlUart3Driver(3, &sitlState);
|
||||
static UARTDriver sitlUart4Driver(4, &sitlState);
|
||||
static UARTDriver sitlUart5Driver(5, &sitlState);
|
||||
static UARTDriver sitlUart6Driver(6, &sitlState);
|
||||
static UARTDriver sitlUart7Driver(7, &sitlState);
|
||||
static UARTDriver sitlUart8Driver(8, &sitlState);
|
||||
static UARTDriver sitlUart9Driver(9, &sitlState);
|
||||
static UARTDriver sitlSerial0Driver(0, &sitlState);
|
||||
static UARTDriver sitlSerial1Driver(1, &sitlState);
|
||||
static UARTDriver sitlSerial2Driver(2, &sitlState);
|
||||
static UARTDriver sitlSerial3Driver(3, &sitlState);
|
||||
static UARTDriver sitlSerial4Driver(4, &sitlState);
|
||||
static UARTDriver sitlSerial5Driver(5, &sitlState);
|
||||
static UARTDriver sitlSerial6Driver(6, &sitlState);
|
||||
static UARTDriver sitlSerial7Driver(7, &sitlState);
|
||||
static UARTDriver sitlSerial8Driver(8, &sitlState);
|
||||
static UARTDriver sitlSerial9Driver(9, &sitlState);
|
||||
|
||||
static I2CDeviceManager i2c_mgr_instance;
|
||||
|
||||
@ -81,22 +81,22 @@ static Empty::WSPIDeviceManager wspi_mgr_instance;
|
||||
|
||||
HAL_SITL::HAL_SITL() :
|
||||
AP_HAL::HAL(
|
||||
&sitlUart0Driver, /* uartA */
|
||||
&sitlUart2Driver, /* uartC */ // ordering captures the historical use of uartB as SERIAL3
|
||||
&sitlUart3Driver, /* uartD */
|
||||
&sitlUart1Driver, /* uartB */
|
||||
&sitlUart4Driver, /* uartE */
|
||||
&sitlUart5Driver, /* uartF */
|
||||
&sitlUart6Driver, /* uartG */
|
||||
&sitlUart7Driver, /* uartH */
|
||||
&sitlUart8Driver, /* uartI */
|
||||
&sitlUart9Driver, /* uartJ */
|
||||
&sitlSerial0Driver,
|
||||
&sitlSerial1Driver,
|
||||
&sitlSerial2Driver,
|
||||
&sitlSerial3Driver,
|
||||
&sitlSerial4Driver,
|
||||
&sitlSerial5Driver,
|
||||
&sitlSerial6Driver,
|
||||
&sitlSerial7Driver,
|
||||
&sitlSerial8Driver,
|
||||
&sitlSerial9Driver,
|
||||
&i2c_mgr_instance,
|
||||
&spi_mgr_instance, /* spi */
|
||||
&wspi_mgr_instance,
|
||||
&sitlAnalogIn, /* analogin */
|
||||
&sitlStorage, /* storage */
|
||||
&sitlUart0Driver, /* console */
|
||||
&sitlSerial0Driver, /* console */
|
||||
&sitlGPIO, /* gpio */
|
||||
&sitlRCInput, /* rcinput */
|
||||
&sitlRCOutput, /* rcoutput */
|
||||
|
@ -83,11 +83,9 @@ void SITL_State::init(int argc, char * const argv[]) {
|
||||
case CMDLINE_SERIAL6:
|
||||
case CMDLINE_SERIAL7:
|
||||
case CMDLINE_SERIAL8:
|
||||
case CMDLINE_SERIAL9: {
|
||||
static const uint8_t mapping[] = { 0, 2, 3, 1, 4, 5, 6, 7, 8, 9 };
|
||||
_uart_path[mapping[opt - CMDLINE_SERIAL0]] = gopt.optarg;
|
||||
case CMDLINE_SERIAL9:
|
||||
_serial_path[opt - CMDLINE_SERIAL0] = gopt.optarg;
|
||||
break;
|
||||
}
|
||||
case CMDLINE_DEFAULTS:
|
||||
defaults_path = strdup(gopt.optarg);
|
||||
break;
|
||||
|
@ -61,11 +61,11 @@ public:
|
||||
}
|
||||
|
||||
// paths for UART devices
|
||||
const char *_uart_path[9] {
|
||||
const char *_serial_path[9] {
|
||||
"none:0",
|
||||
"GPS1",
|
||||
"none:1",
|
||||
"sim:adsb",
|
||||
"GPS1",
|
||||
"udpclient:127.0.0.1:15550", // for CAN UART test
|
||||
"none:5",
|
||||
"none:6",
|
||||
|
@ -29,11 +29,11 @@ public:
|
||||
}
|
||||
|
||||
// paths for UART devices
|
||||
const char *_uart_path[9] {
|
||||
const char *_serial_path[9] {
|
||||
"tcp:0:wait",
|
||||
"GPS1",
|
||||
"tcp:2",
|
||||
"tcp:3",
|
||||
"GPS1",
|
||||
"GPS2",
|
||||
"tcp:5",
|
||||
"tcp:6",
|
||||
|
@ -92,16 +92,16 @@ void SITL_State::_usage(void)
|
||||
"\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"
|
||||
"\t--uartB device set device string for UARTB\n"
|
||||
"\t--uartC device set device string for UARTC\n"
|
||||
"\t--uartD device set device string for UARTD\n"
|
||||
"\t--uartE device set device string for UARTE\n"
|
||||
"\t--uartF device set device string for UARTF\n"
|
||||
"\t--uartG device set device string for UARTG\n"
|
||||
"\t--uartH device set device string for UARTH\n"
|
||||
"\t--uartI device set device string for UARTI\n"
|
||||
"\t--uartJ device set device string for UARTJ\n"
|
||||
"\t--uartA device set device string for SERIAL0\n"
|
||||
"\t--uartB device set device string for SERIAL3\n" // ordering captures the historical use of uartB as SERIAL3
|
||||
"\t--uartC device set device string for SERIAL1\n"
|
||||
"\t--uartD device set device string for SERIAL2\n"
|
||||
"\t--uartE device set device string for SERIAL4\n"
|
||||
"\t--uartF device set device string for SERIAL5\n"
|
||||
"\t--uartG device set device string for SERIAL6\n"
|
||||
"\t--uartH device set device string for SERIAL7\n"
|
||||
"\t--uartI device set device string for SERIAL8\n"
|
||||
"\t--uartJ device set device string for SERIAL9\n"
|
||||
"\t--serial0 device set device string for SERIAL0\n"
|
||||
"\t--serial1 device set device string for SERIAL1\n"
|
||||
"\t--serial2 device set device string for SERIAL2\n"
|
||||
@ -246,17 +246,7 @@ void SITL_State::_parse_command_line(int argc, char * const argv[])
|
||||
CMDLINE_FGVIEW,
|
||||
CMDLINE_AUTOTESTDIR,
|
||||
CMDLINE_DEFAULTS,
|
||||
CMDLINE_UARTA,
|
||||
CMDLINE_UARTB,
|
||||
CMDLINE_UARTC,
|
||||
CMDLINE_UARTD,
|
||||
CMDLINE_UARTE,
|
||||
CMDLINE_UARTF,
|
||||
CMDLINE_UARTG,
|
||||
CMDLINE_UARTH,
|
||||
CMDLINE_UARTI,
|
||||
CMDLINE_UARTJ,
|
||||
CMDLINE_SERIAL0,
|
||||
CMDLINE_SERIAL0, // must be in 0-9 order and numbered consecutively
|
||||
CMDLINE_SERIAL1,
|
||||
CMDLINE_SERIAL2,
|
||||
CMDLINE_SERIAL3,
|
||||
@ -305,16 +295,16 @@ void SITL_State::_parse_command_line(int argc, char * const argv[])
|
||||
{"disable-fgview", false, 0, CMDLINE_FGVIEW},
|
||||
{"autotest-dir", true, 0, CMDLINE_AUTOTESTDIR},
|
||||
{"defaults", true, 0, CMDLINE_DEFAULTS},
|
||||
{"uartA", true, 0, CMDLINE_UARTA},
|
||||
{"uartB", true, 0, CMDLINE_UARTB},
|
||||
{"uartC", true, 0, CMDLINE_UARTC},
|
||||
{"uartD", true, 0, CMDLINE_UARTD},
|
||||
{"uartE", true, 0, CMDLINE_UARTE},
|
||||
{"uartF", true, 0, CMDLINE_UARTF},
|
||||
{"uartG", true, 0, CMDLINE_UARTG},
|
||||
{"uartH", true, 0, CMDLINE_UARTH},
|
||||
{"uartI", true, 0, CMDLINE_UARTI},
|
||||
{"uartJ", true, 0, CMDLINE_UARTJ},
|
||||
{"uartA", true, 0, CMDLINE_SERIAL0},
|
||||
{"uartB", true, 0, CMDLINE_SERIAL3}, // ordering captures the historical use of uartB as SERIAL3
|
||||
{"uartC", true, 0, CMDLINE_SERIAL1},
|
||||
{"uartD", true, 0, CMDLINE_SERIAL2},
|
||||
{"uartE", true, 0, CMDLINE_SERIAL4},
|
||||
{"uartF", true, 0, CMDLINE_SERIAL5},
|
||||
{"uartG", true, 0, CMDLINE_SERIAL6},
|
||||
{"uartH", true, 0, CMDLINE_SERIAL7},
|
||||
{"uartI", true, 0, CMDLINE_SERIAL8},
|
||||
{"uartJ", true, 0, CMDLINE_SERIAL9},
|
||||
{"serial0", true, 0, CMDLINE_SERIAL0},
|
||||
{"serial1", true, 0, CMDLINE_SERIAL1},
|
||||
{"serial2", true, 0, CMDLINE_SERIAL2},
|
||||
@ -449,18 +439,6 @@ void SITL_State::_parse_command_line(int argc, char * const argv[])
|
||||
case CMDLINE_DEFAULTS:
|
||||
defaults_path = strdup(gopt.optarg);
|
||||
break;
|
||||
case CMDLINE_UARTA:
|
||||
case CMDLINE_UARTB:
|
||||
case CMDLINE_UARTC:
|
||||
case CMDLINE_UARTD:
|
||||
case CMDLINE_UARTE:
|
||||
case CMDLINE_UARTF:
|
||||
case CMDLINE_UARTG:
|
||||
case CMDLINE_UARTH:
|
||||
case CMDLINE_UARTI:
|
||||
case CMDLINE_UARTJ:
|
||||
_uart_path[opt - CMDLINE_UARTA] = gopt.optarg;
|
||||
break;
|
||||
case CMDLINE_SERIAL0:
|
||||
case CMDLINE_SERIAL1:
|
||||
case CMDLINE_SERIAL2:
|
||||
@ -470,11 +448,9 @@ void SITL_State::_parse_command_line(int argc, char * const argv[])
|
||||
case CMDLINE_SERIAL6:
|
||||
case CMDLINE_SERIAL7:
|
||||
case CMDLINE_SERIAL8:
|
||||
case CMDLINE_SERIAL9: {
|
||||
static const uint8_t mapping[] = { 0, 2, 3, 1, 4, 5, 6, 7, 8, 9 };
|
||||
_uart_path[mapping[opt - CMDLINE_SERIAL0]] = gopt.optarg;
|
||||
case CMDLINE_SERIAL9:
|
||||
_serial_path[opt - CMDLINE_SERIAL0] = gopt.optarg;
|
||||
break;
|
||||
}
|
||||
case CMDLINE_RTSCTS:
|
||||
_use_rtscts = true;
|
||||
break;
|
||||
|
@ -56,11 +56,11 @@ bool UARTDriver::_console;
|
||||
|
||||
void UARTDriver::_begin(uint32_t baud, uint16_t rxSpace, uint16_t txSpace)
|
||||
{
|
||||
if (_portNumber >= ARRAY_SIZE(_sitlState->_uart_path)) {
|
||||
AP_HAL::panic("port number out of range; you may need to extend _sitlState->_uart_path");
|
||||
if (_portNumber >= ARRAY_SIZE(_sitlState->_serial_path)) {
|
||||
AP_HAL::panic("port number out of range; you may need to extend _sitlState->_serial_path");
|
||||
}
|
||||
|
||||
const char *path = _sitlState->_uart_path[_portNumber];
|
||||
const char *path = _sitlState->_serial_path[_portNumber];
|
||||
|
||||
if (baud != 0) {
|
||||
_uart_baudrate = baud;
|
||||
@ -95,11 +95,11 @@ void UARTDriver::_begin(uint32_t baud, uint16_t rxSpace, uint16_t txSpace)
|
||||
char *args1 = strtok_r(nullptr, ":", &saveptr);
|
||||
char *args2 = strtok_r(nullptr, ":", &saveptr);
|
||||
#if APM_BUILD_COPTER_OR_HELI || APM_BUILD_TYPE(APM_BUILD_ArduPlane)
|
||||
if (_portNumber == 2 && AP::sitl()->adsb_plane_count >= 0) {
|
||||
if (_portNumber == 1 && AP::sitl()->adsb_plane_count >= 0) {
|
||||
// this is ordinarily port 5762. The ADSB simulation assumed
|
||||
// this port, so if enabled we assume we'll be doing ADSB...
|
||||
// add sanity check here that we're doing mavlink on this port?
|
||||
::printf("SIM-ADSB connection on port %u\n", _portNumber);
|
||||
::printf("SIM-ADSB connection on SERIAL%u\n", _portNumber);
|
||||
_connected = true;
|
||||
_sim_serial_device = _sitlState->create_serial_sim("adsb", nullptr);
|
||||
} else
|
||||
@ -122,7 +122,7 @@ void UARTDriver::_begin(uint32_t baud, uint16_t rxSpace, uint16_t txSpace)
|
||||
_uart_start_connection();
|
||||
} else if (strcmp(devtype, "sim") == 0) {
|
||||
if (!_connected) {
|
||||
::printf("SIM connection %s:%s on port %u\n", args1, args2, _portNumber);
|
||||
::printf("SIM connection %s:%s on SERIAL%u\n", args1, args2, _portNumber);
|
||||
_connected = true;
|
||||
_sim_serial_device = _sitlState->create_serial_sim(args1, args2);
|
||||
}
|
||||
@ -334,7 +334,7 @@ void UARTDriver::_tcp_start_connection(uint16_t port, bool wait_for_connection)
|
||||
exit(1);
|
||||
}
|
||||
|
||||
fprintf(stderr, "bind port %u for %u\n",
|
||||
fprintf(stderr, "bind port %u for SERIAL%u\n",
|
||||
(unsigned)ntohs(_listen_sockaddr.sin_port),
|
||||
(unsigned)_portNumber);
|
||||
|
||||
@ -352,7 +352,7 @@ void UARTDriver::_tcp_start_connection(uint16_t port, bool wait_for_connection)
|
||||
exit(1);
|
||||
}
|
||||
|
||||
fprintf(stderr, "Serial port %u on TCP port %u\n", _portNumber,
|
||||
fprintf(stderr, "SERIAL%u on TCP port %u\n", _portNumber,
|
||||
(unsigned)ntohs(_listen_sockaddr.sin_port));
|
||||
fflush(stdout);
|
||||
}
|
||||
@ -630,7 +630,7 @@ void UARTDriver::_check_connection(void)
|
||||
setsockopt(_fd, IPPROTO_TCP, TCP_NODELAY, &one, sizeof(one));
|
||||
setsockopt(_fd, SOL_SOCKET, SO_REUSEADDR, &one, sizeof(one));
|
||||
fcntl(_fd, F_SETFD, FD_CLOEXEC);
|
||||
fprintf(stdout, "New connection on serial port %u\n", _portNumber);
|
||||
fprintf(stdout, "New connection on SERIAL%u\n", _portNumber);
|
||||
}
|
||||
}
|
||||
}
|
||||
@ -917,7 +917,7 @@ void UARTDriver::handle_reading_from_device_to_readbuffer()
|
||||
close(_fd);
|
||||
_fd = -1;
|
||||
_connected = false;
|
||||
fprintf(stdout, "Closed connection on serial port %u\n", _portNumber);
|
||||
fprintf(stdout, "Closed connection on SERIAL%u\n", _portNumber);
|
||||
fflush(stdout);
|
||||
#if defined(__CYGWIN__) || defined(__CYGWIN64__) || defined(CYGWIN_BUILD)
|
||||
if (_portNumber == 0) {
|
||||
@ -990,7 +990,7 @@ ssize_t UARTDriver::get_system_outqueue_length() const
|
||||
uint32_t UARTDriver::bw_in_bytes_per_second() const
|
||||
{
|
||||
// if connected, assume at least a 10/100Mbps connection
|
||||
const uint32_t bitrate = (_connected && _tcp_client_addr != nullptr) ? 10E6 : _uart_baudrate;
|
||||
const uint32_t bitrate = _connected ? 10E6 : _uart_baudrate;
|
||||
return bitrate/10; // convert bits to bytes minus overhead
|
||||
};
|
||||
#endif // CONFIG_HAL_BOARD
|
||||
|
@ -89,9 +89,6 @@ private:
|
||||
const char *_uart_path;
|
||||
uint32_t _uart_baudrate;
|
||||
|
||||
// IPv4 address of target for uartC
|
||||
const char *_tcp_client_addr;
|
||||
|
||||
void _tcp_start_connection(uint16_t port, bool wait_for_connection);
|
||||
void _uart_start_connection(void);
|
||||
void _check_reconnect();
|
||||
|
Loading…
Reference in New Issue
Block a user