HAL_SITL: fix sitl build for mac osx

This commit is contained in:
Siddharth Purohit 2018-01-20 02:20:19 +05:30 committed by Andrew Tridgell
parent 8b0e9bcff4
commit a6be19d8cf
2 changed files with 10 additions and 7 deletions

View File

@ -414,8 +414,11 @@ bool UARTDriver::set_unbuffered_writes(bool on) {
// this has no effect // this has no effect
unsigned v = fcntl(_fd, F_GETFL, 0); unsigned v = fcntl(_fd, F_GETFL, 0);
v &= ~O_NONBLOCK; v &= ~O_NONBLOCK;
#if defined(__APPLE__) && defined(__MACH__)
fcntl(_fd, F_SETFL | F_NOCACHE, v | O_SYNC);
#else
fcntl(_fd, F_SETFL, v | O_DIRECT | O_SYNC); fcntl(_fd, F_SETFL, v | O_DIRECT | O_SYNC);
#endif
return _unbuffered_writes; return _unbuffered_writes;
} }

View File

@ -19,7 +19,7 @@
#include "UARTDriver.h" #include "UARTDriver.h"
#ifdef __CYGWIN__ #if defined(__CYGWIN__) || defined(__APPLE__)
#include <termios.h> #include <termios.h>
#else #else
#include <asm/termbits.h> #include <asm/termbits.h>
@ -35,7 +35,7 @@ bool HALSITL::UARTDriver::set_speed(int speed)
if (_fd < 0) { if (_fd < 0) {
return false; return false;
} }
#ifdef __CYGWIN__ #if defined(__CYGWIN__) || defined(__APPLE__)
struct termios t; struct termios t;
tcgetattr(_fd, &t); tcgetattr(_fd, &t);
cfsetspeed(&t, speed); cfsetspeed(&t, speed);
@ -68,7 +68,7 @@ void HALSITL::UARTDriver::configure_parity(uint8_t v)
if (_fd < 0) { if (_fd < 0) {
return; return;
} }
#ifdef __CYGWIN__ #if defined(__CYGWIN__) || defined(__APPLE__)
struct termios t; struct termios t;
tcgetattr(_fd, &t); tcgetattr(_fd, &t);
@ -93,7 +93,7 @@ void HALSITL::UARTDriver::configure_parity(uint8_t v)
t.c_cflag &= ~PARENB; t.c_cflag &= ~PARENB;
} }
#ifdef __CYGWIN__ #if defined(__CYGWIN__) || defined(__APPLE__)
tcsetattr(_fd, TCSANOW, &t); tcsetattr(_fd, TCSANOW, &t);
#else #else
ioctl(_fd, TCSETS2, &t); ioctl(_fd, TCSETS2, &t);
@ -105,7 +105,7 @@ void HALSITL::UARTDriver::set_stop_bits(int n)
if (_fd < 0) { if (_fd < 0) {
return; return;
} }
#ifdef __CYGWIN__ #if defined(__CYGWIN__) || defined(__APPLE__)
struct termios t; struct termios t;
tcgetattr(_fd, &t); tcgetattr(_fd, &t);
@ -123,7 +123,7 @@ void HALSITL::UARTDriver::set_stop_bits(int n)
t.c_cflag &= ~CSTOPB; t.c_cflag &= ~CSTOPB;
} }
#ifdef __CYGWIN__ #if defined(__CYGWIN__) || defined(__APPLE__)
tcsetattr(_fd, TCSANOW, &t); tcsetattr(_fd, TCSANOW, &t);
#else #else
ioctl(_fd, TCSETS2, &t); ioctl(_fd, TCSETS2, &t);