aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--apps/drivers/mpu6000/Makefile42
-rw-r--r--apps/examples/control_demo/Makefile42
-rw-r--r--apps/examples/kalman_demo/Makefile42
-rw-r--r--apps/fixedwing_pos_control/Makefile45
-rw-r--r--apps/hott_telemetry/Makefile45
-rwxr-xr-xapps/multirotor_att_control/Makefile42
-rw-r--r--apps/multirotor_pos_control/Makefile42
-rw-r--r--makefiles/config_px4fmu_default.mk38
-rw-r--r--src/drivers/blinkm/blinkm.cpp (renamed from apps/drivers/blinkm/blinkm.cpp)0
-rw-r--r--src/drivers/blinkm/module.mk (renamed from apps/drivers/blinkm/Makefile)8
-rw-r--r--src/drivers/bma180/bma180.cpp (renamed from apps/drivers/bma180/bma180.cpp)0
-rw-r--r--src/drivers/bma180/module.mk (renamed from apps/drivers/bma180/Makefile)8
-rw-r--r--src/drivers/gps/gps.cpp (renamed from apps/drivers/gps/gps.cpp)0
-rw-r--r--src/drivers/gps/gps_helper.cpp (renamed from apps/drivers/gps/gps_helper.cpp)0
-rw-r--r--src/drivers/gps/gps_helper.h (renamed from apps/drivers/gps/gps_helper.h)0
-rw-r--r--src/drivers/gps/module.mk (renamed from apps/drivers/gps/Makefile)11
-rw-r--r--src/drivers/gps/mtk.cpp (renamed from apps/drivers/gps/mtk.cpp)0
-rw-r--r--src/drivers/gps/mtk.h (renamed from apps/drivers/gps/mtk.h)0
-rw-r--r--src/drivers/gps/ubx.cpp (renamed from apps/drivers/gps/ubx.cpp)0
-rw-r--r--src/drivers/gps/ubx.h (renamed from apps/drivers/gps/ubx.h)0
-rw-r--r--src/drivers/hil/hil.cpp (renamed from apps/drivers/hil/hil.cpp)0
-rw-r--r--src/drivers/hil/module.mk (renamed from apps/drivers/hmc5883/Makefile)10
-rw-r--r--src/drivers/hmc5883/hmc5883.cpp (renamed from apps/drivers/hmc5883/hmc5883.cpp)0
-rw-r--r--src/drivers/hmc5883/module.mk (renamed from apps/drivers/hil/Makefile)13
-rw-r--r--src/drivers/hott_telemetry/hott_telemetry_main.c (renamed from apps/hott_telemetry/hott_telemetry_main.c)12
-rw-r--r--src/drivers/hott_telemetry/messages.c (renamed from apps/hott_telemetry/messages.c)6
-rw-r--r--src/drivers/hott_telemetry/messages.h (renamed from apps/hott_telemetry/messages.h)5
-rw-r--r--src/drivers/hott_telemetry/module.mk41
-rw-r--r--src/drivers/mb12xx/mb12xx.cpp (renamed from apps/drivers/mb12xx/mb12xx.cpp)2
-rw-r--r--src/drivers/mb12xx/module.mk (renamed from apps/drivers/mb12xx/Makefile)8
-rw-r--r--src/drivers/mpu6000/module.mk43
-rw-r--r--src/drivers/mpu6000/mpu6000.cpp (renamed from apps/drivers/mpu6000/mpu6000.cpp)2
-rw-r--r--src/drivers/ms5611/module.mk (renamed from apps/drivers/ms5611/Makefile)8
-rw-r--r--src/drivers/ms5611/ms5611.cpp (renamed from apps/drivers/ms5611/ms5611.cpp)0
-rw-r--r--src/modules/att_pos_estimator_ekf/KalmanNav.cpp (renamed from apps/examples/kalman_demo/KalmanNav.cpp)0
-rw-r--r--src/modules/att_pos_estimator_ekf/KalmanNav.hpp (renamed from apps/examples/kalman_demo/KalmanNav.hpp)0
-rw-r--r--src/modules/att_pos_estimator_ekf/kalman_main.cpp (renamed from apps/examples/kalman_demo/kalman_demo.cpp)4
-rw-r--r--src/modules/att_pos_estimator_ekf/module.mk (renamed from apps/fixedwing_att_control/Makefile)16
-rw-r--r--src/modules/att_pos_estimator_ekf/params.c (renamed from apps/examples/kalman_demo/params.c)0
-rw-r--r--src/modules/fixedwing_att_control/fixedwing_att_control_att.c (renamed from apps/fixedwing_att_control/fixedwing_att_control_att.c)3
-rw-r--r--src/modules/fixedwing_att_control/fixedwing_att_control_att.h (renamed from apps/fixedwing_att_control/fixedwing_att_control_att.h)0
-rw-r--r--src/modules/fixedwing_att_control/fixedwing_att_control_main.c (renamed from apps/fixedwing_att_control/fixedwing_att_control_main.c)5
-rw-r--r--src/modules/fixedwing_att_control/fixedwing_att_control_rate.c (renamed from apps/fixedwing_att_control/fixedwing_att_control_rate.c)6
-rw-r--r--src/modules/fixedwing_att_control/fixedwing_att_control_rate.h (renamed from apps/fixedwing_att_control/fixedwing_att_control_rate.h)0
-rw-r--r--src/modules/fixedwing_att_control/module.mk42
-rw-r--r--src/modules/fixedwing_backside/fixedwing_backside_main.cpp (renamed from apps/examples/control_demo/control_demo.cpp)14
-rw-r--r--src/modules/fixedwing_backside/module.mk40
-rw-r--r--src/modules/fixedwing_backside/params.c (renamed from apps/examples/control_demo/params.c)0
-rw-r--r--src/modules/fixedwing_pos_control/fixedwing_pos_control_main.c (renamed from apps/fixedwing_pos_control/fixedwing_pos_control_main.c)0
-rw-r--r--src/modules/fixedwing_pos_control/module.mk40
-rw-r--r--src/modules/mavlink/.context0
-rwxr-xr-xsrc/modules/multirotor_att_control/module.mk42
-rw-r--r--src/modules/multirotor_att_control/multirotor_att_control_main.c (renamed from apps/multirotor_att_control/multirotor_att_control_main.c)0
-rw-r--r--src/modules/multirotor_att_control/multirotor_attitude_control.c (renamed from apps/multirotor_att_control/multirotor_attitude_control.c)0
-rw-r--r--src/modules/multirotor_att_control/multirotor_attitude_control.h (renamed from apps/multirotor_att_control/multirotor_attitude_control.h)0
-rw-r--r--src/modules/multirotor_att_control/multirotor_rate_control.c (renamed from apps/multirotor_att_control/multirotor_rate_control.c)0
-rw-r--r--src/modules/multirotor_att_control/multirotor_rate_control.h (renamed from apps/multirotor_att_control/multirotor_rate_control.h)0
-rw-r--r--src/modules/multirotor_pos_control/module.mk41
-rw-r--r--src/modules/multirotor_pos_control/multirotor_pos_control.c (renamed from apps/multirotor_pos_control/multirotor_pos_control.c)0
-rw-r--r--src/modules/multirotor_pos_control/multirotor_pos_control_params.c (renamed from apps/multirotor_pos_control/multirotor_pos_control_params.c)0
-rw-r--r--src/modules/multirotor_pos_control/multirotor_pos_control_params.h (renamed from apps/multirotor_pos_control/multirotor_pos_control_params.h)0
-rw-r--r--src/modules/multirotor_pos_control/position_control.c (renamed from apps/multirotor_pos_control/position_control.c)0
-rw-r--r--src/modules/multirotor_pos_control/position_control.h (renamed from apps/multirotor_pos_control/position_control.h)0
-rw-r--r--src/modules/position_estimator/module.mk (renamed from apps/position_estimator/Makefile)12
-rw-r--r--src/modules/position_estimator/position_estimator_main.c (renamed from apps/position_estimator/position_estimator_main.c)0
65 files changed, 383 insertions, 397 deletions
diff --git a/apps/drivers/mpu6000/Makefile b/apps/drivers/mpu6000/Makefile
deleted file mode 100644
index 32df1bdae..000000000
--- a/apps/drivers/mpu6000/Makefile
+++ /dev/null
@@ -1,42 +0,0 @@
-############################################################################
-#
-# Copyright (C) 2012 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.
-#
-############################################################################
-
-#
-# Makefile to build the BMA180 driver.
-#
-
-APPNAME = mpu6000
-PRIORITY = SCHED_PRIORITY_DEFAULT
-STACKSIZE = 4096
-
-include $(APPDIR)/mk/app.mk
diff --git a/apps/examples/control_demo/Makefile b/apps/examples/control_demo/Makefile
deleted file mode 100644
index 6e40e645f..000000000
--- a/apps/examples/control_demo/Makefile
+++ /dev/null
@@ -1,42 +0,0 @@
-############################################################################
-#
-# Copyright (C) 2012 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.
-#
-############################################################################
-
-#
-# Basic example application
-#
-
-APPNAME = control_demo
-PRIORITY = SCHED_PRIORITY_DEFAULT
-STACKSIZE = 2048
-
-include $(APPDIR)/mk/app.mk
diff --git a/apps/examples/kalman_demo/Makefile b/apps/examples/kalman_demo/Makefile
deleted file mode 100644
index 99c34d934..000000000
--- a/apps/examples/kalman_demo/Makefile
+++ /dev/null
@@ -1,42 +0,0 @@
-############################################################################
-#
-# Copyright (C) 2012 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.
-#
-############################################################################
-
-#
-# Basic example application
-#
-
-APPNAME = kalman_demo
-PRIORITY = SCHED_PRIORITY_MAX - 30
-STACKSIZE = 2048
-
-include $(APPDIR)/mk/app.mk
diff --git a/apps/fixedwing_pos_control/Makefile b/apps/fixedwing_pos_control/Makefile
deleted file mode 100644
index bce391f49..000000000
--- a/apps/fixedwing_pos_control/Makefile
+++ /dev/null
@@ -1,45 +0,0 @@
-############################################################################
-#
-# Copyright (C) 2012 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.
-#
-############################################################################
-
-#
-# Fixedwing Control application
-#
-
-APPNAME = fixedwing_pos_control
-PRIORITY = SCHED_PRIORITY_MAX - 30
-STACKSIZE = 2048
-
-INCLUDES = $(TOPDIR)/../mavlink/include/mavlink
-
-include $(APPDIR)/mk/app.mk
-
diff --git a/apps/hott_telemetry/Makefile b/apps/hott_telemetry/Makefile
deleted file mode 100644
index 8d5faa3b7..000000000
--- a/apps/hott_telemetry/Makefile
+++ /dev/null
@@ -1,45 +0,0 @@
-############################################################################
-#
-# Copyright (C) 2012 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.
-#
-############################################################################
-
-#
-# Graupner HoTT Telemetry application.
-#
-
-# The following line is required for accessing UARTs directly.
-INCLUDES = $(TOPDIR)/arch/arm/src/stm32 $(TOPDIR)/arch/arm/src/common
-
-APPNAME = hott_telemetry
-PRIORITY = SCHED_PRIORITY_DEFAULT
-STACKSIZE = 2048
-
-include $(APPDIR)/mk/app.mk
diff --git a/apps/multirotor_att_control/Makefile b/apps/multirotor_att_control/Makefile
deleted file mode 100755
index 03cf33e43..000000000
--- a/apps/multirotor_att_control/Makefile
+++ /dev/null
@@ -1,42 +0,0 @@
-############################################################################
-#
-# Copyright (C) 2012 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.
-#
-############################################################################
-
-#
-# Makefile to build uORB
-#
-
-APPNAME = multirotor_att_control
-PRIORITY = SCHED_PRIORITY_MAX - 15
-STACKSIZE = 2048
-
-include $(APPDIR)/mk/app.mk
diff --git a/apps/multirotor_pos_control/Makefile b/apps/multirotor_pos_control/Makefile
deleted file mode 100644
index c88c85435..000000000
--- a/apps/multirotor_pos_control/Makefile
+++ /dev/null
@@ -1,42 +0,0 @@
-############################################################################
-#
-# Copyright (C) 2012 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.
-#
-############################################################################
-
-#
-# Makefile to build multirotor position control
-#
-
-APPNAME = multirotor_pos_control
-PRIORITY = SCHED_PRIORITY_MAX - 25
-STACKSIZE = 2048
-
-include $(APPDIR)/mk/app.mk
diff --git a/makefiles/config_px4fmu_default.mk b/makefiles/config_px4fmu_default.mk
index 0e03641db..e332efa68 100644
--- a/makefiles/config_px4fmu_default.mk
+++ b/makefiles/config_px4fmu_default.mk
@@ -10,12 +10,21 @@ ROMFS_ROOT = $(PX4_BASE)/ROMFS/px4fmu_common
#
# Board support modules
#
+MODULES += drivers/px4io
MODULES += drivers/px4fmu
MODULES += drivers/boards/px4fmu
MODULES += drivers/lsm303d
-MODULES += drivers/l3gd20
MODULES += drivers/ardrone_interface
-MODULES += drivers/px4io
+MODULES += drivers/l3gd20
+MODULES += drivers/bma180
+MODULES += drivers/mpu6000
+MODULES += drivers/hmc5883
+MODULES += drivers/ms5611
+MODULES += drivers/mb12xx
+MODULES += drivers/gps
+MODULES += drivers/hil
+MODULES += drivers/hott_telemetry
+MODULES += drivers/blinkm
MODULES += modules/sensors
#
@@ -46,6 +55,17 @@ MODULES += modules/mavlink_onboard
#
MODULES += modules/attitude_estimator_ekf
MODULES += modules/position_estimator_mc
+MODULES += modules/position_estimator
+MODULES += modules/att_pos_estimator_ekf
+
+#
+# Vehicle Control
+#
+MODULES += modules/fixedwing_backside
+MODULES += modules/fixedwing_att_control
+MODULES += modules/fixedwing_pos_control
+MODULES += modules/multirotor_att_control
+MODULES += modules/multirotor_pos_control
#
# Logging
@@ -67,21 +87,7 @@ endef
# command priority stack entrypoint
BUILTIN_COMMANDS := \
$(call _B, adc, , 2048, adc_main ) \
- $(call _B, blinkm, , 2048, blinkm_main ) \
- $(call _B, bma180, , 2048, bma180_main ) \
- $(call _B, control_demo, , 2048, control_demo_main ) \
- $(call _B, fixedwing_att_control, SCHED_PRIORITY_MAX-30, 2048, fixedwing_att_control_main ) \
- $(call _B, fixedwing_pos_control, SCHED_PRIORITY_MAX-30, 2048, fixedwing_pos_control_main ) \
- $(call _B, gps, , 2048, gps_main ) \
- $(call _B, hil, , 2048, hil_main ) \
- $(call _B, hmc5883, , 4096, hmc5883_main ) \
- $(call _B, hott_telemetry, , 2048, hott_telemetry_main ) \
- $(call _B, kalman_demo, SCHED_PRIORITY_MAX-30, 2048, kalman_demo_main ) \
$(call _B, math_demo, , 8192, math_demo_main ) \
- $(call _B, mpu6000, , 4096, mpu6000_main ) \
- $(call _B, ms5611, , 2048, ms5611_main ) \
- $(call _B, multirotor_att_control, SCHED_PRIORITY_MAX-15, 2048, multirotor_att_control_main) \
- $(call _B, multirotor_pos_control, SCHED_PRIORITY_MAX-25, 2048, multirotor_pos_control_main) \
$(call _B, sercon, , 2048, sercon_main ) \
$(call _B, serdis, , 2048, serdis_main ) \
$(call _B, tone_alarm, , 2048, tone_alarm_main ) \
diff --git a/apps/drivers/blinkm/blinkm.cpp b/src/drivers/blinkm/blinkm.cpp
index 3fabfd9a5..3fabfd9a5 100644
--- a/apps/drivers/blinkm/blinkm.cpp
+++ b/src/drivers/blinkm/blinkm.cpp
diff --git a/apps/drivers/blinkm/Makefile b/src/drivers/blinkm/module.mk
index 5a623693d..b48b90f3f 100644
--- a/apps/drivers/blinkm/Makefile
+++ b/src/drivers/blinkm/module.mk
@@ -1,6 +1,6 @@
############################################################################
#
-# Copyright (C) 2012 PX4 Development Team. All rights reserved.
+# Copyright (c) 2012, 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
@@ -35,8 +35,6 @@
# BlinkM I2C LED driver
#
-APPNAME = blinkm
-PRIORITY = SCHED_PRIORITY_DEFAULT
-STACKSIZE = 2048
+MODULE_COMMAND = blinkm
-include $(APPDIR)/mk/app.mk
+SRCS = blinkm.cpp
diff --git a/apps/drivers/bma180/bma180.cpp b/src/drivers/bma180/bma180.cpp
index 4409a8a9c..4409a8a9c 100644
--- a/apps/drivers/bma180/bma180.cpp
+++ b/src/drivers/bma180/bma180.cpp
diff --git a/apps/drivers/bma180/Makefile b/src/drivers/bma180/module.mk
index cc01b629e..4c60ee082 100644
--- a/apps/drivers/bma180/Makefile
+++ b/src/drivers/bma180/module.mk
@@ -1,6 +1,6 @@
############################################################################
#
-# Copyright (C) 2012 PX4 Development Team. All rights reserved.
+# Copyright (c) 2012, 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
@@ -35,8 +35,6 @@
# Makefile to build the BMA180 driver.
#
-APPNAME = bma180
-PRIORITY = SCHED_PRIORITY_DEFAULT
-STACKSIZE = 2048
+MODULE_COMMAND = bma180
-include $(APPDIR)/mk/app.mk
+SRCS = bma180.cpp
diff --git a/apps/drivers/gps/gps.cpp b/src/drivers/gps/gps.cpp
index e35bdb944..e35bdb944 100644
--- a/apps/drivers/gps/gps.cpp
+++ b/src/drivers/gps/gps.cpp
diff --git a/apps/drivers/gps/gps_helper.cpp b/src/drivers/gps/gps_helper.cpp
index 9c1fad569..9c1fad569 100644
--- a/apps/drivers/gps/gps_helper.cpp
+++ b/src/drivers/gps/gps_helper.cpp
diff --git a/apps/drivers/gps/gps_helper.h b/src/drivers/gps/gps_helper.h
index f3d3bc40b..f3d3bc40b 100644
--- a/apps/drivers/gps/gps_helper.h
+++ b/src/drivers/gps/gps_helper.h
diff --git a/apps/drivers/gps/Makefile b/src/drivers/gps/module.mk
index 3859a88a5..097db2abf 100644
--- a/apps/drivers/gps/Makefile
+++ b/src/drivers/gps/module.mk
@@ -1,6 +1,6 @@
############################################################################
#
-# Copyright (C) 2012 PX4 Development Team. All rights reserved.
+# Copyright (c) 2012, 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
@@ -35,8 +35,9 @@
# GPS driver
#
-APPNAME = gps
-PRIORITY = SCHED_PRIORITY_DEFAULT
-STACKSIZE = 2048
+MODULE_COMMAND = gps
-include $(APPDIR)/mk/app.mk
+SRCS = gps.cpp \
+ gps_helper.cpp \
+ mtk.cpp \
+ ubx.cpp
diff --git a/apps/drivers/gps/mtk.cpp b/src/drivers/gps/mtk.cpp
index 4762bd503..4762bd503 100644
--- a/apps/drivers/gps/mtk.cpp
+++ b/src/drivers/gps/mtk.cpp
diff --git a/apps/drivers/gps/mtk.h b/src/drivers/gps/mtk.h
index d4e390b01..d4e390b01 100644
--- a/apps/drivers/gps/mtk.h
+++ b/src/drivers/gps/mtk.h
diff --git a/apps/drivers/gps/ubx.cpp b/src/drivers/gps/ubx.cpp
index c150f5271..c150f5271 100644
--- a/apps/drivers/gps/ubx.cpp
+++ b/src/drivers/gps/ubx.cpp
diff --git a/apps/drivers/gps/ubx.h b/src/drivers/gps/ubx.h
index e3dd1c7ea..e3dd1c7ea 100644
--- a/apps/drivers/gps/ubx.h
+++ b/src/drivers/gps/ubx.h
diff --git a/apps/drivers/hil/hil.cpp b/src/drivers/hil/hil.cpp
index d9aa772d4..d9aa772d4 100644
--- a/apps/drivers/hil/hil.cpp
+++ b/src/drivers/hil/hil.cpp
diff --git a/apps/drivers/hmc5883/Makefile b/src/drivers/hil/module.mk
index 4d7cb4e7b..f8895f5d5 100644
--- a/apps/drivers/hmc5883/Makefile
+++ b/src/drivers/hil/module.mk
@@ -1,6 +1,6 @@
############################################################################
#
-# Copyright (C) 2012 PX4 Development Team. All rights reserved.
+# Copyright (c) 2012, 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
@@ -32,11 +32,9 @@
############################################################################
#
-# HMC5883 driver
+# Hardware in the Loop (HIL) simulation actuator output bank
#
-APPNAME = hmc5883
-PRIORITY = SCHED_PRIORITY_DEFAULT
-STACKSIZE = 4096
+MODULE_COMMAND = hil
-include $(APPDIR)/mk/app.mk
+SRCS = hil.cpp
diff --git a/apps/drivers/hmc5883/hmc5883.cpp b/src/drivers/hmc5883/hmc5883.cpp
index 8ab568282..8ab568282 100644
--- a/apps/drivers/hmc5883/hmc5883.cpp
+++ b/src/drivers/hmc5883/hmc5883.cpp
diff --git a/apps/drivers/hil/Makefile b/src/drivers/hmc5883/module.mk
index 1fb6e37bc..07377556d 100644
--- a/apps/drivers/hil/Makefile
+++ b/src/drivers/hmc5883/module.mk
@@ -1,6 +1,6 @@
############################################################################
#
-# Copyright (C) 2012 PX4 Development Team. All rights reserved.
+# Copyright (c) 2012, 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
@@ -32,11 +32,12 @@
############################################################################
#
-# Interface driver for the PX4FMU board
+# HMC5883 driver
#
-APPNAME = hil
-PRIORITY = SCHED_PRIORITY_DEFAULT
-STACKSIZE = 2048
+MODULE_COMMAND = hmc5883
-include $(APPDIR)/mk/app.mk
+# XXX seems excessive, check if 2048 is sufficient
+MODULE_STACKSIZE = 4096
+
+SRCS = hmc5883.cpp
diff --git a/apps/hott_telemetry/hott_telemetry_main.c b/src/drivers/hott_telemetry/hott_telemetry_main.c
index 31c9247aa..a13a6ef58 100644
--- a/apps/hott_telemetry/hott_telemetry_main.c
+++ b/src/drivers/hott_telemetry/hott_telemetry_main.c
@@ -1,7 +1,7 @@
/****************************************************************************
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
- * Author: @author Simon Wilks <sjwilks@gmail.com>
+ * Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
+ * Author: Simon Wilks <sjwilks@gmail.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -34,6 +34,7 @@
/**
* @file hott_telemetry_main.c
+ * @author Simon Wilks <sjwilks@gmail.com>
*
* Graupner HoTT Telemetry implementation.
*
@@ -41,7 +42,6 @@
* a data packet can be returned if necessary.
*
* TODO: Add support for at least the vario and GPS sensor data.
- *
*/
#include <fcntl.h>
@@ -57,12 +57,6 @@
#include "messages.h"
-/* The following are equired for UART direct manipulation. */
-#include <arch/board/board.h>
-#include "up_arch.h"
-#include "chip.h"
-#include "stm32_internal.h"
-
static int thread_should_exit = false; /**< Deamon exit flag */
static int thread_running = false; /**< Deamon status flag */
static int deamon_task; /**< Handle of deamon task / thread */
diff --git a/apps/hott_telemetry/messages.c b/src/drivers/hott_telemetry/messages.c
index 8bfb99773..5fbee16ce 100644
--- a/apps/hott_telemetry/messages.c
+++ b/src/drivers/hott_telemetry/messages.c
@@ -1,7 +1,7 @@
/****************************************************************************
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
- * Author: @author Simon Wilks <sjwilks@gmail.com>
+ * Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
+ * Author: Simon Wilks <sjwilks@gmail.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -34,7 +34,7 @@
/**
* @file messages.c
- *
+ * @author Simon Wilks <sjwilks@gmail.com>
*/
#include "messages.h"
diff --git a/apps/hott_telemetry/messages.h b/src/drivers/hott_telemetry/messages.h
index 44001e04f..dd38075fa 100644
--- a/apps/hott_telemetry/messages.h
+++ b/src/drivers/hott_telemetry/messages.h
@@ -1,7 +1,7 @@
/****************************************************************************
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
- * Author: @author Simon Wilks <sjwilks@gmail.com>
+ * Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
+ * Author: Simon Wilks <sjwilks@gmail.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -34,6 +34,7 @@
/**
* @file messages.h
+ * @author Simon Wilks <sjwilks@gmail.com>
*
* Graupner HoTT Telemetry message generation.
*
diff --git a/src/drivers/hott_telemetry/module.mk b/src/drivers/hott_telemetry/module.mk
new file mode 100644
index 000000000..def1d59e9
--- /dev/null
+++ b/src/drivers/hott_telemetry/module.mk
@@ -0,0 +1,41 @@
+############################################################################
+#
+# Copyright (c) 2012, 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.
+#
+############################################################################
+
+#
+# Graupner HoTT Telemetry application.
+#
+
+MODULE_COMMAND = hott_telemetry
+
+SRCS = hott_telemetry_main.c \
+ messages.c
diff --git a/apps/drivers/mb12xx/mb12xx.cpp b/src/drivers/mb12xx/mb12xx.cpp
index 9d0f6bddc..397686e8b 100644
--- a/apps/drivers/mb12xx/mb12xx.cpp
+++ b/src/drivers/mb12xx/mb12xx.cpp
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2013 PX4 Development Team. All rights reserved.
+ * 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
diff --git a/apps/drivers/mb12xx/Makefile b/src/drivers/mb12xx/module.mk
index 0d2405787..4e00ada02 100644
--- a/apps/drivers/mb12xx/Makefile
+++ b/src/drivers/mb12xx/module.mk
@@ -1,6 +1,6 @@
############################################################################
#
-# Copyright (C) 2013 PX4 Development Team. All rights reserved.
+# 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
@@ -35,8 +35,6 @@
# Makefile to build the Maxbotix Sonar driver.
#
-APPNAME = mb12xx
-PRIORITY = SCHED_PRIORITY_DEFAULT
-STACKSIZE = 2048
+MODULE_COMMAND = mb12xx
-include $(APPDIR)/mk/app.mk
+SRCS = mb12xx.cpp
diff --git a/src/drivers/mpu6000/module.mk b/src/drivers/mpu6000/module.mk
new file mode 100644
index 000000000..c7d9cd3ef
--- /dev/null
+++ b/src/drivers/mpu6000/module.mk
@@ -0,0 +1,43 @@
+############################################################################
+#
+# Copyright (c) 2012, 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.
+#
+############################################################################
+
+#
+# Makefile to build the MPU6000 driver.
+#
+
+MODULE_COMMAND = mpu6000
+
+# XXX seems excessive, check if 2048 is not sufficient
+MODULE_STACKSIZE = 4096
+
+SRCS = mpu6000.cpp
diff --git a/apps/drivers/mpu6000/mpu6000.cpp b/src/drivers/mpu6000/mpu6000.cpp
index ce7062046..df1958186 100644
--- a/apps/drivers/mpu6000/mpu6000.cpp
+++ b/src/drivers/mpu6000/mpu6000.cpp
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * Copyright (c) 2012, 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
diff --git a/apps/drivers/ms5611/Makefile b/src/drivers/ms5611/module.mk
index d8e67cba2..3c4b0f093 100644
--- a/apps/drivers/ms5611/Makefile
+++ b/src/drivers/ms5611/module.mk
@@ -1,6 +1,6 @@
############################################################################
#
-# Copyright (C) 2012 PX4 Development Team. All rights reserved.
+# Copyright (c) 2012, 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
@@ -35,8 +35,6 @@
# MS5611 driver
#
-APPNAME = ms5611
-PRIORITY = SCHED_PRIORITY_DEFAULT
-STACKSIZE = 2048
+MODULE_COMMAND = ms5611
-include $(APPDIR)/mk/app.mk
+SRCS = ms5611.cpp
diff --git a/apps/drivers/ms5611/ms5611.cpp b/src/drivers/ms5611/ms5611.cpp
index 59ab5936e..59ab5936e 100644
--- a/apps/drivers/ms5611/ms5611.cpp
+++ b/src/drivers/ms5611/ms5611.cpp
diff --git a/apps/examples/kalman_demo/KalmanNav.cpp b/src/modules/att_pos_estimator_ekf/KalmanNav.cpp
index 4ef150da1..4ef150da1 100644
--- a/apps/examples/kalman_demo/KalmanNav.cpp
+++ b/src/modules/att_pos_estimator_ekf/KalmanNav.cpp
diff --git a/apps/examples/kalman_demo/KalmanNav.hpp b/src/modules/att_pos_estimator_ekf/KalmanNav.hpp
index c2bf18115..c2bf18115 100644
--- a/apps/examples/kalman_demo/KalmanNav.hpp
+++ b/src/modules/att_pos_estimator_ekf/KalmanNav.hpp
diff --git a/apps/examples/kalman_demo/kalman_demo.cpp b/src/modules/att_pos_estimator_ekf/kalman_main.cpp
index 581b68b01..aebe3d1fe 100644
--- a/apps/examples/kalman_demo/kalman_demo.cpp
+++ b/src/modules/att_pos_estimator_ekf/kalman_main.cpp
@@ -55,7 +55,7 @@ static int deamon_task; /**< Handle of deamon task / thread */
/**
* Deamon management function.
*/
-extern "C" __EXPORT int kalman_demo_main(int argc, char *argv[]);
+extern "C" __EXPORT int att_pos_estimator_ekf_main(int argc, char *argv[]);
/**
* Mainloop of deamon.
@@ -85,7 +85,7 @@ usage(const char *reason)
* The actual stack size should be set in the call
* to task_create().
*/
-int kalman_demo_main(int argc, char *argv[])
+int att_pos_estimator_ekf_main(int argc, char *argv[])
{
if (argc < 1)
diff --git a/apps/fixedwing_att_control/Makefile b/src/modules/att_pos_estimator_ekf/module.mk
index 01465fa9e..21b7c9166 100644
--- a/apps/fixedwing_att_control/Makefile
+++ b/src/modules/att_pos_estimator_ekf/module.mk
@@ -1,6 +1,6 @@
############################################################################
#
-# Copyright (C) 2012 PX4 Development Team. All rights reserved.
+# Copyright (c) 2012, 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
@@ -32,14 +32,14 @@
############################################################################
#
-# Fixedwing Control application
+# Full attitude / position Extended Kalman Filter
#
-APPNAME = fixedwing_att_control
-PRIORITY = SCHED_PRIORITY_MAX - 30
-STACKSIZE = 2048
+MODULE_COMMAND = att_pos_estimator_ekf
-INCLUDES = $(TOPDIR)/../mavlink/include/mavlink
-
-include $(APPDIR)/mk/app.mk
+# XXX this might be intended for the spawned deamon, validate
+MODULE_PRIORITY = "SCHED_PRIORITY_MAX-30"
+SRCS = kalman_main.cpp \
+ KalmanNav.cpp \
+ params.c
diff --git a/apps/examples/kalman_demo/params.c b/src/modules/att_pos_estimator_ekf/params.c
index 50642f067..50642f067 100644
--- a/apps/examples/kalman_demo/params.c
+++ b/src/modules/att_pos_estimator_ekf/params.c
diff --git a/apps/fixedwing_att_control/fixedwing_att_control_att.c b/src/modules/fixedwing_att_control/fixedwing_att_control_att.c
index b012448a2..769b8b0a8 100644
--- a/apps/fixedwing_att_control/fixedwing_att_control_att.c
+++ b/src/modules/fixedwing_att_control/fixedwing_att_control_att.c
@@ -35,7 +35,6 @@
* @file fixedwing_att_control_rate.c
* Implementation of a fixed wing attitude controller.
*/
-#include <fixedwing_att_control_att.h>
#include <nuttx/config.h>
#include <stdio.h>
@@ -59,7 +58,7 @@
#include <systemlib/geo/geo.h>
#include <systemlib/systemlib.h>
-
+#include "fixedwing_att_control_att.h"
struct fw_att_control_params {
diff --git a/apps/fixedwing_att_control/fixedwing_att_control_att.h b/src/modules/fixedwing_att_control/fixedwing_att_control_att.h
index 600e35b89..600e35b89 100644
--- a/apps/fixedwing_att_control/fixedwing_att_control_att.h
+++ b/src/modules/fixedwing_att_control/fixedwing_att_control_att.h
diff --git a/apps/fixedwing_att_control/fixedwing_att_control_main.c b/src/modules/fixedwing_att_control/fixedwing_att_control_main.c
index aa9db6d52..58477632b 100644
--- a/apps/fixedwing_att_control/fixedwing_att_control_main.c
+++ b/src/modules/fixedwing_att_control/fixedwing_att_control_main.c
@@ -65,8 +65,9 @@
#include <systemlib/geo/geo.h>
#include <systemlib/perf_counter.h>
#include <systemlib/systemlib.h>
-#include <fixedwing_att_control_rate.h>
-#include <fixedwing_att_control_att.h>
+
+#include "fixedwing_att_control_rate.h"
+#include "fixedwing_att_control_att.h"
/* Prototypes */
/**
diff --git a/apps/fixedwing_att_control/fixedwing_att_control_rate.c b/src/modules/fixedwing_att_control/fixedwing_att_control_rate.c
index ba5b593e2..4eccc118c 100644
--- a/apps/fixedwing_att_control/fixedwing_att_control_rate.c
+++ b/src/modules/fixedwing_att_control/fixedwing_att_control_rate.c
@@ -33,11 +33,11 @@
****************************************************************************/
/**
* @file fixedwing_att_control_rate.c
+ * @author Thomas Gubler <thomasgubler@student.ethz.ch>
+ *
* Implementation of a fixed wing attitude controller.
*
- * @author Thomas Gubler <thomasgubler@student.ethz.ch>
*/
-#include <fixedwing_att_control_rate.h>
#include <nuttx/config.h>
#include <stdio.h>
@@ -61,6 +61,8 @@
#include <systemlib/geo/geo.h>
#include <systemlib/systemlib.h>
+#include "fixedwing_att_control_rate.h"
+
/*
* Controller parameters, accessible via MAVLink
*
diff --git a/apps/fixedwing_att_control/fixedwing_att_control_rate.h b/src/modules/fixedwing_att_control/fixedwing_att_control_rate.h
index 500e3e197..500e3e197 100644
--- a/apps/fixedwing_att_control/fixedwing_att_control_rate.h
+++ b/src/modules/fixedwing_att_control/fixedwing_att_control_rate.h
diff --git a/src/modules/fixedwing_att_control/module.mk b/src/modules/fixedwing_att_control/module.mk
new file mode 100644
index 000000000..fd1a8724a
--- /dev/null
+++ b/src/modules/fixedwing_att_control/module.mk
@@ -0,0 +1,42 @@
+############################################################################
+#
+# Copyright (c) 2012, 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.
+#
+############################################################################
+
+#
+# Fixedwing Attitude Control application
+#
+
+MODULE_COMMAND = fixedwing_att_control
+
+SRCS = fixedwing_att_control_main.c \
+ fixedwing_att_control_att.c \
+ fixedwing_att_control_rate.c
diff --git a/apps/examples/control_demo/control_demo.cpp b/src/modules/fixedwing_backside/fixedwing_backside_main.cpp
index e609f2f4b..e21990c92 100644
--- a/apps/examples/control_demo/control_demo.cpp
+++ b/src/modules/fixedwing_backside/fixedwing_backside_main.cpp
@@ -1,7 +1,7 @@
/****************************************************************************
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
- * Author: @author Example User <mail@example.com>
+ * Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
+ * Author: James Goppert
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -33,8 +33,10 @@
****************************************************************************/
/**
- * @file control_demo.cpp
- * Demonstration of control library
+ * @file fixedwing_backside_main.cpp
+ * @author James Goppert
+ *
+ * Fixedwing backside controller using control library
*/
#include <nuttx/config.h>
@@ -55,7 +57,7 @@ static int deamon_task; /**< Handle of deamon task / thread */
/**
* Deamon management function.
*/
-extern "C" __EXPORT int control_demo_main(int argc, char *argv[]);
+extern "C" __EXPORT int fixedwing_backside_main(int argc, char *argv[]);
/**
* Mainloop of deamon.
@@ -90,7 +92,7 @@ usage(const char *reason)
* The actual stack size should be set in the call
* to task_create().
*/
-int control_demo_main(int argc, char *argv[])
+int fixedwing_backside_main(int argc, char *argv[])
{
if (argc < 1)
diff --git a/src/modules/fixedwing_backside/module.mk b/src/modules/fixedwing_backside/module.mk
new file mode 100644
index 000000000..a9233288b
--- /dev/null
+++ b/src/modules/fixedwing_backside/module.mk
@@ -0,0 +1,40 @@
+############################################################################
+#
+# Copyright (c) 2012, 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.
+#
+############################################################################
+
+#
+# Fixedwing backside controller
+#
+
+MODULE_COMMAND = fixedwing_backside
+
+SRCS = fixedwing_backside_main.cpp
diff --git a/apps/examples/control_demo/params.c b/src/modules/fixedwing_backside/params.c
index 428b779b1..428b779b1 100644
--- a/apps/examples/control_demo/params.c
+++ b/src/modules/fixedwing_backside/params.c
diff --git a/apps/fixedwing_pos_control/fixedwing_pos_control_main.c b/src/modules/fixedwing_pos_control/fixedwing_pos_control_main.c
index 71c78f5b8..71c78f5b8 100644
--- a/apps/fixedwing_pos_control/fixedwing_pos_control_main.c
+++ b/src/modules/fixedwing_pos_control/fixedwing_pos_control_main.c
diff --git a/src/modules/fixedwing_pos_control/module.mk b/src/modules/fixedwing_pos_control/module.mk
new file mode 100644
index 000000000..b976377e9
--- /dev/null
+++ b/src/modules/fixedwing_pos_control/module.mk
@@ -0,0 +1,40 @@
+############################################################################
+#
+# Copyright (c) 2012, 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.
+#
+############################################################################
+
+#
+# Fixedwing PositionControl application
+#
+
+MODULE_COMMAND = fixedwing_pos_control
+
+SRCS = fixedwing_pos_control_main.c
diff --git a/src/modules/mavlink/.context b/src/modules/mavlink/.context
deleted file mode 100644
index e69de29bb..000000000
--- a/src/modules/mavlink/.context
+++ /dev/null
diff --git a/src/modules/multirotor_att_control/module.mk b/src/modules/multirotor_att_control/module.mk
new file mode 100755
index 000000000..2fd52c162
--- /dev/null
+++ b/src/modules/multirotor_att_control/module.mk
@@ -0,0 +1,42 @@
+############################################################################
+#
+# Copyright (c) 2012, 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.
+#
+############################################################################
+
+#
+# Makefile to build the multirotor attitude controller
+#
+
+MODULE_COMMAND = multirotor_att_control
+
+SRCS = multirotor_att_control_main.c \
+ multirotor_attitude_control.c \
+ multirotor_rate_control.c
diff --git a/apps/multirotor_att_control/multirotor_att_control_main.c b/src/modules/multirotor_att_control/multirotor_att_control_main.c
index d94c0a69c..d94c0a69c 100644
--- a/apps/multirotor_att_control/multirotor_att_control_main.c
+++ b/src/modules/multirotor_att_control/multirotor_att_control_main.c
diff --git a/apps/multirotor_att_control/multirotor_attitude_control.c b/src/modules/multirotor_att_control/multirotor_attitude_control.c
index 76dbb36d3..76dbb36d3 100644
--- a/apps/multirotor_att_control/multirotor_attitude_control.c
+++ b/src/modules/multirotor_att_control/multirotor_attitude_control.c
diff --git a/apps/multirotor_att_control/multirotor_attitude_control.h b/src/modules/multirotor_att_control/multirotor_attitude_control.h
index 2cf83e443..2cf83e443 100644
--- a/apps/multirotor_att_control/multirotor_attitude_control.h
+++ b/src/modules/multirotor_att_control/multirotor_attitude_control.h
diff --git a/apps/multirotor_att_control/multirotor_rate_control.c b/src/modules/multirotor_att_control/multirotor_rate_control.c
index deba1ac03..deba1ac03 100644
--- a/apps/multirotor_att_control/multirotor_rate_control.c
+++ b/src/modules/multirotor_att_control/multirotor_rate_control.c
diff --git a/apps/multirotor_att_control/multirotor_rate_control.h b/src/modules/multirotor_att_control/multirotor_rate_control.h
index 03dec317a..03dec317a 100644
--- a/apps/multirotor_att_control/multirotor_rate_control.h
+++ b/src/modules/multirotor_att_control/multirotor_rate_control.h
diff --git a/src/modules/multirotor_pos_control/module.mk b/src/modules/multirotor_pos_control/module.mk
new file mode 100644
index 000000000..d04847745
--- /dev/null
+++ b/src/modules/multirotor_pos_control/module.mk
@@ -0,0 +1,41 @@
+############################################################################
+#
+# Copyright (c) 2012, 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.
+#
+############################################################################
+
+#
+# Build multirotor position control
+#
+
+MODULE_COMMAND = multirotor_pos_control
+
+SRCS = multirotor_pos_control.c \
+ multirotor_pos_control_params.c
diff --git a/apps/multirotor_pos_control/multirotor_pos_control.c b/src/modules/multirotor_pos_control/multirotor_pos_control.c
index 7b8d83aa8..7b8d83aa8 100644
--- a/apps/multirotor_pos_control/multirotor_pos_control.c
+++ b/src/modules/multirotor_pos_control/multirotor_pos_control.c
diff --git a/apps/multirotor_pos_control/multirotor_pos_control_params.c b/src/modules/multirotor_pos_control/multirotor_pos_control_params.c
index 6b73dc405..6b73dc405 100644
--- a/apps/multirotor_pos_control/multirotor_pos_control_params.c
+++ b/src/modules/multirotor_pos_control/multirotor_pos_control_params.c
diff --git a/apps/multirotor_pos_control/multirotor_pos_control_params.h b/src/modules/multirotor_pos_control/multirotor_pos_control_params.h
index 274f6c22a..274f6c22a 100644
--- a/apps/multirotor_pos_control/multirotor_pos_control_params.h
+++ b/src/modules/multirotor_pos_control/multirotor_pos_control_params.h
diff --git a/apps/multirotor_pos_control/position_control.c b/src/modules/multirotor_pos_control/position_control.c
index 9c53a5bf6..9c53a5bf6 100644
--- a/apps/multirotor_pos_control/position_control.c
+++ b/src/modules/multirotor_pos_control/position_control.c
diff --git a/apps/multirotor_pos_control/position_control.h b/src/modules/multirotor_pos_control/position_control.h
index 2144ebc34..2144ebc34 100644
--- a/apps/multirotor_pos_control/position_control.h
+++ b/src/modules/multirotor_pos_control/position_control.h
diff --git a/apps/position_estimator/Makefile b/src/modules/position_estimator/module.mk
index cc5072152..f64095d9d 100644
--- a/apps/position_estimator/Makefile
+++ b/src/modules/position_estimator/module.mk
@@ -1,6 +1,6 @@
############################################################################
#
-# Copyright (C) 2012 PX4 Development Team. All rights reserved.
+# Copyright (c) 2012, 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
@@ -35,10 +35,10 @@
# Makefile to build the position estimator
#
-APPNAME = position_estimator
-PRIORITY = SCHED_PRIORITY_DEFAULT
-STACKSIZE = 4096
+MODULE_COMMAND = position_estimator
-CSRCS = position_estimator_main.c
+# XXX this should be converted to a deamon, its a pretty bad example app
+MODULE_PRIORITY = SCHED_PRIORITY_DEFAULT
+MODULE_STACKSIZE = 4096
-include $(APPDIR)/mk/app.mk
+SRCS = position_estimator_main.c
diff --git a/apps/position_estimator/position_estimator_main.c b/src/modules/position_estimator/position_estimator_main.c
index e84945299..e84945299 100644
--- a/apps/position_estimator/position_estimator_main.c
+++ b/src/modules/position_estimator/position_estimator_main.c