mirror of https://github.com/ArduPilot/ardupilot
HAL_SITL: added uartF
This commit is contained in:
parent
9c9f66e5f3
commit
0d27409511
|
@ -43,6 +43,7 @@ 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 Util utilInstance(&sitlState);
|
||||
|
||||
|
@ -53,6 +54,7 @@ HAL_SITL::HAL_SITL() :
|
|||
&sitlUart2Driver, /* uartC */
|
||||
&sitlUart3Driver, /* uartD */
|
||||
&sitlUart4Driver, /* uartE */
|
||||
&sitlUart5Driver, /* uartF */
|
||||
&i2c_mgr_instance,
|
||||
&emptyI2C, /* i2c */
|
||||
&emptyI2C, /* i2c */
|
||||
|
|
|
@ -61,12 +61,13 @@ public:
|
|||
const char *get_client_address(void) const { return _client_address; }
|
||||
|
||||
// paths for UART devices
|
||||
const char *_uart_path[5] {
|
||||
const char *_uart_path[6] {
|
||||
"tcp:0:wait",
|
||||
"GPS1",
|
||||
"tcp:2",
|
||||
"tcp:3",
|
||||
"GPS2"
|
||||
"tcp:4",
|
||||
};
|
||||
|
||||
private:
|
||||
|
|
|
@ -122,6 +122,7 @@ void SITL_State::_parse_command_line(int argc, char * const argv[])
|
|||
CMDLINE_UARTC,
|
||||
CMDLINE_UARTD,
|
||||
CMDLINE_UARTE,
|
||||
CMDLINE_UARTF,
|
||||
CMDLINE_ADSB,
|
||||
CMDLINE_DEFAULTS
|
||||
};
|
||||
|
@ -211,6 +212,7 @@ void SITL_State::_parse_command_line(int argc, char * const argv[])
|
|||
case CMDLINE_UARTC:
|
||||
case CMDLINE_UARTD:
|
||||
case CMDLINE_UARTE:
|
||||
case CMDLINE_UARTF:
|
||||
_uart_path[opt - CMDLINE_UARTA] = gopt.optarg;
|
||||
break;
|
||||
|
||||
|
|
Loading…
Reference in New Issue