HAL_SITL: fixed UART utils for cygwin and Linux

This commit is contained in:
Andrew Tridgell 2017-12-01 07:36:51 +11:00
parent 6bdbe53024
commit da4d3ebe2b
2 changed files with 57 additions and 36 deletions

View File

@ -61,10 +61,9 @@ public:
enum flow_control get_flow_control(void) { return FLOW_CONTROL_ENABLE; } enum flow_control get_flow_control(void) { return FLOW_CONTROL_ENABLE; }
virtual bool set_speed(int speed) { return true; } void configure_parity(uint8_t v) override;
virtual void configure_parity(uint8_t v) { } void set_stop_bits(int n) override;
virtual void set_stop_bits(int n) { } bool set_unbuffered_writes(bool on) override;
bool set_unbuffered_writes(bool on);
void _timer_tick(void); void _timer_tick(void);
@ -92,6 +91,7 @@ private:
void _check_connection(void); void _check_connection(void);
static bool _select_check(int ); static bool _select_check(int );
static void _set_nonblocking(int ); static void _set_nonblocking(int );
bool set_speed(int speed);
SITL_State *_sitlState; SITL_State *_sitlState;

View File

@ -15,11 +15,16 @@
* with this program. If not, see <http://www.gnu.org/licenses/>. * with this program. If not, see <http://www.gnu.org/licenses/>.
*/ */
#include <AP_HAL/AP_HAL.h> #include <AP_HAL/AP_HAL.h>
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL && !defined(__CYGWIN__) #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
#include "UARTDriver.h" #include "UARTDriver.h"
#ifdef __CYGWIN__
#include <termios.h> #include <termios.h>
#else
#include <asm/termbits.h>
#endif
#include <string.h> #include <string.h>
#include <sys/ioctl.h> #include <sys/ioctl.h>
#include <sys/stat.h> #include <sys/stat.h>
@ -27,12 +32,16 @@
bool HALSITL::UARTDriver::set_speed(int speed) bool HALSITL::UARTDriver::set_speed(int speed)
{ {
struct termios2 tc;
if (_fd < 0) { if (_fd < 0) {
return false; return false;
} }
#ifdef __CYGWIN__
struct termios t;
tcgetattr(_fd, &t);
cfsetspeed(&t, speed);
tcsetattr(_fd, TCSANOW, &t);
#else
struct termios2 tc;
memset(&tc, 0, sizeof(tc)); memset(&tc, 0, sizeof(tc));
if (ioctl(_fd, TCGETS2, &tc) == -1) { if (ioctl(_fd, TCGETS2, &tc) == -1) {
return false; return false;
@ -43,70 +52,82 @@ bool HALSITL::UARTDriver::set_speed(int speed)
tc.c_cflag |= BOTHER; tc.c_cflag |= BOTHER;
tc.c_ispeed = speed; tc.c_ispeed = speed;
tc.c_ospeed = speed; tc.c_ospeed = speed;
if (ioctl(_fd, TCSETS2, &tc) == -1) { if (ioctl(_fd, TCSETS2, &tc) == -1) {
return false; return false;
} }
if (ioctl(_fd, TCFLSH, TCIOFLUSH) == -1) { if (ioctl(_fd, TCFLSH, TCIOFLUSH) == -1) {
return false; return false;
} }
#endif
return true; return true;
} }
void HALSITL::UARTDriver::configure_parity(uint8_t v) { void HALSITL::UARTDriver::configure_parity(uint8_t v)
{
if (_fd < 0) { if (_fd < 0) {
return; return;
} }
struct termios2 tc; #ifdef __CYGWIN__
struct termios t;
memset(&tc, 0, sizeof(tc)); tcgetattr(_fd, &t);
if (ioctl(_fd, TCGETS2, &tc) == -1) { #else
struct termios2 t;
memset(&t, 0, sizeof(t));
if (ioctl(_fd, TCGETS2, &t) == -1) {
return; return;
} }
#endif
if (v != 0) { if (v != 0) {
// enable parity // enable parity
tc.c_cflag |= PARENB; t.c_cflag |= PARENB;
if (v == 1) { if (v == 1) {
tc.c_cflag |= PARODD; t.c_cflag |= PARODD;
} else { } else {
tc.c_cflag &= ~PARODD; t.c_cflag &= ~PARODD;
} }
} }
else { else {
// disable parity // disable parity
tc.c_cflag &= ~PARENB; t.c_cflag &= ~PARENB;
}
if (ioctl(_fd, TCSETS2, &tc) == -1) {
return;
} }
if (ioctl(_fd, TCFLSH, TCIOFLUSH) == -1) { #ifdef __CYGWIN__
return; tcsetattr(_fd, TCSANOW, &t);
} #else
ioctl(_fd, TCSETS2, &t);
#endif
} }
void HALSITL::UARTDriver::set_stop_bits(int n) { void HALSITL::UARTDriver::set_stop_bits(int n)
{
if (_fd < 0) { if (_fd < 0) {
return; return;
} }
struct termios2 tc; #ifdef __CYGWIN__
struct termios t;
memset(&tc, 0, sizeof(tc)); tcgetattr(_fd, &t);
if (ioctl(_fd, TCGETS2, &tc) == -1) { #else
struct termios2 t;
memset(&t, 0, sizeof(t));
if (ioctl(_fd, TCGETS2, &t) == -1) {
return; return;
} }
if (n > 1) tc.c_cflag |= CSTOPB; #endif
else tc.c_cflag &= ~CSTOPB;
if (ioctl(_fd, TCSETS2, &tc) == -1) { if (n > 1) {
return; t.c_cflag |= CSTOPB;
} else {
t.c_cflag &= ~CSTOPB;
} }
if (ioctl(_fd, TCFLSH, TCIOFLUSH) == -1) { #ifdef __CYGWIN__
return; tcsetattr(_fd, TCSANOW, &t);
} #else
ioctl(_fd, TCSETS2, &t);
#endif
} }
#endif #endif