aboutsummaryrefslogtreecommitdiff
path: root/nuttx
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2013-04-28 10:37:07 +0200
committerLorenz Meier <lm@inf.ethz.ch>2013-04-28 10:37:07 +0200
commit25612cebc2c4ecfc131e545c926f6ff581e11030 (patch)
treee364911002eea58f0d8706e1747c97b57175fba4 /nuttx
parent13fc6703862862f4263d8d5d085b7a16b87190e1 (diff)
downloadpx4-firmware-25612cebc2c4ecfc131e545c926f6ff581e11030.tar.gz
px4-firmware-25612cebc2c4ecfc131e545c926f6ff581e11030.tar.bz2
px4-firmware-25612cebc2c4ecfc131e545c926f6ff581e11030.zip
Cleaned up NuttX appconfig, added examples to config
Diffstat (limited to 'nuttx')
-rw-r--r--nuttx/configs/px4fmu/nsh/appconfig87
1 files changed, 0 insertions, 87 deletions
diff --git a/nuttx/configs/px4fmu/nsh/appconfig b/nuttx/configs/px4fmu/nsh/appconfig
index 6e91f3d1a..0e18aa8ef 100644
--- a/nuttx/configs/px4fmu/nsh/appconfig
+++ b/nuttx/configs/px4fmu/nsh/appconfig
@@ -41,93 +41,6 @@ CONFIGURED_APPS += examples/nsh
CONFIGURED_APPS += nshlib
CONFIGURED_APPS += system/readline
-# System library - utility functions
-CONFIGURED_APPS += systemlib
-CONFIGURED_APPS += systemlib/mixer
-
-# Math library
-ifneq ($(CONFIG_APM),y)
-CONFIGURED_APPS += mathlib
-CONFIGURED_APPS += mathlib/CMSIS
-CONFIGURED_APPS += examples/math_demo
-endif
-
-# Control library
-ifneq ($(CONFIG_APM),y)
-CONFIGURED_APPS += controllib
-CONFIGURED_APPS += examples/control_demo
-CONFIGURED_APPS += examples/kalman_demo
-endif
-
-# System utility commands
-CONFIGURED_APPS += systemcmds/reboot
-CONFIGURED_APPS += systemcmds/perf
-CONFIGURED_APPS += systemcmds/top
-CONFIGURED_APPS += systemcmds/boardinfo
-CONFIGURED_APPS += systemcmds/mixer
-CONFIGURED_APPS += systemcmds/param
-CONFIGURED_APPS += systemcmds/pwm
-CONFIGURED_APPS += systemcmds/bl_update
-CONFIGURED_APPS += systemcmds/preflight_check
-CONFIGURED_APPS += systemcmds/delay_test
-
-# Tutorial code from
-# https://pixhawk.ethz.ch/px4/dev/hello_sky
-# CONFIGURED_APPS += examples/px4_simple_app
-
-# Tutorial code from
-# https://pixhawk.ethz.ch/px4/dev/deamon
-# CONFIGURED_APPS += examples/px4_deamon_app
-
-# Tutorial code from
-# https://pixhawk.ethz.ch/px4/dev/debug_values
-# CONFIGURED_APPS += examples/px4_mavlink_debug
-
-# Shared object broker; required by many parts of the system.
-CONFIGURED_APPS += uORB
-
-CONFIGURED_APPS += mavlink
-CONFIGURED_APPS += mavlink_onboard
-CONFIGURED_APPS += commander
-CONFIGURED_APPS += sdlog
-CONFIGURED_APPS += sensors
-
-ifneq ($(CONFIG_APM),y)
-CONFIGURED_APPS += ardrone_interface
-CONFIGURED_APPS += multirotor_att_control
-CONFIGURED_APPS += multirotor_pos_control
-CONFIGURED_APPS += position_estimator_mc
-CONFIGURED_APPS += fixedwing_att_control
-CONFIGURED_APPS += fixedwing_pos_control
-CONFIGURED_APPS += position_estimator
-CONFIGURED_APPS += attitude_estimator_ekf
-CONFIGURED_APPS += hott_telemetry
-endif
-
-# Hacking tools
-#CONFIGURED_APPS += system/i2c
-CONFIGURED_APPS += systemcmds/i2c
-
-# Communication and Drivers
-#CONFIGURED_APPS += drivers/boards/px4fmu
-CONFIGURED_APPS += drivers/device
-CONFIGURED_APPS += drivers/ms5611
-CONFIGURED_APPS += drivers/hmc5883
-CONFIGURED_APPS += drivers/mpu6000
-CONFIGURED_APPS += drivers/bma180
-CONFIGURED_APPS += drivers/px4io
-CONFIGURED_APPS += drivers/stm32
-#CONFIGURED_APPS += drivers/led
-CONFIGURED_APPS += drivers/blinkm
-CONFIGURED_APPS += drivers/stm32/tone_alarm
-CONFIGURED_APPS += drivers/stm32/adc
-CONFIGURED_APPS += drivers/hil
-CONFIGURED_APPS += drivers/gps
-CONFIGURED_APPS += drivers/mb12xx
-
-# Testing stuff
-CONFIGURED_APPS += px4/sensors_bringup
-
ifeq ($(CONFIG_CAN),y)
#CONFIGURED_APPS += examples/can
endif