mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_SITL: support port SITL to OpenBSD
This commit is contained in:
parent
7f04c82994
commit
bc9e135d6f
|
@ -7,7 +7,7 @@
|
|||
#include <sys/time.h>
|
||||
#include <fenv.h>
|
||||
#include <AP_BoardConfig/AP_BoardConfig.h>
|
||||
#if defined (__clang__) || (defined (__APPLE__) && defined (__MACH__))
|
||||
#if defined (__clang__) || (defined (__APPLE__) && defined (__MACH__)) || defined (__OpenBSD__)
|
||||
#include <stdlib.h>
|
||||
#else
|
||||
#include <malloc.h>
|
||||
|
@ -385,7 +385,7 @@ bool Scheduler::thread_create(AP_HAL::MemberProc proc, const char *name, uint32_
|
|||
goto failed;
|
||||
}
|
||||
|
||||
#if !defined(__APPLE__)
|
||||
#if !defined(__APPLE__) && !defined(__OpenBSD__)
|
||||
pthread_setname_np(thread, name);
|
||||
#endif
|
||||
|
||||
|
|
|
@ -714,6 +714,8 @@ bool UARTDriver::set_unbuffered_writes(bool on) {
|
|||
v &= ~O_NONBLOCK;
|
||||
#if defined(__APPLE__) && defined(__MACH__)
|
||||
fcntl(_fd, F_SETFL | F_NOCACHE, v | O_SYNC);
|
||||
#elif defined(__OpenBSD__)
|
||||
fcntl(_fd, F_SETFL, v | O_SYNC);
|
||||
#else
|
||||
fcntl(_fd, F_SETFL, v | O_DIRECT | O_SYNC);
|
||||
#endif
|
||||
|
|
|
@ -19,7 +19,7 @@
|
|||
|
||||
#include "UARTDriver.h"
|
||||
|
||||
#if defined(__CYGWIN__) || defined(__CYGWIN64__) || defined(__APPLE__)
|
||||
#if defined(__CYGWIN__) || defined(__CYGWIN64__) || defined(__APPLE__) || defined(__OpenBSD__)
|
||||
#define USE_TERMIOS
|
||||
#endif
|
||||
|
||||
|
|
Loading…
Reference in New Issue