forked from Archive/PX4-Autopilot
Linux to posix conversion
Changed "linux" target to "posix". Most of the changes are shared with QuRT and with OSX. The Linux specific parts are in for i2c which uses <linux/i2c.h> and <linux/i2c-dev.h>. There is also a check for __PX4_LINUX in mavlink for a tty ioctl that is not supported. Signed-off-by: Mark Charlebois <charlebm@gmail.com>
This commit is contained in:
parent
40faa98416
commit
f3b5076d70
8
Makefile
8
Makefile
|
@ -100,8 +100,8 @@ endif
|
|||
ifeq ($(PX4_TARGET_OS),nuttx)
|
||||
include $(PX4_BASE)makefiles/firmware_nuttx.mk
|
||||
endif
|
||||
ifeq ($(PX4_TARGET_OS),linux)
|
||||
include $(PX4_BASE)makefiles/firmware_linux.mk
|
||||
ifeq ($(PX4_TARGET_OS),posix)
|
||||
include $(PX4_BASE)makefiles/firmware_posix.mk
|
||||
endif
|
||||
ifeq ($(PX4_TARGET_OS),qurt)
|
||||
include $(PX4_BASE)makefiles/firmware_qurt.mk
|
||||
|
@ -146,8 +146,8 @@ testbuild:
|
|||
$(Q) (cd $(PX4_BASE) && $(MAKE) distclean && $(MAKE) archives && $(MAKE) -j8)
|
||||
$(Q) (zip -r Firmware.zip $(PX4_BASE)/Images)
|
||||
|
||||
linuxrun:
|
||||
Tools/linux_run.sh
|
||||
posixrun:
|
||||
Tools/posix_run.sh
|
||||
|
||||
#
|
||||
# Unittest targets. Builds and runs the host-level
|
||||
|
|
|
@ -30,9 +30,9 @@ firmware_nuttx.mk
|
|||
|
||||
Called by firmware.mk to build NuttX based firmware.
|
||||
|
||||
firmware_linux.mk
|
||||
firmware_posix.mk
|
||||
|
||||
Called by firmware.mk to build Linux (non-ROS) based firmware.
|
||||
Called by firmware.mk to build POSIX (non-ROS) based firmware.
|
||||
|
||||
module.mk
|
||||
|
||||
|
@ -46,10 +46,10 @@ nuttx.mk
|
|||
Called by ../Makefile to build or download the NuttX archives if
|
||||
PX4_TARGET_OS is set to "nuttx".
|
||||
|
||||
linux.mk
|
||||
posix.mk
|
||||
|
||||
Called by ../Makefile to set Linux specific parameters if
|
||||
PX4_TARGET_OS is set to "linux".
|
||||
Called by ../Makefile to set POSIX specific parameters if
|
||||
PX4_TARGET_OS is set to "posix".
|
||||
|
||||
upload.mk
|
||||
|
||||
|
|
|
@ -360,8 +360,8 @@ $(filter %.S.o,$(OBJS)): $(WORK_DIR)%.S.o: %.S $(GLOBAL_DEPS)
|
|||
ifeq ($(PX4_TARGET_OS),nuttx)
|
||||
include $(MK_DIR)/nuttx_romfs.mk
|
||||
endif
|
||||
ifeq ($(PX4_TARGET_OS),linux)
|
||||
include $(MK_DIR)/linux_elf.mk
|
||||
ifeq ($(PX4_TARGET_OS),posix)
|
||||
include $(MK_DIR)/posix_elf.mk
|
||||
endif
|
||||
ifeq ($(PX4_TARGET_OS),qurt)
|
||||
include $(MK_DIR)/qurt_elf.mk
|
||||
|
|
|
@ -36,5 +36,5 @@
|
|||
|
||||
MODULES += \
|
||||
platforms/common \
|
||||
platforms/linux/px4_layer
|
||||
platforms/posix/px4_layer
|
||||
|
|
@ -1,11 +1,11 @@
|
|||
#
|
||||
# Board-specific definitions for the Linux port of PX4
|
||||
# Board-specific definitions for the POSIX port of PX4
|
||||
#
|
||||
|
||||
#
|
||||
# Configure the toolchain
|
||||
#
|
||||
CONFIG_ARCH = NATIVE
|
||||
CONFIG_BOARD = LINUXTEST
|
||||
CONFIG_BOARD = POSIXTEST
|
||||
|
||||
include $(PX4_MK_DIR)/toolchain_native.mk
|
|
@ -1,12 +1,7 @@
|
|||
#
|
||||
# Makefile for the Foo *default* configuration
|
||||
# Makefile for the POSIXTEST *default* configuration
|
||||
#
|
||||
|
||||
#
|
||||
# Use the configuration's ROMFS.
|
||||
#
|
||||
#ROMFS_ROOT = $(PX4_BASE)/ROMFS/px4fmu_common
|
||||
|
||||
#
|
||||
# Board support modules
|
||||
#
|
||||
|
@ -61,17 +56,17 @@ MODULES += lib/conversion
|
|||
#
|
||||
# Linux port
|
||||
#
|
||||
MODULES += platforms/linux/px4_layer
|
||||
MODULES += platforms/linux/drivers/accelsim
|
||||
MODULES += platforms/linux/drivers/gyrosim
|
||||
MODULES += platforms/linux/drivers/adcsim
|
||||
MODULES += platforms/linux/drivers/barosim
|
||||
MODULES += platforms/posix/px4_layer
|
||||
MODULES += platforms/posix/drivers/accelsim
|
||||
MODULES += platforms/posix/drivers/gyrosim
|
||||
MODULES += platforms/posix/drivers/adcsim
|
||||
MODULES += platforms/posix/drivers/barosim
|
||||
|
||||
#
|
||||
# Unit tests
|
||||
#
|
||||
#MODULES += platforms/linux/tests/hello
|
||||
#MODULES += platforms/linux/tests/vcdev_test
|
||||
#MODULES += platforms/linux/tests/hrt_test
|
||||
#MODULES += platforms/linux/tests/wqueue
|
||||
#MODULES += platforms/posix/tests/hello
|
||||
#MODULES += platforms/posix/tests/vcdev_test
|
||||
#MODULES += platforms/posix/tests/hrt_test
|
||||
#MODULES += platforms/posix/tests/wqueue
|
||||
|
|
@ -30,7 +30,7 @@
|
|||
#
|
||||
|
||||
#
|
||||
# Makefile for PX4 Linux based firmware images.
|
||||
# Makefile for PX4 POSIX based firmware images.
|
||||
#
|
||||
|
||||
################################################################################
|
||||
|
@ -56,9 +56,9 @@ $(PRODUCT_SHARED_PRELINK): $(OBJS) $(MODULE_OBJS) $(LIBRARY_LIBS) $(GLOBAL_DEPS)
|
|||
$(PRODUCT_SHARED_LIB): $(PRODUCT_SHARED_PRELINK)
|
||||
$(call LINK_A,$@,$(PRODUCT_SHARED_PRELINK))
|
||||
|
||||
MAIN = $(PX4_BASE)/src/platforms/linux/main.cpp
|
||||
MAIN = $(PX4_BASE)/src/platforms/posix/main.cpp
|
||||
$(WORK_DIR)mainapp: $(PRODUCT_SHARED_LIB)
|
||||
$(PX4_BASE)/Tools/linux_apps.py > apps.h
|
||||
$(PX4_BASE)/Tools/posix_apps.py > apps.h
|
||||
$(call LINK,$@, -I. $(MAIN) $(PRODUCT_SHARED_LIB))
|
||||
|
||||
#
|
|
@ -35,9 +35,9 @@
|
|||
|
||||
export PX4_TARGET_OS ?= nuttx
|
||||
|
||||
# PX4_TARGET_OS can be nuttx, linux, or qurt
|
||||
# PX4_TARGET_OS can be nuttx, posix, or qurt
|
||||
ifeq ($(PX4_TARGET_OS),)
|
||||
$(error Use: make PX4_TARGET_OS=<target> where <target> is nuttx, linux, or qurt)
|
||||
$(error Use: make PX4_TARGET_OS=<target> where <target> is nuttx, posix, or qurt)
|
||||
endif
|
||||
|
||||
#
|
||||
|
|
|
@ -181,7 +181,7 @@ AFLAGS = $(CFLAGS) -D__ASSEMBLY__ \
|
|||
$(EXTRADEFINES) \
|
||||
$(EXTRAAFLAGS)
|
||||
|
||||
LDSCRIPT = $(PX4_BASE)/linux-configs/linuxtest/scripts/ld.script
|
||||
LDSCRIPT = $(PX4_BASE)/posix-configs/posixtest/scripts/ld.script
|
||||
# Flags we pass to the linker
|
||||
#
|
||||
LDFLAGS += \
|
||||
|
|
|
@ -1,7 +1,7 @@
|
|||
#
|
||||
# Copyright (C) 2012-2014 PX4 Development Team. All rights reuint32_tserved.
|
||||
#
|
||||
# 2005 Modified for clang and GCC on Linux:
|
||||
# 2005 Modified for clang and GCC on POSIX:
|
||||
# Author: Mark Charlebois <charlebm@gmail.com>
|
||||
#
|
||||
# Redistribution and use in source and binary forms, with or without
|
||||
|
@ -120,10 +120,10 @@ ifeq ($(CONFIG_BOARD),)
|
|||
$(error Board config does not define CONFIG_BOARD)
|
||||
endif
|
||||
ARCHDEFINES += -DCONFIG_ARCH_BOARD_$(CONFIG_BOARD) \
|
||||
-D__PX4_LINUX \
|
||||
-D__PX4_LINUX -D__PX4_POSIX \
|
||||
-Dnoreturn_function= \
|
||||
-I$(PX4_BASE)/src/lib/eigen \
|
||||
-I$(PX4_BASE)/src/platforms/linux/include \
|
||||
-I$(PX4_BASE)/src/platforms/posix/include \
|
||||
-Wno-error=shadow
|
||||
|
||||
# optimisation flags
|
||||
|
@ -250,7 +250,7 @@ AFLAGS = $(CFLAGS) -D__ASSEMBLY__ \
|
|||
$(EXTRADEFINES) \
|
||||
$(EXTRAAFLAGS)
|
||||
|
||||
LDSCRIPT = $(PX4_BASE)/linux-configs/linuxtest/scripts/ld.script
|
||||
LDSCRIPT = $(PX4_BASE)/posix-configs/posixtest/scripts/ld.script
|
||||
# Flags we pass to the linker
|
||||
#
|
||||
LDFLAGS += $(EXTRALDFLAGS) \
|
||||
|
|
|
@ -31,7 +31,7 @@ upload-serial-px4fmu-v2: $(BUNDLE) $(UPLOADER)
|
|||
$(Q) $(PYTHON) -u $(UPLOADER) --port $(SERIAL_PORTS) $(BUNDLE)
|
||||
|
||||
upload-serial-aerocore:
|
||||
openocd -f $(PX4_BASE)/makefiles/gumstix-aerocore.cfg -c 'init; reset halt; flash write_image erase $(PX4_BASE)/../Bootloader/px4aerocore_bl.bin 0x08000000; flash write_image erase $(PX4_BASE)/Build/aerocore_default.build/firmware.bin 0x08004000; reset run; exit'
|
||||
openocd -f $(PX4_BASE)/makefiles/nuttx/gumstix-aerocore.cfg -c 'init; reset halt; flash write_image erase $(PX4_BASE)/../Bootloader/px4aerocore_bl.bin 0x08000000; flash write_image erase $(PX4_BASE)/Build/aerocore_default.build/firmware.bin 0x08004000; reset run; exit'
|
||||
|
||||
upload-serial-px4-stm32f4discovery: $(BUNDLE) $(UPLOADER)
|
||||
$(Q) $(PYTHON) -u $(UPLOADER) --port $(SERIAL_PORTS) $(BUNDLE)
|
||||
|
|
|
@ -40,7 +40,7 @@ MODULE_COMMAND = blinkm
|
|||
ifeq ($(PX4_TARGET_OS),nuttx)
|
||||
SRCS = blinkm_nuttx.cpp
|
||||
else
|
||||
SRCS = blinkm_linux.cpp
|
||||
SRCS = blinkm_posix.cpp
|
||||
endif
|
||||
|
||||
MAXOPTIMIZATION = -Os
|
||||
|
|
|
@ -35,7 +35,7 @@
|
|||
|
||||
#ifdef __PX4_NUTTX
|
||||
#include "device_nuttx.h"
|
||||
#elif defined (__PX4_LINUX)
|
||||
#elif defined (__PX4_POSIX)
|
||||
#include "vdev.h"
|
||||
#endif
|
||||
|
||||
|
|
|
@ -35,5 +35,5 @@
|
|||
#ifdef __PX4_NUTTX
|
||||
#include "i2c_nuttx.h"
|
||||
#else
|
||||
#include "i2c_linux.h"
|
||||
#include "i2c_posix.h"
|
||||
#endif
|
||||
|
|
|
@ -41,8 +41,10 @@
|
|||
*/
|
||||
|
||||
#include "i2c.h"
|
||||
#ifdef __PX4_LINUX
|
||||
#include <linux/i2c.h>
|
||||
#include <linux/i2c-dev.h>
|
||||
#endif
|
||||
#include <unistd.h>
|
||||
#include <fcntl.h>
|
||||
#include <sys/ioctl.h>
|
|
@ -43,8 +43,10 @@
|
|||
#include "vdev.h"
|
||||
|
||||
#include <px4_i2c.h>
|
||||
#ifdef __PX4_LINUX
|
||||
#include <linux/i2c.h>
|
||||
#include <linux/i2c-dev.h>
|
||||
#endif
|
||||
#include <string>
|
||||
|
||||
namespace device __EXPORT
|
|
@ -44,11 +44,11 @@ SRCS = \
|
|||
spi.cpp \
|
||||
ringbuffer.cpp
|
||||
endif
|
||||
ifeq ($(PX4_TARGET_OS),linux)
|
||||
ifeq ($(PX4_TARGET_OS),posix)
|
||||
SRCS = vdev.cpp \
|
||||
device.cpp \
|
||||
vdev_posix.cpp \
|
||||
i2c_linux.cpp \
|
||||
i2c_posix.cpp \
|
||||
sim.cpp \
|
||||
ringbuffer.cpp
|
||||
endif
|
||||
|
|
|
@ -114,14 +114,14 @@
|
|||
/* no GPIO driver on the PX4_STM32F4DISCOVERY board */
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_ARCH_BOARD_LINUXTEST
|
||||
/* no GPIO driver on the LINUXTEST board */
|
||||
#ifdef CONFIG_ARCH_BOARD_POSIXTEST
|
||||
/* no GPIO driver on the POSIXTEST board */
|
||||
#endif
|
||||
|
||||
#if !defined(CONFIG_ARCH_BOARD_PX4IO_V1) && !defined(CONFIG_ARCH_BOARD_PX4IO_V2) && \
|
||||
!defined(CONFIG_ARCH_BOARD_PX4FMU_V1) && !defined(CONFIG_ARCH_BOARD_PX4FMU_V2) && \
|
||||
!defined(CONFIG_ARCH_BOARD_AEROCORE) && !defined(CONFIG_ARCH_BOARD_PX4_STM32F4DISCOVERY) && \
|
||||
!defined(CONFIG_ARCH_BOARD_LINUXTEST)
|
||||
!defined(CONFIG_ARCH_BOARD_POSIXTEST)
|
||||
# error No CONFIG_ARCH_BOARD_xxxx set
|
||||
#endif
|
||||
/*
|
||||
|
|
|
@ -41,6 +41,6 @@ ifeq ($(PX4_TARGET_OS),nuttx)
|
|||
SRCS = hil.cpp
|
||||
MAXOPTIMIZATION = -Os
|
||||
else
|
||||
SRCS = hil_linux.cpp
|
||||
SRCS = hil_posix.cpp
|
||||
endif
|
||||
|
||||
|
|
|
@ -40,7 +40,7 @@ MODULE_COMMAND = ms5611
|
|||
ifeq ($(PX4_TARGET_OS),nuttx)
|
||||
SRCS = ms5611_nuttx.cpp ms5611_spi.cpp ms5611_i2c.cpp
|
||||
else
|
||||
SRCS = ms5611_linux.cpp ms5611_spi.cpp ms5611_i2c.cpp ms5611_sim.cpp
|
||||
SRCS = ms5611_posix.cpp ms5611_spi.cpp ms5611_i2c.cpp ms5611_sim.cpp
|
||||
endif
|
||||
|
||||
MAXOPTIMIZATION = -Os
|
||||
|
|
|
@ -7,7 +7,7 @@ MODULE_COMMAND = rgbled
|
|||
ifeq ($(PX4_TARGET_OS),nuttx)
|
||||
SRCS = rgbled.cpp
|
||||
else
|
||||
SRCS = rgbled_linux.cpp
|
||||
SRCS = rgbled_posix.cpp
|
||||
endif
|
||||
|
||||
MAXOPTIMIZATION = -Os
|
||||
|
|
|
@ -47,7 +47,7 @@
|
|||
namespace math
|
||||
{
|
||||
|
||||
#if !defined(CONFIG_ARCH_ARM) && !defined(__PX4_LINUX)
|
||||
#if !defined(CONFIG_ARCH_ARM) && !defined(__PX4_POSIX)
|
||||
#define M_PI_F 3.14159265358979323846f
|
||||
#endif
|
||||
|
||||
|
|
|
@ -59,7 +59,7 @@
|
|||
#define HW_ARCH "PX4_STM32F4DISCOVERY"
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_ARCH_BOARD_LINUXTEST
|
||||
#ifdef CONFIG_ARCH_BOARD_POSIXTEST
|
||||
#define HW_ARCH "LINUXTEST"
|
||||
#endif
|
||||
#endif /* VERSION_H_ */
|
||||
|
|
|
@ -52,7 +52,7 @@ ifdef ($(PX4_TARGET_OS),nuttx)
|
|||
SRCS +=
|
||||
state_machine_helper.cpp
|
||||
else
|
||||
SRCS += state_machine_helper_linux.cpp
|
||||
SRCS += state_machine_helper_posix.cpp
|
||||
endif
|
||||
|
||||
MODULE_STACKSIZE = 5000
|
||||
|
|
|
@ -35,5 +35,5 @@
|
|||
#ifdef __PX4_NUTTX
|
||||
#include "mavlink_main_nuttx.h"
|
||||
#else
|
||||
#include "mavlink_main_linux.h"
|
||||
#include "mavlink_main_posix.h"
|
||||
#endif
|
||||
|
|
|
@ -32,7 +32,7 @@
|
|||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file mavlink_main_linux.h
|
||||
* @file mavlink_main_posix.h
|
||||
* MAVLink 1.0 protocol interface definition.
|
||||
*
|
||||
* @author Lorenz Meier <lm@inf.ethz.ch>
|
|
@ -41,7 +41,7 @@
|
|||
*/
|
||||
|
||||
/* XXX trim includes */
|
||||
#include <px4_config.h>
|
||||
#include <nuttx/config.h>
|
||||
#include <unistd.h>
|
||||
#include <pthread.h>
|
||||
#include <stdio.h>
|
||||
|
|
|
@ -42,7 +42,7 @@ SRCS = mavlink_tests.cpp \
|
|||
ifeq ($(PX4_TARGET_NUTTX),nuttx)
|
||||
SRCS += ../mavlink_ftp_nuttx.cpp
|
||||
else
|
||||
SRCS += ../mavlink_ftp_linux.cpp
|
||||
SRCS += ../mavlink_ftp_posix.cpp
|
||||
endif
|
||||
|
||||
INCLUDE_DIRS += $(MAVLINK_SRC)/include/mavlink
|
||||
|
|
|
@ -41,9 +41,9 @@ SRCS += mavlink_main_nuttx.cpp \
|
|||
mavlink_ftp_nuttx.cpp \
|
||||
mavlink_receiver_nuttx.cpp
|
||||
else
|
||||
SRCS += mavlink_main_linux.cpp \
|
||||
mavlink_ftp_linux.cpp \
|
||||
mavlink_receiver_linux.cpp
|
||||
SRCS += mavlink_main_posix.cpp \
|
||||
mavlink_ftp_posix.cpp \
|
||||
mavlink_receiver_posix.cpp
|
||||
endif
|
||||
|
||||
SRCS += mavlink.c \
|
||||
|
|
|
@ -41,7 +41,7 @@ MODULE_PRIORITY = "SCHED_PRIORITY_MAX-5"
|
|||
ifeq ($(PX$_TARGET_OS),nuttx)
|
||||
SRCS = sensors_nuttx.cpp
|
||||
else
|
||||
SRCS = sensors_linux.cpp
|
||||
SRCS = sensors_posix.cpp
|
||||
endif
|
||||
SRCS += sensor_params.c
|
||||
|
||||
|
|
|
@ -46,7 +46,7 @@
|
|||
* @author Anton Babushkin <anton@px4.io>
|
||||
*/
|
||||
|
||||
#include <px4_config.h>
|
||||
#include <nuttx/config.h>
|
||||
|
||||
#include <fcntl.h>
|
||||
#include <poll.h>
|
||||
|
|
|
@ -396,7 +396,7 @@ struct param_info_s {
|
|||
// See https://llvm.org/bugs/show_bug.cgi?format=multiple&id=18006
|
||||
// The following hack is for GCC >=4.8 only. Clang works fine without
|
||||
// this.
|
||||
#ifdef __PX4_LINUX
|
||||
#ifdef __PX4_POSIX
|
||||
__attribute__((aligned(16)));
|
||||
#else
|
||||
;
|
||||
|
|
|
@ -36,8 +36,8 @@
|
|||
#
|
||||
|
||||
SRCS = \
|
||||
px4_linux_impl.cpp \
|
||||
px4_linux_tasks.cpp \
|
||||
px4_posix_impl.cpp \
|
||||
px4_posix_tasks.cpp \
|
||||
work_thread.c \
|
||||
work_queue.c \
|
||||
work_cancel.c \
|
|
@ -32,7 +32,7 @@
|
|||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file px4_linux_impl.cpp
|
||||
* @file px4_posix_impl.cpp
|
||||
*
|
||||
* PX4 Middleware Wrapper Linux Implementation
|
||||
*/
|
|
@ -33,7 +33,7 @@
|
|||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file px4_linux_tasks.c
|
||||
* @file px4_posix_tasks.c
|
||||
* Implementation of existing task API for Linux
|
||||
*/
|
||||
|
|
@ -35,7 +35,7 @@
|
|||
************************************************************************/
|
||||
|
||||
// FIXME - need px4_queue
|
||||
#include <platforms/linux/include/queue.h>
|
||||
#include <platforms/posix/include/queue.h>
|
||||
#include <stddef.h>
|
||||
|
||||
__EXPORT void sq_rem(sq_entry_t *node, sq_queue_t *queue);
|
|
@ -32,7 +32,7 @@
|
|||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file hello_start_linux.cpp
|
||||
* @file hello_start_posix.cpp
|
||||
*
|
||||
* @author Thomas Gubler <thomasgubler@gmail.com>
|
||||
* @author Mark Charlebois <mcharleb@gmail.com>
|
|
@ -38,6 +38,6 @@
|
|||
MODULE_COMMAND = hello
|
||||
|
||||
SRCS = hello_main.cpp \
|
||||
hello_start_linux.cpp \
|
||||
hello_start_posix.cpp \
|
||||
hello_example.cpp
|
||||
|
|
@ -32,7 +32,7 @@
|
|||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file hrt_test_start_linux.cpp
|
||||
* @file hrt_test_start_posix.cpp
|
||||
*
|
||||
* @author Mark Charlebois <mcharleb@gmail.com>
|
||||
*/
|
|
@ -38,6 +38,6 @@
|
|||
MODULE_COMMAND = hrttest
|
||||
|
||||
SRCS = hrt_test_main.cpp \
|
||||
hrt_test_start_linux.cpp \
|
||||
hrt_test_start_posix.cpp \
|
||||
hrt_test.cpp
|
||||
|
|
@ -38,6 +38,6 @@
|
|||
MODULE_COMMAND = vcdevtest
|
||||
|
||||
SRCS = vcdevtest_main.cpp \
|
||||
vcdevtest_start_linux.cpp \
|
||||
vcdevtest_start_posix.cpp \
|
||||
vcdevtest_example.cpp
|
||||
|
|
@ -32,7 +32,7 @@
|
|||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file vcdevtest_start_linux.cpp
|
||||
* @file vcdevtest_start_posix.cpp
|
||||
*
|
||||
* @author Thomas Gubler <thomasgubler@gmail.com>
|
||||
* @author Mark Charlebois <mcharleb@gmail.com>
|
|
@ -38,6 +38,6 @@
|
|||
MODULE_COMMAND = wqueue_test
|
||||
|
||||
SRCS = wqueue_main.cpp \
|
||||
wqueue_start_linux.cpp \
|
||||
wqueue_start_posix.cpp \
|
||||
wqueue_test.cpp
|
||||
|
|
@ -32,7 +32,7 @@
|
|||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file wqueue_start_linux.cpp
|
||||
* @file wqueue_start_posix.cpp
|
||||
*
|
||||
* @author Thomas Gubler <thomasgubler@gmail.com>
|
||||
* @author Mark Charlebois <mcharleb@gmail.com>
|
|
@ -48,7 +48,7 @@
|
|||
* Building for NuttX
|
||||
*/
|
||||
#include <nuttx/analog/adc.h>
|
||||
#elif defined(__PX4_LINUX)
|
||||
#elif defined(__PX4_POSIX)
|
||||
|
||||
// FIXME - this needs to be a px4_adc_msg_s type
|
||||
// Curently copied from NuttX
|
||||
|
|
Some files were not shown because too many files have changed in this diff Show More
Loading…
Reference in New Issue