mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-31 04:58:30 -04:00
AP_HAL_SITL: Add uart specification and array
This commit is contained in:
parent
29534a7e2d
commit
b67f2e9307
@ -54,7 +54,7 @@ public:
|
||||
uint16_t voltage2_pin_value; // pin 15
|
||||
uint16_t current2_pin_value; // pin 14
|
||||
// paths for UART devices
|
||||
const char *_uart_path[7] {
|
||||
const char *_uart_path[9] {
|
||||
"none:0",
|
||||
"fifo:gps",
|
||||
"none:1",
|
||||
@ -62,6 +62,8 @@ public:
|
||||
"none:3",
|
||||
"none:4",
|
||||
"none:5",
|
||||
"none:6",
|
||||
"none:7",
|
||||
};
|
||||
|
||||
uint8_t get_instance() const { return _instance; }
|
||||
|
@ -104,7 +104,7 @@ public:
|
||||
uint16_t current2_pin_value; // pin 14
|
||||
|
||||
// paths for UART devices
|
||||
const char *_uart_path[7] {
|
||||
const char *_uart_path[9] {
|
||||
"tcp:0:wait",
|
||||
"GPS1",
|
||||
"tcp:2",
|
||||
@ -112,6 +112,8 @@ public:
|
||||
"GPS2",
|
||||
"tcp:5",
|
||||
"tcp:6",
|
||||
"tcp:7",
|
||||
"tcp:8",
|
||||
};
|
||||
std::vector<struct AP_Param::defaults_table_struct> cmdline_param;
|
||||
|
||||
|
@ -408,6 +408,7 @@ void SITL_State::_parse_command_line(int argc, char * const argv[])
|
||||
case CMDLINE_UARTF:
|
||||
case CMDLINE_UARTG:
|
||||
case CMDLINE_UARTH:
|
||||
case CMDLINE_UARTI:
|
||||
_uart_path[opt - CMDLINE_UARTA] = gopt.optarg;
|
||||
break;
|
||||
case CMDLINE_SERIAL0:
|
||||
@ -418,6 +419,7 @@ void SITL_State::_parse_command_line(int argc, char * const argv[])
|
||||
case CMDLINE_SERIAL5:
|
||||
case CMDLINE_SERIAL6:
|
||||
case CMDLINE_SERIAL7:
|
||||
case CMDLINE_SERIAL8:
|
||||
_uart_path[opt - CMDLINE_SERIAL0] = gopt.optarg;
|
||||
break;
|
||||
case CMDLINE_RTSCTS:
|
||||
|
Loading…
Reference in New Issue
Block a user