From 00296ba24170d808bfe610fbde3e89e95d6f3908 Mon Sep 17 00:00:00 2001 From: Mark Charlebois Date: Tue, 19 May 2015 16:42:55 -0700 Subject: [PATCH 1/3] POSIX: Fixed uint64_t print in generated topic_listener.cpp Signed-off-by: Mark Charlebois --- Tools/generate_listener.py | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/Tools/generate_listener.py b/Tools/generate_listener.py index e52d3cd26f..5cfe4a6281 100755 --- a/Tools/generate_listener.py +++ b/Tools/generate_listener.py @@ -91,6 +91,8 @@ print """ #include #include #include +#define __STDC_FORMAT_MACROS +#include """ for m in messages: print "#include " % m @@ -135,7 +137,7 @@ for index,m in enumerate(messages[1:]): print "\t\t\t}" print "\t\t\tprintf(\"\\n\");" elif item[0] == "uint64": - print "\t\t\tprintf(\"%s: %%lu\\n \",container.%s);" % (item[1], item[1]) + print "\t\t\tprintf(\"%s: %%\" PRIu64 \"\\n \",container.%s);" % (item[1], item[1]) elif item[0] == "uint8": print "\t\t\tprintf(\"%s: %%u\\n \",container.%s);" % (item[1], item[1]) elif item[0] == "bool": From 43345e29dc961282089c1ee4d673cea01c4861b8 Mon Sep 17 00:00:00 2001 From: Mark Charlebois Date: Wed, 20 May 2015 19:19:08 -0700 Subject: [PATCH 2/3] Makefile multi-target support NuttX is still the default target and all NuttX configs can still be built with: make Individual NuttX, POSIX, and QuRT configs can now be built more easily by specifying the target and configs: make posix posix_default make qurt qurt_hello make nuttx aerocore_default Running make with just the target will make all the configs for that target: make nuttx make qurt make posix The help is also target specific: make nuttx help make qurt help make posix help "make help" will still assume you want help for the NuttX target Added a new QuRT config called qurt_hello as a sample config to test buiding in different commands for separate configs. Signed-off-by: Mark Charlebois --- Makefile | 22 ++++-- makefiles/firmware_posix.mk | 2 +- makefiles/firmware_qurt.mk | 2 +- makefiles/qurt/config_qurt_hello.mk | 73 +++++++++++++++++++ .../qurt/px4_layer/commands_default.c | 68 +++++++++++++++++ src/platforms/qurt/px4_layer/commands_hello.c | 45 ++++++++++++ src/platforms/qurt/px4_layer/main.cpp | 30 ++------ src/platforms/qurt/px4_layer/module.mk | 8 +- 8 files changed, 216 insertions(+), 34 deletions(-) create mode 100644 makefiles/qurt/config_qurt_hello.mk create mode 100644 src/platforms/qurt/px4_layer/commands_default.c create mode 100644 src/platforms/qurt/px4_layer/commands_hello.c diff --git a/Makefile b/Makefile index 4a0f13cd19..3f78f32362 100644 --- a/Makefile +++ b/Makefile @@ -33,6 +33,12 @@ # Top-level Makefile for building PX4 firmware images. # +TARGETS := nuttx posix qurt +EXPLICIT_TARGET := $(filter $(TARGETS),$(MAKECMDGOALS)) +ifneq ($(EXPLICIT_TARGET),) + export PX4_TARGET_OS=$(EXPLICIT_TARGET) +endif + # # Get path and tool configuration # @@ -271,14 +277,14 @@ testbuild: $(Q) (cd $(PX4_BASE) && $(MAKE) distclean && $(MAKE) archives && $(MAKE) -j8) $(Q) (zip -r Firmware.zip $(PX4_BASE)/Images) -posix: - make PX4_TARGET_OS=posix +nuttx: + make PX4_TARGET_OS=$@ $(wordlist 2,$(words $(MAKECMDGOALS)),$(MAKECMDGOALS)) -nuttx: - make PX4_TARGET_OS=nuttx +posix: + make PX4_TARGET_OS=$@ $(wordlist 2,$(words $(MAKECMDGOALS)),$(MAKECMDGOALS)) -qurt: - make PX4_TARGET_OS=qurt +qurt: + make PX4_TARGET_OS=$@ $(wordlist 2,$(words $(MAKECMDGOALS)),$(MAKECMDGOALS)) posixrun: Tools/posix_run.sh @@ -327,9 +333,11 @@ help: @$(ECHO) " Available targets:" @$(ECHO) " ------------------" @$(ECHO) "" +ifeq ($(PX4_TARGET_OS),nuttx) @$(ECHO) " archives" @$(ECHO) " Build the NuttX RTOS archives that are used by the firmware build." @$(ECHO) "" +endif @$(ECHO) " all" @$(ECHO) " Build all firmware configs: $(CONFIGS)" @$(ECHO) " A limited set of configs can be built with CONFIGS=" @@ -342,6 +350,7 @@ help: @$(ECHO) " clean" @$(ECHO) " Remove all firmware build pieces." @$(ECHO) "" +ifeq ($(PX4_TARGET_OS),nuttx) @$(ECHO) " distclean" @$(ECHO) " Remove all compilation products, including NuttX RTOS archives." @$(ECHO) "" @@ -350,6 +359,7 @@ help: @$(ECHO) " firmware to the board when the build is complete. Not supported for" @$(ECHO) " all configurations." @$(ECHO) "" +endif @$(ECHO) " testbuild" @$(ECHO) " Perform a complete clean build of the entire tree." @$(ECHO) "" diff --git a/makefiles/firmware_posix.mk b/makefiles/firmware_posix.mk index 6acec4e733..912e7bcc3f 100644 --- a/makefiles/firmware_posix.mk +++ b/makefiles/firmware_posix.mk @@ -32,7 +32,7 @@ # # Built products # -FIRMWARES = $(foreach config,$(KNOWN_CONFIGS),$(BUILD_DIR)$(config).build/firmware.a) +FIRMWARES = $(foreach config,$(CONFIGS),$(BUILD_DIR)$(config).build/firmware.a) all: $(FIRMWARES) diff --git a/makefiles/firmware_qurt.mk b/makefiles/firmware_qurt.mk index 41128fa60f..a367e4a327 100644 --- a/makefiles/firmware_qurt.mk +++ b/makefiles/firmware_qurt.mk @@ -32,7 +32,7 @@ # # Built products # -FIRMWARES = $(foreach config,$(KNOWN_CONFIGS),$(BUILD_DIR)$(config).build/firmware.a) +FIRMWARES = $(foreach config,$(CONFIGS),$(BUILD_DIR)$(config).build/firmware.a) all: $(FIRMWARES) diff --git a/makefiles/qurt/config_qurt_hello.mk b/makefiles/qurt/config_qurt_hello.mk new file mode 100644 index 0000000000..4b11a79fe3 --- /dev/null +++ b/makefiles/qurt/config_qurt_hello.mk @@ -0,0 +1,73 @@ +# +# Makefile for the Foo *default* configuration +# + +# +# Board support modules +# +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 + +# +# General system control +# +#MODULES += modules/mavlink + +# +# Estimation modules (EKF/ SO3 / other filters) +# +#MODULES += modules/attitude_estimator_ekf +#MODULES += modules/ekf_att_pos_estimator + +# +# Vehicle Control +# +#MODULES += modules/mc_att_control + +# +# Library modules +# +MODULES += modules/systemlib +#MODULES += modules/systemlib/mixer +MODULES += modules/uORB +#MODULES += modules/dataman +#MODULES += modules/sdlog2 +#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 + +# +# 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 + +# +# Unit tests +# +MODULES += platforms/qurt/tests/hello +#MODULES += platforms/posix/tests/vcdev_test +#MODULES += platforms/posix/tests/hrt_test +#MODULES += platforms/posix/tests/wqueue + diff --git a/src/platforms/qurt/px4_layer/commands_default.c b/src/platforms/qurt/px4_layer/commands_default.c new file mode 100644 index 0000000000..9d229d610f --- /dev/null +++ b/src/platforms/qurt/px4_layer/commands_default.c @@ -0,0 +1,68 @@ +/**************************************************************************** + * + * 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 hello.c + * Commands to run for the QuRT "default" target + * + * @author Mark Charlebois + */ + +const char *get_commands() +{ + static const char *commands = + "hello start\n" + "uorb start\n" + "simulator start -s\n" + "barosim start\n" + "adcsim start\n" + "accelsim start\n" + "gyrosim start\n" + "list_devices\n" + "list_topics\n" + "list_tasks\n" + "param show *\n" + "rgbled start\n" +#if 0 + "sensors start\n" + "param set CAL_GYRO0_ID 2293760\n" + "param set CAL_ACC0_ID 1310720\n" + "hil mode_pwm" + "param set CAL_ACC1_ID 1376256\n" + "param set CAL_MAG0_ID 196608\n" + "mavlink start -d /tmp/ttyS0\n" + "commander start\n" +#endif + ; + + return commands; +} diff --git a/src/platforms/qurt/px4_layer/commands_hello.c b/src/platforms/qurt/px4_layer/commands_hello.c new file mode 100644 index 0000000000..d38e73da0e --- /dev/null +++ b/src/platforms/qurt/px4_layer/commands_hello.c @@ -0,0 +1,45 @@ +/**************************************************************************** + * + * 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 hello.c + * Commands to run for the QuRT "hello" target + * + * @author Mark Charlebois + */ + +const char *get_commands() +{ + static const char *commands = "hello start"; + + return commands; +} diff --git a/src/platforms/qurt/px4_layer/main.cpp b/src/platforms/qurt/px4_layer/main.cpp index 3f42c1c301..538b64229f 100644 --- a/src/platforms/qurt/px4_layer/main.cpp +++ b/src/platforms/qurt/px4_layer/main.cpp @@ -50,30 +50,10 @@ using namespace std; extern void init_app_map(map &apps); extern void list_builtins(map &apps); -static const char *commands = -"hello start\n" -"uorb start\n" -"simulator start -s\n" -"barosim start\n" -"adcsim start\n" -"accelsim start\n" -"gyrosim start\n" -"list_devices\n" -"list_topics\n" -"list_tasks\n" -"param show *\n" -"rgbled start\n" -#if 0 -"hil mode_pwm" -"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" -"sensors start\n" -"mavlink start -d /tmp/ttyS0\n" -"commander start\n" -#endif -; +__BEGIN_DECLS +// The commands to run are specified in a target file: commands_.c +extern const char *get_commands(void); +__END_DECLS static void run_cmd(map &apps, const vector &appargs) { // command is appargs[0] @@ -158,7 +138,7 @@ int main(int argc, char **argv) init_app_map(apps); px4::init_once(); px4::init(argc, argv, "mainapp"); - process_commands(apps, commands); + process_commands(apps, get_commands()); for (;;) {} } diff --git a/src/platforms/qurt/px4_layer/module.mk b/src/platforms/qurt/px4_layer/module.mk index 92f1c6abfb..714263edcb 100644 --- a/src/platforms/qurt/px4_layer/module.mk +++ b/src/platforms/qurt/px4_layer/module.mk @@ -52,6 +52,12 @@ SRCS = \ sq_remfirst.c \ sq_addafter.c \ dq_rem.c \ - main.cpp + main.cpp +ifeq ($(CONFIG),qurt_hello) +SRCS += commands_hello.c +endif +ifeq ($(CONFIG),qurt_default) +SRCS += commands_default.c +endif MAXOPTIMIZATION = -Os From e45f040c76a36857c516bcc3aa698ff37b4cafaa Mon Sep 17 00:00:00 2001 From: Mark Charlebois Date: Wed, 20 May 2015 19:35:43 -0700 Subject: [PATCH 3/3] QuRT: Fixed file descriptions for command_.c Signed-off-by: Mark Charlebois --- src/platforms/qurt/px4_layer/commands_default.c | 4 ++-- src/platforms/qurt/px4_layer/commands_hello.c | 4 ++-- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/src/platforms/qurt/px4_layer/commands_default.c b/src/platforms/qurt/px4_layer/commands_default.c index 9d229d610f..1c4c50f022 100644 --- a/src/platforms/qurt/px4_layer/commands_default.c +++ b/src/platforms/qurt/px4_layer/commands_default.c @@ -31,8 +31,8 @@ * ****************************************************************************/ /** - * @file hello.c - * Commands to run for the QuRT "default" target + * @file commands_default.c + * Commands to run for the "qurt_default" config * * @author Mark Charlebois */ diff --git a/src/platforms/qurt/px4_layer/commands_hello.c b/src/platforms/qurt/px4_layer/commands_hello.c index d38e73da0e..b2ef09b457 100644 --- a/src/platforms/qurt/px4_layer/commands_hello.c +++ b/src/platforms/qurt/px4_layer/commands_hello.c @@ -31,8 +31,8 @@ * ****************************************************************************/ /** - * @file hello.c - * Commands to run for the QuRT "hello" target + * @file commands_hello.c + * Commands to run for the "qurt_hello" config * * @author Mark Charlebois */