Browse Source

AP_HAL: added enable_flow_control() option in AP_HAL

mission-4.1.18
Andrew Tridgell 11 years ago
parent
commit
3e637ac5d9
  1. 1
      libraries/AP_HAL/UARTDriver.h
  2. 19
      libraries/AP_HAL_PX4/UARTDriver.cpp
  3. 2
      libraries/AP_HAL_PX4/UARTDriver.h

1
libraries/AP_HAL/UARTDriver.h

@ -38,6 +38,7 @@ public: @@ -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

19
libraries/AP_HAL_PX4/UARTDriver.cpp

@ -117,6 +117,9 @@ void PX4UARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS) @@ -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) @@ -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);

2
libraries/AP_HAL_PX4/UARTDriver.h

@ -36,6 +36,8 @@ public: @@ -36,6 +36,8 @@ public:
return _fd;
}
void enable_flow_control(bool enable);
private:
const char *_devpath;
int _fd;

Loading…
Cancel
Save