forked from Archive/PX4-Autopilot
Build fixes for qurt after rebase on PX4 master
Removed the re-definitions of the usage method in the posix/main.cpp file. Added qurt_external_hook interface to call externally linked module. Fixed code format to comply with PX4 style. Added usage information to main app and handled cases for unknown arguments. Fixed the orb_priority interface to use int32_t instead of int. Fixes to get hil working with led changes. Added the config_eagle_adsp.mk file and update the make files to to use new include/lib paths Signed-off-by: Mark Charlebois <charlebm@gmail.com>
This commit is contained in:
parent
4fae86b5ac
commit
54bae34a2c
|
@ -0,0 +1,57 @@
|
|||
#
|
||||
# Makefile for the EAGLE *default* configuration
|
||||
#
|
||||
|
||||
#
|
||||
# Board support modules
|
||||
#
|
||||
MODULES += drivers/device
|
||||
|
||||
#
|
||||
# System commands
|
||||
#
|
||||
MODULES += systemcmds/param
|
||||
MODULES += systemcmds/ver
|
||||
|
||||
#
|
||||
# General system control
|
||||
#
|
||||
MODULES += modules/mavlink
|
||||
|
||||
#
|
||||
# Estimation modules (EKF/ SO3 / other filters)
|
||||
#
|
||||
|
||||
#
|
||||
# Vehicle Control
|
||||
#
|
||||
|
||||
#
|
||||
# Library modules
|
||||
#
|
||||
MODULES += modules/systemlib
|
||||
MODULES += modules/uORB
|
||||
MODULES += modules/dataman
|
||||
|
||||
#
|
||||
# Libraries
|
||||
#
|
||||
MODULES += lib/mathlib
|
||||
MODULES += lib/mathlib/math/filter
|
||||
MODULES += lib/geo
|
||||
MODULES += lib/geo_lookup
|
||||
MODULES += lib/conversion
|
||||
#
|
||||
# Linux port
|
||||
#
|
||||
MODULES += platforms/posix/px4_layer
|
||||
MODULES += platforms/posix/work_queue
|
||||
|
||||
#
|
||||
# Unit tests
|
||||
#
|
||||
|
||||
#
|
||||
# muorb fastrpc changes.
|
||||
#
|
||||
MODULES += modules/muorb/krait
|
|
@ -6,6 +6,7 @@
|
|||
# Board support modules
|
||||
#
|
||||
MODULES += drivers/device
|
||||
MODULES += drivers/boards/sitl
|
||||
#MODULES += drivers/blinkm
|
||||
#MODULES += drivers/pwm_out_sim
|
||||
#MODULES += drivers/rgbled
|
||||
|
|
|
@ -39,14 +39,17 @@
|
|||
#
|
||||
CROSSDEV = arm-linux-gnueabihf-
|
||||
|
||||
CC = $(CROSSDEV)gcc
|
||||
CXX = $(CROSSDEV)g++
|
||||
CPP = $(CROSSDEV)gcc -E
|
||||
LD = $(CROSSDEV)ld
|
||||
AR = $(CROSSDEV)ar rcs
|
||||
NM = $(CROSSDEV)nm
|
||||
OBJCOPY = $(CROSSDEV)objcopy
|
||||
OBJDUMP = $(CROSSDEV)objdump
|
||||
CC ?= $(CROSSDEV)gcc
|
||||
CXX ?= $(CROSSDEV)g++
|
||||
CPP ?= $(CROSSDEV)gcc -E
|
||||
LD ?= $(CROSSDEV)ld
|
||||
AR ?= $(CROSSDEV)ar rcs
|
||||
NM ?= $(CROSSDEV)nm
|
||||
OBJCOPY ?= $(CROSSDEV)objcopy
|
||||
OBJDUMP ?= $(CROSSDEV)objdump
|
||||
ifdef OECORE_NATIVE_SYSROOT
|
||||
AR := $(AR) rcs
|
||||
endif
|
||||
|
||||
# Check if the right version of the toolchain is available
|
||||
#
|
||||
|
@ -57,7 +60,9 @@ ifeq (,$(findstring $(CROSSDEV_VER_FOUND), $(CROSSDEV_VER_SUPPORTED)))
|
|||
$(error Unsupported version of $(CC), found: $(CROSSDEV_VER_FOUND) instead of one in: $(CROSSDEV_VER_SUPPORTED))
|
||||
endif
|
||||
|
||||
EXT_MUORB_LIB_ROOT = /opt/muorb_libs
|
||||
ifndef POSIX_EXT_LIB_ROOT
|
||||
$(error POSIX_EXT_LIB_ROOT is not set)
|
||||
endif
|
||||
|
||||
# XXX this is pulled pretty directly from the fmu Make.defs - needs cleanup
|
||||
|
||||
|
@ -189,7 +194,8 @@ LIBM := $(shell $(CC) $(ARCHCPUFLAGS) -print-file-name=libm.a)
|
|||
EXTRA_LIBS += -lpx4muorb -ladsprpc
|
||||
EXTRA_LIBS += -pthread -lm -lrt
|
||||
|
||||
LIB_DIRS += $(EXT_MUORB_LIB_ROOT)/krait/libs
|
||||
LIB_DIRS += $(POSIX_EXT_LIB_ROOT)/libs
|
||||
INCLUDE_DIRS += $(POSIX_EXT_LIB_ROOT)/inc
|
||||
|
||||
# Flags we pass to the C compiler
|
||||
#
|
||||
|
|
|
@ -5,6 +5,7 @@
|
|||
#
|
||||
# Board support modules
|
||||
#
|
||||
MODULES += drivers/boards/sitl
|
||||
MODULES += drivers/device
|
||||
MODULES += drivers/blinkm
|
||||
MODULES += drivers/pwm_out_sim
|
||||
|
|
|
@ -1,8 +1,19 @@
|
|||
#Added configuration specific flags here.
|
||||
|
||||
ifndef HEXAGON_DRIVERS_ROOT
|
||||
$(error HEXAGON_DRIVERS_ROOT is not set)
|
||||
endif
|
||||
ifndef EAGLE_DRIVERS_SRC
|
||||
$(error EAGLE_DRIVERS_SRC is not set)
|
||||
endif
|
||||
|
||||
INCLUDE_DIRS += $(HEXAGON_DRIVERS_ROOT)/inc
|
||||
|
||||
# For Actual flight we need to link against the driver dynamic libraries
|
||||
LDFLAGS += -L${DSPAL_ROOT}/mpu_spi/hexagon_Debug_dynamic_toolv64/ship -lmpu9x50
|
||||
LDFLAGS += -L${DSPAL_ROOT}/uart_esc/hexagon_Debug_dynamic_toolv64/ship -luart_esc
|
||||
LDFLAGS += -L${HEXAGON_DRIVERS_ROOT}/libs -lmpu9x50
|
||||
LDFLAGS += -luart_esc
|
||||
LDFLAGS += -lcsr_gps
|
||||
LDFLAGS += -lrc_receiver
|
||||
|
||||
#
|
||||
# Makefile for the EAGLE QuRT *default* configuration
|
||||
|
@ -13,8 +24,10 @@ LDFLAGS += -L${DSPAL_ROOT}/uart_esc/hexagon_Debug_dynamic_toolv64/ship -luart_es
|
|||
#
|
||||
MODULES += drivers/device
|
||||
MODULES += modules/sensors
|
||||
#MODULES += platforms/qurt/drivers/mpu9x50
|
||||
#MODULES += platforms/qurt/drivers/uart_esc
|
||||
MODULES += $(EAGLE_DRIVERS_SRC)/mpu9x50
|
||||
MODULES += $(EAGLE_DRIVERS_SRC)/uart_esc
|
||||
MODULES += $(EAGLE_DRIVERS_SRC)/rc_receiver
|
||||
MODULES += $(EAGLE_DRIVERS_SRC)/csr_gps
|
||||
|
||||
#
|
||||
# System commands
|
||||
|
@ -47,6 +60,7 @@ MODULES += modules/systemlib/mixer
|
|||
MODULES += modules/uORB
|
||||
#MODULES += modules/dataman
|
||||
MODULES += modules/commander
|
||||
MODULES += modules/controllib
|
||||
|
||||
#
|
||||
# Libraries
|
||||
|
@ -61,6 +75,7 @@ MODULES += lib/conversion
|
|||
# QuRT port
|
||||
#
|
||||
MODULES += platforms/qurt/px4_layer
|
||||
MODULES += platforms/posix/work_queue
|
||||
|
||||
#
|
||||
# Unit tests
|
||||
|
|
|
@ -6,6 +6,7 @@
|
|||
# Board support modules
|
||||
#
|
||||
MODULES += drivers/device
|
||||
MODULES += drivers/boards/sitl
|
||||
#MODULES += drivers/blinkm
|
||||
MODULES += drivers/pwm_out_sim
|
||||
MODULES += drivers/led
|
||||
|
|
|
@ -53,8 +53,7 @@ $(FIRMWARES): $(BUILD_DIR)%.build/firmware.a: generateuorbtopicheaders
|
|||
WORK_DIR=$(work_dir) \
|
||||
$(FIRMWARE_GOAL)
|
||||
|
||||
HEXAGON_TOOLS_ROOT = /opt/6.4.05
|
||||
#V_ARCH = v4
|
||||
HEXAGON_TOOLS_ROOT ?= /opt/6.4.03
|
||||
V_ARCH = v5
|
||||
HEXAGON_CLANG_BIN = $(addsuffix /qc/bin,$(HEXAGON_TOOLS_ROOT))
|
||||
SIM = $(HEXAGON_CLANG_BIN)/hexagon-sim
|
||||
|
|
|
@ -36,11 +36,11 @@
|
|||
#$(info TOOLCHAIN gnu-arm-eabi)
|
||||
|
||||
#
|
||||
# Stop making if ADSP_LIB_ROOT is not set. This defines the path to
|
||||
# DspAL headers and driver headers
|
||||
# Stop making if DSPAL paths are not set. This defines the path to
|
||||
# DspAL headers and libs
|
||||
#
|
||||
ifndef DSPAL_ROOT
|
||||
$(error DSPAL_ROOT is not set)
|
||||
ifndef DSPAL_INCS
|
||||
$(error DSPAL_INCS is not set)
|
||||
endif
|
||||
|
||||
# Toolchain commands. Normally only used inside this file.
|
||||
|
@ -57,7 +57,6 @@ HEXAGON_ISS_DIR = $(HEXAGON_TOOLS_ROOT)/qc/lib/iss
|
|||
TOOLSLIB = $(HEXAGON_TOOLS_ROOT)/dinkumware/lib/$(V_ARCH)/G0
|
||||
QCTOOLSLIB = $(HEXAGON_TOOLS_ROOT)/qc/lib/$(V_ARCH)/G0
|
||||
QURTLIB = $(HEXAGON_SDK_ROOT)/lib/common/qurt/ADSP$(V_ARCH)MP/lib
|
||||
#DSPAL = $(PX4_BASE)/../dspal_libs/libdspal.a
|
||||
|
||||
|
||||
CC = $(HEXAGON_CLANG_BIN)/$(CROSSDEV)clang
|
||||
|
@ -93,8 +92,7 @@ DYNAMIC_LIBS = \
|
|||
|
||||
# Check if the right version of the toolchain is available
|
||||
#
|
||||
CROSSDEV_VER_SUPPORTED = 6.4.03
|
||||
#CROSSDEV_VER_SUPPORTED = 6.4.05
|
||||
CROSSDEV_VER_SUPPORTED = 6.4.03 6.4.05
|
||||
CROSSDEV_VER_FOUND = $(shell $(CC) --version | sed -n 's/^.*version \([\. 0-9]*\),.*$$/\1/p')
|
||||
|
||||
ifeq (,$(findstring $(CROSSDEV_VER_FOUND), $(CROSSDEV_VER_SUPPORTED)))
|
||||
|
@ -122,18 +120,17 @@ ARCHDEFINES += -DCONFIG_ARCH_BOARD_$(CONFIG_BOARD) \
|
|||
-Dnoreturn_function= \
|
||||
-D__EXPORT= \
|
||||
-Drestrict= \
|
||||
-D_DEBUG \
|
||||
-I$(DSPAL_ROOT)/ \
|
||||
-I$(DSPAL_ROOT)/dspal/include \
|
||||
-I$(DSPAL_ROOT)/dspal/sys \
|
||||
-I$(DSPAL_ROOT)/dspal/sys/sys \
|
||||
-I$(DSPAL_ROOT)/mpu_spi/inc/ \
|
||||
-I$(DSPAL_ROOT)/uart_esc/inc/ \
|
||||
-D_DEBUG \
|
||||
-I$(DSPAL_INCS)/ \
|
||||
-I$(DSPAL_INCS)/dspal/include \
|
||||
-I$(DSPAL_INCS)/dspal/sys \
|
||||
-I$(DSPAL_INCS)/dspal/sys/sys \
|
||||
-I$(HEXAGON_TOOLS_ROOT)/gnu/hexagon/include \
|
||||
-I$(PX4_BASE)/src/lib/eigen \
|
||||
-I$(PX4_BASE)/src/platforms/qurt/include \
|
||||
-I$(PX4_BASE)/src/platforms/posix/include \
|
||||
-I$(PX4_BASE)/mavlink/include/mavlink \
|
||||
-I$(PX4_BASE)/../inc \
|
||||
-I$(QURTLIB)/..//include \
|
||||
-I$(HEXAGON_SDK_ROOT)/inc \
|
||||
-I$(HEXAGON_SDK_ROOT)/inc/stddef \
|
||||
|
|
|
@ -5,6 +5,7 @@ uint8 RC_INPUT_SOURCE_PX4IO_SPEKTRUM = 3
|
|||
uint8 RC_INPUT_SOURCE_PX4IO_SBUS = 4
|
||||
uint8 RC_INPUT_SOURCE_PX4IO_ST24 = 5
|
||||
uint8 RC_INPUT_SOURCE_MAVLINK = 6
|
||||
uint8 RC_INPUT_SOURCE_QURT = 7
|
||||
|
||||
uint8 RC_INPUT_MAX_CHANNELS = 18 # Maximum number of R/C input channels in the system. S.Bus has up to 18 channels.
|
||||
|
||||
|
|
|
@ -0,0 +1,8 @@
|
|||
#
|
||||
# Board-specific startup code for SITL
|
||||
#
|
||||
|
||||
SRCS = \
|
||||
sitl_led.c
|
||||
|
||||
MAXOPTIMIZATION = -Os
|
|
@ -0,0 +1,81 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2013 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file sitl_led.c
|
||||
*
|
||||
* sitl LED backend.
|
||||
*/
|
||||
|
||||
#include <px4_config.h>
|
||||
#include <px4_log.h>
|
||||
#include <stdbool.h>
|
||||
|
||||
__BEGIN_DECLS
|
||||
extern void led_init(void);
|
||||
extern void led_on(int led);
|
||||
extern void led_off(int led);
|
||||
extern void led_toggle(int led);
|
||||
__END_DECLS
|
||||
|
||||
static bool _led_state[2] = { false , false };
|
||||
|
||||
__EXPORT void led_init()
|
||||
{
|
||||
PX4_DEBUG("LED_INIT");
|
||||
}
|
||||
|
||||
__EXPORT void led_on(int led)
|
||||
{
|
||||
if (led == 1 || led == 0) {
|
||||
PX4_DEBUG("LED%d_ON", led);
|
||||
_led_state[led] = true;
|
||||
}
|
||||
}
|
||||
|
||||
__EXPORT void led_off(int led)
|
||||
{
|
||||
if (led == 1 || led == 0) {
|
||||
PX4_DEBUG("LED%d_OFF", led);
|
||||
_led_state[led] = false;
|
||||
}
|
||||
}
|
||||
|
||||
__EXPORT void led_toggle(int led)
|
||||
{
|
||||
if (led == 1 || led == 0) {
|
||||
_led_state[led] = !_led_state[led];
|
||||
PX4_DEBUG("LED%d_TOGGLE: %s", led, _led_state[led] ? "ON" : "OFF");
|
||||
|
||||
}
|
||||
}
|
|
@ -38,7 +38,7 @@
|
|||
#include <string>
|
||||
#include <pthread.h>
|
||||
#include "uORB/uORBCommunicator.hpp"
|
||||
#include <px4_muorb/px4muorb_KraitRpcWrapper.hpp>
|
||||
#include <px4muorb_KraitRpcWrapper.hpp>
|
||||
#include <map>
|
||||
#include "drivers/drv_hrt.h"
|
||||
|
||||
|
|
|
@ -141,10 +141,6 @@ static void usage()
|
|||
|
||||
__BEGIN_DECLS
|
||||
extern int simulator_main(int argc, char *argv[]);
|
||||
extern void led_init(void);
|
||||
extern void led_on(int led);
|
||||
extern void led_off(int led);
|
||||
extern void led_toggle(int led);
|
||||
__END_DECLS
|
||||
|
||||
extern "C" {
|
||||
|
@ -198,39 +194,3 @@ int simulator_main(int argc, char *argv[])
|
|||
}
|
||||
|
||||
}
|
||||
|
||||
bool static _led_state[2] = { false , false };
|
||||
|
||||
__EXPORT void led_init()
|
||||
{
|
||||
PX4_DEBUG("LED_INIT");
|
||||
}
|
||||
|
||||
__EXPORT void led_on(int led)
|
||||
{
|
||||
if (led == 1 || led == 0)
|
||||
{
|
||||
PX4_DEBUG("LED%d_ON", led);
|
||||
_led_state[led] = true;
|
||||
}
|
||||
}
|
||||
|
||||
__EXPORT void led_off(int led)
|
||||
{
|
||||
if (led == 1 || led == 0)
|
||||
{
|
||||
PX4_DEBUG("LED%d_OFF", led);
|
||||
_led_state[led] = false;
|
||||
}
|
||||
}
|
||||
|
||||
__EXPORT void led_toggle(int led)
|
||||
{
|
||||
if (led == 1 || led == 0)
|
||||
{
|
||||
_led_state[led] = !_led_state[led];
|
||||
PX4_DEBUG("LED%d_TOGGLE: %s", led, _led_state[led] ? "ON" : "OFF");
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -284,7 +284,7 @@ int orb_group_count(const struct orb_metadata *meta)
|
|||
* priority, independent of the startup order of the associated publishers.
|
||||
* @return OK on success, ERROR otherwise with errno set accordingly.
|
||||
*/
|
||||
int orb_priority(int handle, int *priority)
|
||||
int orb_priority(int handle, int32_t *priority)
|
||||
{
|
||||
return uORB::Manager::get_instance()->orb_priority(handle, priority);
|
||||
}
|
||||
|
|
|
@ -269,7 +269,7 @@ public:
|
|||
* priority, independent of the startup order of the associated publishers.
|
||||
* @return OK on success, ERROR otherwise with errno set accordingly.
|
||||
*/
|
||||
int orb_priority(int handle, int *priority) ;
|
||||
int orb_priority(int handle, int32_t *priority) ;
|
||||
|
||||
/**
|
||||
* Set the minimum interval between which updates are seen for a subscription.
|
||||
|
|
|
@ -166,7 +166,7 @@ int uORB::Manager::orb_stat(int handle, uint64_t *time)
|
|||
return ioctl(handle, ORBIOCLASTUPDATE, (unsigned long)(uintptr_t)time);
|
||||
}
|
||||
|
||||
int uORB::Manager::orb_priority(int handle, int *priority)
|
||||
int uORB::Manager::orb_priority(int handle, int32_t *priority)
|
||||
{
|
||||
return ioctl(handle, ORBIOCGPRIORITY, (unsigned long)(uintptr_t)priority);
|
||||
}
|
||||
|
|
|
@ -172,7 +172,7 @@ int uORB::Manager::orb_stat(int handle, uint64_t *time)
|
|||
return px4_ioctl(handle, ORBIOCLASTUPDATE, (unsigned long)(uintptr_t)time);
|
||||
}
|
||||
|
||||
int uORB::Manager::orb_priority(int handle, int *priority)
|
||||
int uORB::Manager::orb_priority(int handle, int32_t *priority)
|
||||
{
|
||||
return px4_ioctl(handle, ORBIOCGPRIORITY, (unsigned long)(uintptr_t)priority);
|
||||
}
|
||||
|
|
|
@ -127,6 +127,7 @@ __EXPORT extern uint64_t hrt_absolute_time(void);
|
|||
|
||||
__EXPORT extern const char *__px4_log_level_str[5];
|
||||
__EXPORT extern int __px4_log_level_current;
|
||||
__END_DECLS
|
||||
|
||||
// __px4_log_level_current will be initialized to PX4_LOG_LEVEL_AT_RUN_TIME
|
||||
#define PX4_LOG_LEVEL_AT_RUN_TIME _PX4_LOG_LEVEL_WARN
|
||||
|
@ -162,22 +163,6 @@ __EXPORT extern int __px4_log_level_current;
|
|||
****************************************************************************/
|
||||
|
||||
|
||||
/****************************************************************************
|
||||
* __px4_log_named_cond:
|
||||
* Convert a message in the form:
|
||||
* PX4_LOG_COND(__dbg_enabled, "val is %d", val);
|
||||
* to
|
||||
* printf("%-5s val is %d\n", "LOG", val);
|
||||
* if the first arg/condition is true.
|
||||
****************************************************************************/
|
||||
#define __px4_log_named_cond(name, cond, FMT, ...) \
|
||||
__px4__log_startcond(cond)\
|
||||
"%s " \
|
||||
FMT\
|
||||
__px4__log_end_fmt \
|
||||
,name, ##__VA_ARGS__\
|
||||
__px4__log_endline
|
||||
|
||||
/****************************************************************************
|
||||
* __px4_log_named_cond:
|
||||
* Convert a message in the form:
|
||||
|
@ -389,5 +374,4 @@ __EXPORT extern int __px4_log_level_current;
|
|||
#endif
|
||||
#define PX4_LOG_NAMED(name, FMT, ...) __px4_log_named_cond(name, true, FMT, ##__VA_ARGS__)
|
||||
#define PX4_LOG_NAMED_COND(name, cond, FMT, ...) __px4_log_named_cond(name, cond, FMT, ##__VA_ARGS__)
|
||||
__END_DECLS
|
||||
#endif
|
||||
|
|
|
@ -1,190 +0,0 @@
|
|||
diff --git a/src/include/mavlink/mavlink_log.h b/src/include/mavlink/mavlink_log.h
|
||||
index 4ba2f98..a7b664e 100644
|
||||
--- a/src/include/mavlink/mavlink_log.h
|
||||
+++ b/src/include/mavlink/mavlink_log.h
|
||||
@@ -106,10 +106,11 @@ __EXPORT void mavlink_vasprintf(int _fd, int severity, const char *fmt, ...);
|
||||
* @param _fd A file descriptor returned from open(MAVLINK_LOG_DEVICE, 0);
|
||||
* @param _text The text to log;
|
||||
*/
|
||||
-#define mavlink_and_console_log_emergency(_fd, _text, ...) mavlink_vasprintf(_fd, MAVLINK_IOC_SEND_TEXT_EMERGENCY, _text, ##__VA_ARGS__); \
|
||||
- fprintf(stderr, "telem> "); \
|
||||
+#define mavlink_and_console_log_emergency(_fd, _text, ...) mavlink_vasprintf(_fd, MAVLINK_IOC_SEND_TEXT_EMERGENCY, _text, ##__VA_ARGS__);
|
||||
+/* fprintf(stderr, "telem> "); \
|
||||
fprintf(stderr, _text, ##__VA_ARGS__); \
|
||||
fprintf(stderr, "\n");
|
||||
+*/
|
||||
|
||||
/**
|
||||
* Send a mavlink critical message and print to console.
|
||||
@@ -117,10 +118,11 @@ __EXPORT void mavlink_vasprintf(int _fd, int severity, const char *fmt, ...);
|
||||
* @param _fd A file descriptor returned from open(MAVLINK_LOG_DEVICE, 0);
|
||||
* @param _text The text to log;
|
||||
*/
|
||||
-#define mavlink_and_console_log_critical(_fd, _text, ...) mavlink_vasprintf(_fd, MAVLINK_IOC_SEND_TEXT_CRITICAL, _text, ##__VA_ARGS__); \
|
||||
- fprintf(stderr, "telem> "); \
|
||||
+#define mavlink_and_console_log_critical(_fd, _text, ...) mavlink_vasprintf(_fd, MAVLINK_IOC_SEND_TEXT_CRITICAL, _text, ##__VA_ARGS__)
|
||||
+/* fprintf(stderr, "telem> "); \
|
||||
fprintf(stderr, _text, ##__VA_ARGS__); \
|
||||
fprintf(stderr, "\n");
|
||||
+*/
|
||||
|
||||
/**
|
||||
* Send a mavlink emergency message and print to console.
|
||||
@@ -128,11 +130,11 @@ __EXPORT void mavlink_vasprintf(int _fd, int severity, const char *fmt, ...);
|
||||
* @param _fd A file descriptor returned from open(MAVLINK_LOG_DEVICE, 0);
|
||||
* @param _text The text to log;
|
||||
*/
|
||||
-#define mavlink_and_console_log_info(_fd, _text, ...) mavlink_vasprintf(_fd, MAVLINK_IOC_SEND_TEXT_INFO, _text, ##__VA_ARGS__); \
|
||||
- fprintf(stderr, "telem> "); \
|
||||
+#define mavlink_and_console_log_info(_fd, _text, ...) mavlink_vasprintf(_fd, MAVLINK_IOC_SEND_TEXT_INFO, _text, ##__VA_ARGS__);
|
||||
+/* fprintf(stderr, "telem> "); \
|
||||
fprintf(stderr, _text, ##__VA_ARGS__); \
|
||||
fprintf(stderr, "\n");
|
||||
-
|
||||
+*/
|
||||
struct mavlink_logmessage {
|
||||
char text[MAVLINK_LOG_MAXLEN + 1];
|
||||
unsigned char severity;
|
||||
diff --git a/src/lib/eigen b/src/lib/eigen
|
||||
--- a/src/lib/eigen
|
||||
+++ b/src/lib/eigen
|
||||
@@ -1 +1 @@
|
||||
-Subproject commit e7850ed81f9c469e02df496ef09ae32ec0379b71
|
||||
+Subproject commit e7850ed81f9c469e02df496ef09ae32ec0379b71-dirty
|
||||
diff --git a/src/modules/commander/PreflightCheck.cpp b/src/modules/commander/PreflightCheck.cpp
|
||||
index bbf5f8e..50c7d8b 100644
|
||||
--- a/src/modules/commander/PreflightCheck.cpp
|
||||
+++ b/src/modules/commander/PreflightCheck.cpp
|
||||
@@ -378,6 +378,14 @@ bool preflightCheck(int mavlink_fd, bool checkMag, bool checkAcc, bool checkGyro
|
||||
}
|
||||
}
|
||||
|
||||
+
|
||||
+#ifdef __PX4_QURT
|
||||
+ // WARNING: Preflight checks are important and should be added back when
|
||||
+ // all the sensors are supported
|
||||
+ PX4_WARN("WARNING: Preflight checks PASS always.");
|
||||
+ failed = false;
|
||||
+#endif
|
||||
+
|
||||
/* Report status */
|
||||
return !failed;
|
||||
}
|
||||
diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp
|
||||
index 971e086..c165322 100644
|
||||
--- a/src/modules/commander/commander.cpp
|
||||
+++ b/src/modules/commander/commander.cpp
|
||||
@@ -1836,8 +1836,13 @@ int commander_thread_main(int argc, char *argv[])
|
||||
}
|
||||
|
||||
/* RC input check */
|
||||
+#ifndef __PX4_QURT
|
||||
if (!(status.rc_input_mode == vehicle_status_s::RC_IN_MODE_OFF) && !status.rc_input_blocked && sp_man.timestamp != 0 &&
|
||||
- hrt_absolute_time() < sp_man.timestamp + (uint64_t)(rc_loss_timeout * 1e6f)) {
|
||||
+ hrt_absolute_time() < sp_man.timestamp + (uint64_t)(rc_loss_timeout * 1e6f)) {
|
||||
+#else
|
||||
+ // HACK: remove old data check due to timestamp issue in QURT
|
||||
+ if (!(status.rc_input_mode == vehicle_status_s::RC_IN_MODE_OFF) && !status.rc_input_blocked && sp_man.timestamp != 0 ) {
|
||||
+#endif
|
||||
/* handle the case where RC signal was regained */
|
||||
if (!status.rc_signal_found_once) {
|
||||
status.rc_signal_found_once = true;
|
||||
@@ -2526,7 +2531,7 @@ set_control_mode()
|
||||
/* set vehicle_control_mode according to set_navigation_state */
|
||||
control_mode.flag_armed = armed.armed;
|
||||
control_mode.flag_external_manual_override_ok = (!status.is_rotary_wing && !status.is_vtol);
|
||||
- control_mode.flag_system_hil_enabled = status.hil_state == vehicle_status_s::HIL_STATE_ON;
|
||||
+ //control_mode.flag_system_hil_enabled = status.hil_state == vehicle_status_s::HIL_STATE_ON;
|
||||
control_mode.flag_control_offboard_enabled = false;
|
||||
|
||||
switch (status.nav_state) {
|
||||
diff --git a/src/modules/position_estimator_inav/position_estimator_inav_main.c b/src/modules/position_estimator_inav/position_estimator_inav_main.c
|
||||
index 892e50f..7ac6776 100644
|
||||
--- a/src/modules/position_estimator_inav/position_estimator_inav_main.c
|
||||
+++ b/src/modules/position_estimator_inav/position_estimator_inav_main.c
|
||||
@@ -384,7 +384,13 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
|
||||
};
|
||||
|
||||
/* wait for initial baro value */
|
||||
+#ifdef __PX4_QURT
|
||||
+ // WARNING skipping
|
||||
+ PX4_WARN("Hacked to skip baro initialization for testing.");
|
||||
+ bool wait_baro = false;
|
||||
+#else
|
||||
bool wait_baro = true;
|
||||
+#endif
|
||||
|
||||
thread_running = true;
|
||||
|
||||
diff --git a/src/modules/sensors/sensors.cpp b/src/modules/sensors/sensors.cpp
|
||||
index 3fa4458..0ef1883 100644
|
||||
--- a/src/modules/sensors/sensors.cpp
|
||||
+++ b/src/modules/sensors/sensors.cpp
|
||||
@@ -1099,7 +1099,12 @@ Sensors::gyro_poll(struct sensor_combined_s &raw)
|
||||
raw.gyro_raw[1] = gyro_report.y_raw;
|
||||
raw.gyro_raw[2] = gyro_report.z_raw;
|
||||
|
||||
+#ifdef __PX4_QURT
|
||||
+// Temporary fix required due to lack of time sync between apps and dsp cores
|
||||
+ raw.timestamp = hrt_absolute_time();
|
||||
+#else
|
||||
raw.timestamp = gyro_report.timestamp;
|
||||
+#endif
|
||||
raw.gyro_errcount = gyro_report.error_count;
|
||||
raw.gyro_temp = gyro_report.temperature;
|
||||
}
|
||||
@@ -2068,6 +2073,7 @@ Sensors::task_main()
|
||||
|
||||
/* start individual sensors */
|
||||
int ret = 0;
|
||||
+#if 0
|
||||
do { /* create a scope to handle exit with break */
|
||||
ret = accel_init();
|
||||
if (ret) break;
|
||||
@@ -2091,7 +2097,7 @@ Sensors::task_main()
|
||||
}
|
||||
return;
|
||||
}
|
||||
-
|
||||
+#endif
|
||||
/*
|
||||
* do subscriptions
|
||||
*/
|
||||
diff --git a/src/systemcmds/mixer/mixer.cpp b/src/systemcmds/mixer/mixer.cpp
|
||||
index 83a9378..ec86faf 100644
|
||||
--- a/src/systemcmds/mixer/mixer.cpp
|
||||
+++ b/src/systemcmds/mixer/mixer.cpp
|
||||
@@ -118,6 +118,8 @@ load(const char *devname, const char *fname)
|
||||
return 1;
|
||||
}
|
||||
|
||||
+#ifndef __PX4_QURT
|
||||
+
|
||||
if (load_mixer_file(fname, &buf[0], sizeof(buf)) < 0) {
|
||||
warnx("can't load mixer: %s", fname);
|
||||
return 1;
|
||||
@@ -125,6 +127,24 @@ load(const char *devname, const char *fname)
|
||||
|
||||
/* XXX pass the buffer to the device */
|
||||
int ret = px4_ioctl(dev, MIXERIOCLOADBUF, (unsigned long)buf);
|
||||
+#else
|
||||
+ char newbuf[] =
|
||||
+ "R: 4x 10000 10000 10000 0\n"
|
||||
+ "M: 1\n"
|
||||
+ "O: 10000 10000 0 -10000 10000\n"
|
||||
+ "S: 0 4 10000 10000 0 -10000 10000\n"
|
||||
+ "M: 1\n"
|
||||
+ "O: 10000 10000 0 -10000 10000\n"
|
||||
+ "S: 0 5 10000 10000 0 -10000 10000\n"
|
||||
+ "M: 1\n"
|
||||
+ "O: 10000 10000 0 -10000 10000\n"
|
||||
+ "S: 0 6 10000 10000 0 -10000 10000\n"
|
||||
+ "M: 1\n"
|
||||
+ "O: 10000 10000 0 -10000 10000\n"
|
||||
+ "S: 0 7 10000 10000 0 -10000 10000\n";
|
||||
+ /* XXX pass the buffer to the device */
|
||||
+ int ret = px4_ioctl(dev, MIXERIOCLOADBUF, (unsigned long)newbuf);
|
||||
+#endif
|
||||
|
||||
if (ret < 0) {
|
||||
warnx("error loading mixers from %s", fname);
|
|
@ -0,0 +1,175 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2015 Mark Charlebois. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
/**
|
||||
* @file commands_muorb_test.c
|
||||
* Commands to run for the "qurt_muorb_test" config
|
||||
*
|
||||
* @author Mark Charlebois <charlebm@gmail.com>
|
||||
*/
|
||||
|
||||
const char *get_commands()
|
||||
{
|
||||
|
||||
static const char *commands =
|
||||
"uorb start\n"
|
||||
"param set CAL_GYRO0_ID 2293760\n"
|
||||
"param set CAL_ACC0_ID 1310720\n"
|
||||
"param set CAL_ACC1_ID 1376256\n"
|
||||
"param set CAL_MAG0_ID 196608\n"
|
||||
"commander start\n"
|
||||
"param set RC_RECEIVER_TYPE 1\n"
|
||||
"rc_receiver start -D /dev/tty-1\n"
|
||||
"attitude_estimator_q start\n"
|
||||
"position_estimator_inav start\n"
|
||||
//"ekf_att_pos_estimator start\n"
|
||||
"mc_pos_control start\n"
|
||||
"mc_att_control start\n"
|
||||
"sleep 1\n"
|
||||
|
||||
// Channel mapping for Spektrum DX8
|
||||
"param set RC_MAP_THROTTLE 1\n"
|
||||
"param set RC_MAP_ROLL 2\n"
|
||||
"param set RC_MAP_PITCH 3\n"
|
||||
"param set RC_MAP_YAW 4\n"
|
||||
"param set RC_MAP_MODE_SW 5\n"
|
||||
"param set RC_MAP_POSCTL_SW 6\n"
|
||||
|
||||
// RC calibration for Spektrum DX8
|
||||
"param set RC1_MAX 852\n"
|
||||
"param set RC1_MIN 171\n"
|
||||
"param set RC1_TRIM 171\n"
|
||||
"param set RC1_REV 1\n"
|
||||
"param set RC2_MAX 852\n"
|
||||
"param set RC2_MIN 171\n"
|
||||
"param set RC2_TRIM 512\n"
|
||||
"param set RC2_REV -1\n"
|
||||
"param set RC3_MAX 852\n"
|
||||
"param set RC3_MIN 171\n"
|
||||
"param set RC3_TRIM 512\n"
|
||||
"param set RC3_REV 1\n"
|
||||
"param set RC4_MAX 852\n"
|
||||
"param set RC4_MIN 171\n"
|
||||
"param set RC4_TRIM 514\n"
|
||||
"param set RC4_REV -1\n"
|
||||
"param set RC5_MAX 852\n"
|
||||
"param set RC5_MIN 171\n"
|
||||
"param set RC5_TRIM 512\n"
|
||||
"param set RC5_REV 1\n"
|
||||
"param set RC6_MAX 852\n"
|
||||
"param set RC6_MIN 171\n"
|
||||
"param set RC6_TRIM 171\n"
|
||||
"param set RC6_REV 1\n"
|
||||
|
||||
// // RC calibration for DX6i
|
||||
// "param set RC1_MAX 2015\n"
|
||||
// "param set RC1_MIN 996\n"
|
||||
// "param set RC1_TRIM 1502\n"
|
||||
// "param set RC1_REV -1\n"
|
||||
// "param set RC2_MAX 2016 \n"
|
||||
// "param set RC2_MIN 995\n"
|
||||
// "param set RC2_TRIM 1500\n"
|
||||
// "param set RC3_MAX 2003\n"
|
||||
// "param set RC3_MIN 992\n"
|
||||
// "param set RC3_TRIM 992\n"
|
||||
// "param set RC4_MAX 2011\n"
|
||||
// "param set RC4_MIN 997\n"
|
||||
// "param set RC4_TRIM 1504\n"
|
||||
// "param set RC4_REV -1\n"
|
||||
// "param set RC6_MAX 2016\n"
|
||||
// "param set RC6_MIN 992\n"
|
||||
// "param set RC6_TRIM 1504\n"
|
||||
// "param set RC_CHAN_CNT 8\n"
|
||||
// "param set RC_MAP_MODE_SW 5\n"
|
||||
// "param set RC_MAP_POSCTL_SW 7\n"
|
||||
// "param set RC_MAP_RETURN_SW 8\n"
|
||||
|
||||
"sensors start\n"
|
||||
"param set MC_YAW_P 7.0\n"
|
||||
"param set MC_YAWRATE_P 0.1125\n"
|
||||
"param set MC_YAWRATE_I 0.0\n"
|
||||
"param set MC_YAWRATE_D 0\n"
|
||||
"param set MC_PITCH_P 6.0\n"
|
||||
"param set MC_PITCHRATE_P 0.125\n"
|
||||
"param set MC_PITCHRATE_I 0.0\n"
|
||||
"param set MC_PITCHRATE_D 0.0\n"
|
||||
"param set MC_ROLL_P 6.0\n"
|
||||
"param set MC_ROLLRATE_P 0.1125\n"
|
||||
"param set MC_ROLLRATE_I 0.0\n"
|
||||
"param set MC_ROLLRATE_D 0.0\n"
|
||||
"param set ATT_W_MAG 0.00\n"
|
||||
"param set PE_MAG_NOISE 1.0f\n" // ekf_att_pos only
|
||||
"param set SENS_BOARD_ROT 6\n"
|
||||
|
||||
"param set CAL_GYRO0_XOFF 0.0\n"
|
||||
"param set CAL_GYRO0_YOFF 0.0\n"
|
||||
"param set CAL_GYRO0_ZOFF 0.0\n"
|
||||
"param set CAL_GYRO0_XSCALE 1.000000\n"
|
||||
"param set CAL_GYRO0_YSCALE 1.000000\n"
|
||||
"param set CAL_GYRO0_ZSCALE 1.000000\n"
|
||||
"param set CAL_ACC0_XOFF 0.0\n"
|
||||
"param set CAL_ACC0_YOFF 0.0\n"
|
||||
"param set CAL_ACC0_ZOFF 0.0\n"
|
||||
"param set CAL_ACC0_XSCALE 1.0\n"
|
||||
"param set CAL_ACC0_YSCALE 1.0\n"
|
||||
"param set CAL_ACC0_ZSCALE 1.0\n"
|
||||
// "param set CAL_ACC0_XOFF 0.064189\n"
|
||||
// "param set CAL_ACC0_YOFF 0.153990\n"
|
||||
// "param set CAL_ACC0_ZOFF -0.000567\n"
|
||||
"param set MPU_GYRO_LPF_ENUM 4\n"
|
||||
"param set MPU_ACC_LPF_ENUM 4\n"
|
||||
"param set MPU_SAMPLE_RATE_ENUM 2\n"
|
||||
"sleep 1\n"
|
||||
"mpu9x50 start -D /dev/spi-1\n"
|
||||
"uart_esc start -D /dev/tty-2\n"
|
||||
"csr_gps start -D /dev/tty-3\n"
|
||||
"param set MAV_TYPE 2\n"
|
||||
"list_devices\n"
|
||||
"list_files\n"
|
||||
"list_tasks\n"
|
||||
"list_topics\n"
|
||||
|
||||
;
|
||||
|
||||
return commands;
|
||||
|
||||
}
|
||||
|
||||
/*
|
||||
simulator numbers
|
||||
"param set MC_YAW_P 1.5\n"
|
||||
"param set MC_PITCH_P 3.0\n"
|
||||
"param set MC_ROLL_P 3.0\n"
|
||||
"param set MC_YAWRATE_P 0.2\n"
|
||||
"param set MC_PITCHRATE_P 0.03\n"
|
||||
"param set MC_ROLLRATE_P 0.03\n"
|
||||
*/
|
|
@ -56,7 +56,7 @@ const char *get_commands()
|
|||
"mc_pos_control start\n"
|
||||
"mc_att_control start\n"
|
||||
"sleep 1\n"
|
||||
"hil mode_pwm\n"
|
||||
"pwm_out_sim mode_pwm\n"
|
||||
"param set RC1_MAX 2015\n"
|
||||
"param set RC1_MIN 996\n"
|
||||
"param set RC1_TRIM 1502\n"
|
||||
|
|
|
@ -32,7 +32,7 @@
|
|||
****************************************************************************/
|
||||
/**
|
||||
* @file main.cpp
|
||||
* Basic shell to execute builtin "apps"
|
||||
* Basic shell to execute builtin "apps"
|
||||
*
|
||||
* @author Mark Charlebois <charlebm@gmail.com>
|
||||
*/
|
||||
|
@ -56,6 +56,8 @@ static px4_task_t g_dspal_task = -1;
|
|||
__BEGIN_DECLS
|
||||
// The commands to run are specified in a target file: commands_<target>.c
|
||||
extern const char *get_commands(void);
|
||||
// Enable external library hook
|
||||
void qurt_external_hook(void) __attribute__((weak));
|
||||
__END_DECLS
|
||||
|
||||
static void run_cmd(map<string,px4_main_t> &apps, const vector<string> &appargs) {
|
||||
|
@ -108,7 +110,7 @@ static void process_commands(map<string,px4_main_t> &apps, const char *cmds)
|
|||
|
||||
// Eat leading whitespace
|
||||
eat_whitespace(b, i);
|
||||
|
||||
|
||||
|
||||
for(;;) {
|
||||
// End of command line
|
||||
|
@ -156,15 +158,17 @@ __END_DECLS
|
|||
|
||||
int dspal_entry( int argc, char* argv[] )
|
||||
{
|
||||
//const char *argv[2] = { "dspal_client", NULL };
|
||||
//int argc = 1;
|
||||
|
||||
PX4_INFO("In main\n");
|
||||
map<string,px4_main_t> apps;
|
||||
init_app_map(apps);
|
||||
px4::init_once();
|
||||
px4::init(argc, (char **)argv, "mainapp");
|
||||
process_commands(apps, get_commands());
|
||||
usleep( 1000000 ); // give time for all commands to execute before starting external function
|
||||
if(qurt_external_hook)
|
||||
{
|
||||
qurt_external_hook();
|
||||
}
|
||||
for( ;; ){
|
||||
usleep( 1000000 );
|
||||
}
|
||||
|
|
|
@ -58,6 +58,9 @@ endif
|
|||
ifeq ($(CONFIG),qurt_hil)
|
||||
SRCS += commands_hil.c
|
||||
endif
|
||||
ifeq ($(CONFIG),qurt_adsp)
|
||||
SRCS += commands_adsp.c
|
||||
endif
|
||||
|
||||
|
||||
MAXOPTIMIZATION = -Os
|
||||
|
|
Loading…
Reference in New Issue