mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
AP_HAL: added enable_flow_control() option in AP_HAL
This commit is contained in:
parent
8f5585423c
commit
3e637ac5d9
@ -38,6 +38,7 @@ public:
|
||||
virtual bool is_initialized() = 0;
|
||||
virtual void set_blocking_writes(bool blocking) = 0;
|
||||
virtual bool tx_pending() = 0;
|
||||
virtual void enable_flow_control(bool enable) {};
|
||||
|
||||
/* Implementations of BetterStream virtual methods. These are
|
||||
* provided by AP_HAL to ensure consistency between ports to
|
||||
|
@ -117,6 +117,9 @@ void PX4UARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS)
|
||||
cfsetspeed(&t, _baudrate);
|
||||
// disable LF -> CR/LF
|
||||
t.c_oflag &= ~ONLCR;
|
||||
// always enable input flow control (notifying devices that we
|
||||
// have space). This is harmless even if the pin is not connected
|
||||
t.c_cflag |= CRTS_IFLOW;
|
||||
tcsetattr(_fd, TCSANOW, &t);
|
||||
}
|
||||
|
||||
@ -129,6 +132,22 @@ void PX4UARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS)
|
||||
}
|
||||
}
|
||||
|
||||
void PX4UARTDriver::enable_flow_control(bool enable)
|
||||
{
|
||||
if (_fd == -1) {
|
||||
return;
|
||||
}
|
||||
struct termios t;
|
||||
tcgetattr(_fd, &t);
|
||||
// we already enabled CRTS_IFLOW above, just enable output flow control
|
||||
if (enable) {
|
||||
t.c_cflag |= CRTSCTS;
|
||||
} else {
|
||||
t.c_cflag &= ~CRTSCTS;
|
||||
}
|
||||
tcsetattr(_fd, TCSANOW, &t);
|
||||
}
|
||||
|
||||
void PX4UARTDriver::begin(uint32_t b)
|
||||
{
|
||||
begin(b, 0, 0);
|
||||
|
@ -36,6 +36,8 @@ public:
|
||||
return _fd;
|
||||
}
|
||||
|
||||
void enable_flow_control(bool enable);
|
||||
|
||||
private:
|
||||
const char *_devpath;
|
||||
int _fd;
|
||||
|
Loading…
Reference in New Issue
Block a user