Browse Source

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
sbg
Matthias Grob 7 years ago committed by Daniel Agar
parent
commit
70de169f15
  1. 11
      platforms/posix/cmake/px4_impl_os.cmake
  2. 2
      src/lib/rc/dsm.cpp
  3. 8
      src/lib/version/version.c
  4. 12
      src/modules/mavlink/mavlink_main.cpp
  5. 4
      src/modules/mavlink/mavlink_shell.cpp
  6. 11
      src/modules/systemlib/print_load_posix.c
  7. 4
      src/platforms/posix/px4_layer/px4_log.c
  8. 5
      src/platforms/posix/px4_layer/px4_posix_tasks.cpp
  9. 2
      src/platforms/posix/px4_layer/px4_sem.cpp
  10. 2
      src/platforms/px4_defines.h
  11. 2
      src/platforms/px4_sem.h
  12. 6
      src/platforms/px4_tasks.h
  13. 2
      src/platforms/px4_time.h

11
platforms/posix/cmake/px4_impl_os.cmake

@ -196,8 +196,17 @@ function(px4_os_add_flags) @@ -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

2
src/lib/rc/dsm.cpp

@ -52,7 +52,7 @@ @@ -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>

8
src/lib/version/version.c

@ -253,8 +253,8 @@ uint32_t px4_board_version(void) @@ -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) @@ -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) @@ -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

12
src/modules/mavlink/mavlink_main.cpp

@ -836,7 +836,7 @@ int Mavlink::mavlink_open_uart(int baud, const char *uart_name) @@ -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() @@ -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) @@ -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() @@ -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);

4
src/modules/mavlink/mavlink_shell.cpp

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

11
src/modules/systemlib/print_load_posix.c

@ -91,15 +91,10 @@ void print_load(uint64_t t, int fd, struct print_load_s *print_state) @@ -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);

4
src/platforms/posix/px4_layer/px4_log.c

@ -1,7 +1,7 @@ @@ -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) @@ -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;

5
src/platforms/posix/px4_layer/px4_posix_tasks.cpp

@ -212,6 +212,11 @@ px4_task_t px4_task_spawn_cmd(const char *name, int scheduler, int priority, int @@ -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);

2
src/platforms/posix/px4_layer/px4_sem.cpp

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

2
src/platforms/px4_defines.h

@ -152,7 +152,9 @@ using ::isfinite; @@ -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)

2
src/platforms/px4_sem.h

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

6
src/platforms/px4_tasks.h

@ -69,11 +69,7 @@ typedef int px4_task_t; @@ -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))

2
src/platforms/px4_time.h

@ -16,7 +16,7 @@ __EXPORT unsigned int sleep(unsigned int sec); @@ -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

Loading…
Cancel
Save