QuRT: toolchain changes

Reworking toolchain and main.cpp for QuRT to a final link can be
done and the apps.h file is autogenerated.

Signed-off-by: Mark Charlebois <charlebm@gmail.com>
This commit is contained in:
Mark Charlebois 2015-05-12 11:37:28 -07:00
parent 14cbd240ff
commit 3db5f3bb3b
10 changed files with 109 additions and 84 deletions

View File

@ -44,8 +44,7 @@ print
print """
#include <string>
#include <map>
#define __EXPORT
#include <stdio.h>
#include <px4_tasks.h>
#include <px4_posix.h>
@ -84,14 +83,14 @@ map<string,px4_main_t> apps = app_map();
static void list_builtins(void)
{
cout << "Builtin Commands:" << endl;
printf("Builtin Commands:\\n");
for (map<string,px4_main_t>::iterator it=apps.begin(); it!=apps.end(); ++it)
cout << '\t' << it->first << endl;
printf("\\t%s\\n", (it->first).c_str());
}
static int shutdown_main(int argc, char *argv[])
{
cout << "Shutting down" << endl;
printf("Shutting down\\n");
exit(0);
}

View File

@ -58,6 +58,6 @@ HEXAGON_TOOLS_ROOT = /opt/6.4.05
V_ARCH = v5
HEXAGON_CLANG_BIN = $(addsuffix /qc/bin,$(HEXAGON_TOOLS_ROOT))
SIM = $(HEXAGON_CLANG_BIN)/hexagon-sim
SIMFLAGS+= -m$(V_ARCH) --timing
SIMFLAGS+= -m$(V_ARCH)
sim:
$(SIM) $(SIMFLAGS) Build/qurt_default.build/mainapp

View File

@ -10,18 +10,18 @@
#
# Board support modules
#
MODULES += drivers/device
MODULES += drivers/blinkm
MODULES += drivers/hil
MODULES += drivers/led
MODULES += drivers/rgbled
MODULES += modules/sensors
#MODULES += drivers/device
#MODULES += drivers/blinkm
#MODULES += drivers/hil
#MODULES += drivers/led
#MODULES += drivers/rgbled
#MODULES += modules/sensors
#MODULES += drivers/ms5611
#
# System commands
#
MODULES += systemcmds/param
#MODULES += systemcmds/param
#
# General system control
@ -31,8 +31,8 @@ MODULES += systemcmds/param
#
# Estimation modules (EKF/ SO3 / other filters)
#
MODULES += modules/attitude_estimator_ekf
MODULES += modules/ekf_att_pos_estimator
#MODULES += modules/attitude_estimator_ekf
#MODULES += modules/ekf_att_pos_estimator
#
# Vehicle Control
@ -42,37 +42,37 @@ MODULES += modules/ekf_att_pos_estimator
#
# Library modules
#
MODULES += modules/systemlib
MODULES += modules/systemlib/mixer
MODULES += modules/uORB
#MODULES += modules/systemlib
#MODULES += modules/systemlib/mixer
#MODULES += modules/uORB
#MODULES += modules/dataman
#MODULES += modules/sdlog2
MODULES += modules/simulator
MODULES += modules/commander
#MODULES += modules/simulator
#MODULES += modules/commander
#
# Libraries
#
MODULES += lib/mathlib
MODULES += lib/mathlib/math/filter
MODULES += lib/geo
MODULES += lib/geo_lookup
MODULES += lib/conversion
#MODULES += lib/mathlib
#MODULES += lib/mathlib/math/filter
#MODULES += lib/geo
#MODULES += lib/geo_lookup
#MODULES += lib/conversion
#
# QuRT port
#
MODULES += platforms/qurt/px4_layer
MODULES += platforms/posix/drivers/accelsim
MODULES += platforms/posix/drivers/gyrosim
MODULES += platforms/posix/drivers/adcsim
MODULES += platforms/posix/drivers/barosim
#MODULES += platforms/posix/drivers/accelsim
#MODULES += platforms/posix/drivers/gyrosim
#MODULES += platforms/posix/drivers/adcsim
#MODULES += platforms/posix/drivers/barosim
#
# Unit tests
#
MODULES += platforms/qurt/tests/hello
MODULES += platforms/posix/tests/vcdev_test
#MODULES += platforms/posix/tests/vcdev_test
#MODULES += platforms/posix/tests/hrt_test
MODULES += platforms/posix/tests/wqueue
#MODULES += platforms/posix/tests/wqueue

View File

@ -56,10 +56,8 @@ $(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/qurt/main.cpp
$(WORK_DIR)mainapp: $(PRODUCT_SHARED_LIB)
$(PX4_BASE)/Tools/qurt_apps.py > apps.h
$(call LINK,$@, -I. $(MAIN) $(PRODUCT_SHARED_LIB))
$(call LINK,$@, $(PRODUCT_SHARED_LIB))
#
# Utility rules
@ -70,4 +68,3 @@ clean: $(MODULE_CLEANS)
@$(ECHO) %% cleaning
$(Q) $(REMOVE) $(PRODUCT_ELF)
$(Q) $(REMOVE) $(OBJS) $(DEP_INCLUDES) $(EXTRA_CLEANS)

View File

@ -38,6 +38,7 @@
# Toolchain commands. Normally only used inside this file.
#
HEXAGON_TOOLS_ROOT = /opt/6.4.05
HEXAGON_SDK_ROOT = /opt/Hexagon_SDK/2.0
#V_ARCH = v4
V_ARCH = v5
CROSSDEV = hexagon-
@ -45,6 +46,9 @@ HEXAGON_BIN = $(addsuffix /gnu/bin,$(HEXAGON_TOOLS_ROOT))
HEXAGON_CLANG_BIN = $(addsuffix /qc/bin,$(HEXAGON_TOOLS_ROOT))
HEXAGON_LIB_DIR = $(HEXAGON_TOOLS_ROOT)/gnu/hexagon/lib
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
CC = $(HEXAGON_CLANG_BIN)/$(CROSSDEV)clang
@ -56,6 +60,24 @@ NM = $(HEXAGON_BIN)/$(CROSSDEV)nm
OBJCOPY = $(HEXAGON_BIN)/$(CROSSDEV)objcopy
OBJDUMP = $(HEXAGON_BIN)/$(CROSSDEV)objdump
QURTLIBS = \
$(TOOLSLIB)/init.o \
$(QURTLIB)/crt0.o \
$(TOOLSLIB)/libc.a \
$(TOOLSLIB)/libqcc.a \
$(QCTOOLSLIB)/libhexagon.a \
$(QURTLIB)/libqurt.a \
$(QURTLIB)/libqurtkernel.a \
$(QURTLIB)/libqurtcfs.a \
$(QURTLIB)/libqube_compat.a \
$(QURTLIB)/libtimer.a \
$(QURTLIB)/libposix.a \
$(TOOLSLIB)/libstdc++.a \
$(QURTLIB)/../examples/cust_config.o \
$(TOOLSLIB)/fini.o
# Check if the right version of the toolchain is available
#
CROSSDEV_VER_SUPPORTED = 6.4.05
@ -68,7 +90,7 @@ endif
# XXX this is pulled pretty directly from the fmu Make.defs - needs cleanup
MAXOPTIMIZATION ?= -Os
MAXOPTIMIZATION ?= -O0
# Base CPU flags for each of the supported architectures.
#
@ -91,6 +113,7 @@ ARCHDEFINES += -DCONFIG_ARCH_BOARD_$(CONFIG_BOARD) \
-I$(PX4_BASE)/../dspal/include \
-I$(PX4_BASE)/../dspal/sys \
-I$(PX4_BASE)/mavlink/include/mavlink \
-I$(QURTLIB)/..//include \
-Wno-error=shadow
# optimisation flags
@ -179,7 +202,7 @@ endif
HEXAGON_LIB_PATH = $(HEXAGON_TOOLS_ROOT)/gnu/hexagon/lib/$(V_ARCH)/G0
LIB_HEXAGON = $(HEXAGON_TOOLS_ROOT)/qc/lib/$(V_ARCH)/G0/libhexagon.a
EXTRA_LIBS += $(PX4_BASE)../dspal_libs/libdspal.a
#EXTRA_LIBS += $(PX4_BASE)../dspal_libs/libdspal.a
# Flags we pass to the assembler
#
@ -190,7 +213,7 @@ AFLAGS = $(CFLAGS) -D__ASSEMBLY__ \
LDSCRIPT = $(PX4_BASE)/posix-configs/posixtest/scripts/ld.script
# Flags we pass to the linker
#
LDFLAGS += \
LDFLAGS += -g -nostdlib --section-start .start=0x1d000000\
$(EXTRALDFLAGS) \
$(addprefix -L,$(LIB_DIRS))
@ -240,7 +263,7 @@ endef
define PRELINK
@$(ECHO) "PRELINK: $1"
@$(MKDIR) -p $(dir $1)
echo $(Q) $(LD) -Ur -o $1 $2
@echo $(Q) $(LD) -Ur -o $1 $2
$(Q) $(LD) -Ur -o $1 $2
endef
@ -250,8 +273,8 @@ endef
define PRELINKF
@$(ECHO) "PRELINKF: $1"
@$(MKDIR) -p $(dir $1)
echo $(Q) $(LD) -Ur -T$(LDSCRIPT) -o $1 $2
$(Q) $(LD) -Ur -T$(LDSCRIPT) -o $1 $2
@echo $(Q) $(LD) -Ur -T$(LDSCRIPT) -o $1 $2
$(Q) $(LD) -Ur -T$(LDSCRIPT) -o $1 $2
endef
# $(Q) $(LD) -Ur -o $1 $2 && $(OBJCOPY) --localize-hidden $1
@ -287,10 +310,7 @@ endef
define LINK
@$(ECHO) "LINK: $1"
@$(MKDIR) -p $(dir $1)
echo $(Q) $(CXX) $(CXXFLAGS) $(LDFLAGS) -o $1 $2 $(LIBS)
$(Q) $(CXX) $(CXXFLAGS) $(LDFLAGS) -o $1 $2 $(EXTRA_LIBS)
# $(Q) $(CXX) $(CXXFLAGS) $(LDFLAGS) -o $1 $2 $(LIBS) $(EXTRA_LIBS) $(LIBGCC)
@echo $(Q) $(LD) $(LDFLAGS) -o $1 --start-group $2 $(EXTRA_LIBS) $(QURTLIBS) --end-group
$(Q) $(LD) $(LDFLAGS) -o $1 --start-group $2 $(EXTRA_LIBS) $(QURTLIBS) --end-group
endef

View File

@ -53,7 +53,7 @@ static int update_interval = 1;
static void timer_expired(void *arg)
{
static int i = 0;
printf("Test\n");
PX4_INFO("Test\n");
if (i < 5) {
i++;
hrt_call_after(&t1, update_interval, timer_expired, (void *)0);
@ -67,24 +67,24 @@ int HRTTest::main()
hrt_abstime t = hrt_absolute_time();
usleep(1000000);
hrt_abstime elt = hrt_elapsed_time(&t);
printf("Elapsed time %llu in 1 sec (usleep)\n", (unsigned long long)elt);
printf("Start time %llu\n", (unsigned long long)t);
PX4_INFO("Elapsed time %llu in 1 sec (usleep)\n", (unsigned long long)elt);
PX4_INFO("Start time %llu\n", (unsigned long long)t);
t = hrt_absolute_time();
sleep(1);
elt = hrt_elapsed_time(&t);
printf("Elapsed time %llu in 1 sec (sleep)\n", (unsigned long long)elt);
printf("Start time %llu\n", (unsigned long long)t);
PX4_INFO("Elapsed time %llu in 1 sec (sleep)\n", (unsigned long long)elt);
PX4_INFO("Start time %llu\n", (unsigned long long)t);
memset(&t1, 0, sizeof(t1));
printf("HRT_CALL %d\n", hrt_called(&t1));
PX4_INFO("HRT_CALL %d\n", hrt_called(&t1));
hrt_call_after(&t1, update_interval, timer_expired, (void *)0);
sleep(2);
printf("HRT_CALL - %d\n", hrt_called(&t1));
PX4_INFO("HRT_CALL - %d\n", hrt_called(&t1));
hrt_cancel(&t1);
printf("HRT_CALL + %d\n", hrt_called(&t1));
PX4_INFO("HRT_CALL + %d\n", hrt_called(&t1));
return 0;
}

View File

@ -49,14 +49,14 @@ extern "C" __EXPORT int hrttest_main(int argc, char *argv[]);
int hrttest_main(int argc, char *argv[])
{
if (argc < 2) {
printf("usage: hrttest_main {start|stop|status}\n");
PX4_WARN("usage: hrttest_main {start|stop|status}\n");
return 1;
}
if (!strcmp(argv[1], "start")) {
if (HRTTest::appState.isRunning()) {
printf("already running\n");
PX4_INFO("already running\n");
/* this is not an error */
return 0;
}
@ -78,15 +78,15 @@ int hrttest_main(int argc, char *argv[])
if (!strcmp(argv[1], "status")) {
if (HRTTest::appState.isRunning()) {
printf("is running\n");
PX4_INFO("is running\n");
} else {
printf("not started\n");
PX4_INFO("not started\n");
}
return 0;
}
printf("usage: hrttest_main {start|stop|status}\n");
PX4_WARN("usage: hrttest_main {start|stop|status}\n");
return 1;
}

View File

@ -37,12 +37,9 @@
* @author Mark Charlebois <charlebm@gmail.com>
*/
#include <iostream>
#include <fstream>
#include <string>
#include <sstream>
#include <vector>
#include <hexagon_standalone.h>
//#include <hexagon_standalone.h>
//using namespace std;
@ -52,7 +49,6 @@
#include "px4_middleware.h"
static const char *commands =
"x\n"
"hello start"
#if 0
"uorb start\n"
@ -79,15 +75,15 @@ static const char *commands =
static void run_cmd(const vector<string> &appargs) {
// command is appargs[0]
string command = appargs[0];
printf("Looking for %s\n", command.c_str());
//printf("Looking for %s\n", command.c_str());
if (apps.find(command) != apps.end()) {
const char *arg[2+1];
unsigned int i = 0;
printf("size = %d\n", appargs.size());
//printf("size = %d\n", appargs.size());
while (i < appargs.size() && appargs[i].c_str()[0] != '\0') {
arg[i] = (char *)appargs[i].c_str();
printf(" arg = '%s'\n", arg[i]);
//printf(" arg = '%s'\n", arg[i]);
++i;
}
arg[i] = (char *)0;
@ -97,7 +93,7 @@ static void run_cmd(const vector<string> &appargs) {
}
else
{
cout << "Invalid command" << endl;
//cout << "Invalid command" << endl;
list_builtins();
}
}
@ -159,8 +155,10 @@ extern void init_once(void);
int main(int argc, char **argv)
{
printf("In main\n");
px4::init_once();
px4::init(argc, argv, "mainapp");
process_commands(commands);
for (;;) {}
}

View File

@ -35,6 +35,15 @@
# NuttX / uORB adapter library
#
SRCDIR=$(dir $(MODULE_MK))
apps.h: $(PX4_BASE)/Tools/qurt_apps.py
$(PX4_BASE)/Tools/qurt_apps.py > $@
# Force creation of apps.h
main_.cpp: $(SRCDIR)/../main.cpp apps.h
cp $(SRCDIR)/../main.cpp $@
SRCS = \
px4_qurt_impl.cpp \
px4_qurt_tasks.cpp \
@ -49,6 +58,7 @@ SRCS = \
sq_addlast.c \
sq_remfirst.c \
sq_addafter.c \
dq_rem.c
dq_rem.c \
main_.cpp
MAXOPTIMIZATION = -Os

View File

@ -46,7 +46,9 @@
#include <signal.h>
#include <errno.h>
#include <unistd.h>
#include <semaphore.h>
#include "systemlib/param/param.h"
#include <hexagon_standalone.h>
__BEGIN_DECLS
@ -58,6 +60,14 @@ unsigned int sleep(unsigned int sec) { return 0; }
extern void hrt_init(void);
void qurt_log(const char *fmt, ...)
{
va_list args;
va_start(args, fmt);
printf(fmt, args);
printf("n");
}
__END_DECLS
extern struct wqueue_s gwork[NWORKERS];
@ -71,12 +81,7 @@ void init_once(void)
{
work_queues_init();
hrt_init();
}
void init(int argc, char *argv[], const char *app_name)
{
printf("App name: %s\n", app_name);
// Create high priority worker thread
g_work[HPWORK].pid = px4_task_spawn_cmd("wkr_high",
SCHED_DEFAULT,
@ -95,6 +100,11 @@ void init(int argc, char *argv[], const char *app_name)
}
void init(int argc, char *argv[], const char *app_name)
{
PX4_DEBUG("App name: %s\n", app_name);
}
}
/** Retrieve from the data manager store */
@ -131,12 +141,3 @@ size_t strnlen(const char *s, size_t maxlen)
return i;
}
void qurt_log(const char *fmt, ...)
{
va_list args;
va_start(args, fmt);
vprintf(fmt, args);
printf("\n");
}