Cygwin: Enable build of SITL jMAVsim under Windows using the Cygwin Unix-like environment

Most of the incompatitbilities are luckily similar to the darwin build.
- New target OS __PX4_CYGWIN added because in other build environments on Windows defines will very likely be completely different
- added all necessary exeptions to the defines
- disabled priorities completely because on Windows they are defined 1-32 and with all the arbitrary +40 -40 priority settings there were a lot of problems
  not only did some threads/"virtual tasks" not start because of out of bound priorities but also the resulting scheduling was totally random and inadequate
  with default priorities it ran toally fine during my first tests, should be rethought when windows is used onboard in the future
This commit is contained in:
Matthias Grob
2017-11-18 15:26:26 +00:00
committed by Daniel Agar
parent 02c4ec9b2a
commit 70de169f15
13 changed files with 41 additions and 30 deletions

View File

@@ -196,8 +196,17 @@ function(px4_os_add_flags)
)
endif()
else()
elseif(CYGWIN)
set(added_definitions
-D__PX4_POSIX
-D__PX4_CYGWIN
-D_GNU_SOURCE
-D__USE_LINUX_IOCTL_DEFS
-Dnoreturn_function=__attribute__\(\(noreturn\)\)
-U __CUSTOM_FILE_IO__
)
else()
set(added_definitions
-D__PX4_POSIX
-D__PX4_LINUX

View File

@@ -52,7 +52,7 @@
#include "common_rc.h"
#include <drivers/drv_hrt.h>
#if defined (__PX4_LINUX) || defined (__PX4_DARWIN) || defined(__PX4_QURT)
#if defined (__PX4_LINUX) || defined (__PX4_DARWIN) || defined(__PX4_CYGWIN) || defined(__PX4_QURT)
#define dsm_udelay(arg) usleep(arg)
#else
#include <nuttx/arch.h>

View File

@@ -253,8 +253,8 @@ uint32_t px4_board_version(void)
uint32_t px4_os_version(void)
{
#if defined(__PX4_DARWIN)
return 0; //TODO: implement version for Darwin
#if defined(__PX4_DARWIN) || defined(__PX4_CYGWIN) || defined(__PX4_QURT)
return 0; //TODO: implement version for Darwin, Cygwin, QuRT
#elif defined(__PX4_LINUX)
struct utsname name;
@@ -273,8 +273,6 @@ uint32_t px4_os_version(void)
return 0;
}
#elif defined(__PX4_QURT)
return 0; //TODO: implement version for QuRT
#elif defined(__PX4_NUTTX)
return version_tag_to_number(NUTTX_GIT_TAG_STR);
#else
@@ -301,6 +299,8 @@ const char *px4_os_name(void)
return "QuRT";
#elif defined(__PX4_NUTTX)
return "NuttX";
#elif defined(__PX4_CYGWIN)
return "Cygwin";
#else
# error "px4_os_name not implemented for current OS"
#endif

View File

@@ -836,7 +836,7 @@ int Mavlink::mavlink_open_uart(int baud, const char *uart_name)
_rstatus.type = telemetry_status_s::TELEMETRY_STATUS_RADIO_TYPE_USB;
}
#if defined (__PX4_LINUX) || defined (__PX4_DARWIN)
#if defined(__PX4_LINUX) || defined(__PX4_DARWIN) || defined(__PX4_CYGWIN)
/* Put in raw mode */
cfmakeraw(&uart_config);
#endif
@@ -933,11 +933,11 @@ Mavlink::get_free_tx_buf()
} else {
// No FIONSPACE on Linux todo:use SIOCOUTQ and queue size to emulate FIONSPACE
#if !defined(__PX4_LINUX) && !defined(__PX4_DARWIN)
(void) ioctl(_uart_fd, FIONSPACE, (unsigned long)&buf_free);
#else
#if defined(__PX4_LINUX) || defined(__PX4_DARWIN) || defined(__PX4_CYGWIN)
//Linux cp210x does not support TIOCOUTQ
buf_free = 256;
#else
(void) ioctl(_uart_fd, FIONSPACE, (unsigned long)&buf_free);
#endif
if (get_flow_control_enabled() && buf_free < FLOW_CONTROL_DISABLE_THRESHOLD) {
@@ -1084,7 +1084,7 @@ Mavlink::send_bytes(const uint8_t *buf, unsigned packet_len)
void
Mavlink::find_broadcast_address()
{
#if defined (__PX4_LINUX) || defined (__PX4_DARWIN)
#if defined(__PX4_LINUX) || defined(__PX4_DARWIN) || defined(__PX4_CYGWIN)
struct ifconf ifconf;
int ret;
@@ -1231,7 +1231,7 @@ Mavlink::find_broadcast_address()
void
Mavlink::init_udp()
{
#if defined (__PX4_LINUX) || defined (__PX4_DARWIN)
#if defined (__PX4_LINUX) || defined (__PX4_DARWIN) || defined(__PX4_CYGWIN)
PX4_DEBUG("Setting up UDP with port %d", _network_port);

View File

@@ -50,6 +50,10 @@
#include <nshlib/nshlib.h>
#endif /* __PX4_NUTTX */
#ifdef __PX4_CYGWIN
#include <asm/socket.h>
#endif
MavlinkShell::MavlinkShell()
{

View File

@@ -91,15 +91,10 @@ void print_load(uint64_t t, int fd, struct print_load_s *print_state)
clear_line = CL;
}
#if defined (__PX4_LINUX)
dprintf(fd, "%sTOP NOT IMPLEMENTED ON LINUX\n",
clear_line);
#if defined(__PX4_LINUX) || defined(__PX4_CYGWIN) || defined(__PX4_QURT)
dprintf(fd, "%sTOP NOT IMPLEMENTED ON LINUX, QURT, WINDOWS (ONLY ON NUTTX, APPLE)\n", clear_line);
#elif defined (__PX4_QURT)
dprintf(fd, "%sTOP NOT IMPLEMENTED ON QURT\n",
clear_line);
#elif defined (__PX4_DARWIN)
#elif defined(__PX4_DARWIN)
pid_t pid = getpid(); //-- this is the process id you need info for
task_t task_handle;
task_for_pid(mach_task_self(), pid, &task_handle);

View File

@@ -1,7 +1,7 @@
#include <stdlib.h>
#include <string.h>
#include <px4_log.h>
#ifdef __PX4_POSIX
#if defined(__PX4_POSIX) && !defined(__PX4_CYGWIN)
#include <execinfo.h>
#endif
#include <uORB/uORB.h>
@@ -34,7 +34,7 @@ void px4_log_initialize(void)
void px4_backtrace()
{
#ifdef __PX4_POSIX
#if defined(__PX4_POSIX) && !defined(__PX4_CYGWIN)
void *buffer[10];
char **callstack;
int bt_size;

View File

@@ -212,6 +212,11 @@ px4_task_t px4_task_spawn_cmd(const char *name, int scheduler, int priority, int
return (rv < 0) ? rv : -rv;
}
#ifdef __PX4_CYGWIN
/* Priorities on Windows are defined a lot differently */
priority = SCHED_PRIORITY_DEFAULT;
#endif
param.sched_priority = priority;
rv = pthread_attr_setschedparam(&attr, &param);

View File

@@ -45,7 +45,7 @@
#include <pthread.h>
#include <errno.h>
#ifdef __PX4_DARWIN
#if defined(__PX4_DARWIN) || defined(__PX4_CYGWIN)
#include <px4_posix.h>

View File

@@ -152,7 +152,9 @@ using ::isfinite;
****************************************************************************/
// Flag is meaningless on Linux
#ifndef O_BINARY
#define O_BINARY 0
#endif
// mode for open with O_CREAT
#define PX4_O_MODE_777 (S_IRWXU | S_IRWXG | S_IRWXO)

View File

@@ -50,7 +50,7 @@
#define sem_setprotocol(s,p)
#endif
#ifdef __PX4_DARWIN
#if defined(__PX4_DARWIN) || defined(__PX4_CYGWIN)
__BEGIN_DECLS

View File

@@ -69,11 +69,7 @@ typedef int px4_task_t;
/** Default scheduler type */
#define SCHED_DEFAULT SCHED_FIFO
#ifdef __PX4_LINUX
#define SCHED_PRIORITY_MAX sched_get_priority_max(SCHED_FIFO)
#define SCHED_PRIORITY_MIN sched_get_priority_min(SCHED_FIFO)
#define SCHED_PRIORITY_DEFAULT (((sched_get_priority_max(SCHED_FIFO) - sched_get_priority_min(SCHED_FIFO)) / 2) + sched_get_priority_min(SCHED_FIFO))
#elif defined(__PX4_DARWIN)
#if defined(__PX4_LINUX) || defined(__PX4_DARWIN) || defined(__PX4_CYGWIN)
#define SCHED_PRIORITY_MAX sched_get_priority_max(SCHED_FIFO)
#define SCHED_PRIORITY_MIN sched_get_priority_min(SCHED_FIFO)
#define SCHED_PRIORITY_DEFAULT (((sched_get_priority_max(SCHED_FIFO) - sched_get_priority_min(SCHED_FIFO)) / 2) + sched_get_priority_min(SCHED_FIFO))

View File

@@ -16,7 +16,7 @@ __EXPORT unsigned int sleep(unsigned int sec);
__END_DECLS
#elif defined(__PX4_LINUX) || defined(__PX4_NUTTX) || defined(__PX4_DARWIN)
#elif defined(__PX4_LINUX) || defined(__PX4_NUTTX) || defined(__PX4_DARWIN) || defined(__PX4_CYGWIN)
#define px4_clock_gettime clock_gettime
#define px4_clock_settime clock_settime