diff --git a/libraries/AP_HAL_SITL/SITL_State.h b/libraries/AP_HAL_SITL/SITL_State.h index 23086d4324..ef66037ad1 100644 --- a/libraries/AP_HAL_SITL/SITL_State.h +++ b/libraries/AP_HAL_SITL/SITL_State.h @@ -51,6 +51,10 @@ public: return _base_port; } + bool use_rtscts(void) const { + return _use_rtscts; + } + // simulated airspeed, sonar and battery monitor uint16_t sonar_pin_value; // pin 0 uint16_t airspeed_pin_value; // pin 1 @@ -157,6 +161,8 @@ private: bool _synthetic_clock_mode; + bool _use_rtscts; + const char *_fdm_address; // delay buffer variables diff --git a/libraries/AP_HAL_SITL/SITL_cmdline.cpp b/libraries/AP_HAL_SITL/SITL_cmdline.cpp index ad1c523f13..a9a6ab4df7 100644 --- a/libraries/AP_HAL_SITL/SITL_cmdline.cpp +++ b/libraries/AP_HAL_SITL/SITL_cmdline.cpp @@ -129,6 +129,7 @@ void SITL_State::_parse_command_line(int argc, char * const argv[]) CMDLINE_UARTE, CMDLINE_UARTF, CMDLINE_ADSB, + CMDLINE_RTSCTS, CMDLINE_DEFAULTS }; @@ -153,6 +154,7 @@ void SITL_State::_parse_command_line(int argc, char * const argv[]) {"adsb", false, 0, CMDLINE_ADSB}, {"autotest-dir", true, 0, CMDLINE_AUTOTESTDIR}, {"defaults", true, 0, CMDLINE_DEFAULTS}, + {"rtscts", false, 0, CMDLINE_RTSCTS}, {0, false, 0, 0} }; @@ -205,6 +207,9 @@ void SITL_State::_parse_command_line(int argc, char * const argv[]) case CMDLINE_ADSB: enable_ADSB = true; break; + case CMDLINE_RTSCTS: + _use_rtscts = true; + break; case CMDLINE_AUTOTESTDIR: autotest_dir = strdup(gopt.optarg); break; diff --git a/libraries/AP_HAL_SITL/UARTDriver.cpp b/libraries/AP_HAL_SITL/UARTDriver.cpp index df008e6e2b..5641f833dc 100644 --- a/libraries/AP_HAL_SITL/UARTDriver.cpp +++ b/libraries/AP_HAL_SITL/UARTDriver.cpp @@ -324,6 +324,9 @@ void UARTDriver::_uart_start_connection(const char *path, uint32_t baudrate) t.c_oflag &= ~(OPOST | ONLCR); t.c_lflag &= ~(ISIG | ICANON | IEXTEN | ECHO | ECHOE | ECHOK | ECHOCTL | ECHOKE); t.c_cc[VMIN] = 0; + if (_sitlState->use_rtscts()) { + t.c_cflag |= CRTSCTS; + } tcsetattr(_fd, TCSANOW, &t); // set baudrate