aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2013-04-27 11:30:41 +0200
committerLorenz Meier <lm@inf.ethz.ch>2013-04-27 11:50:10 +0200
commit574e76532126fea8ab0ac5fd0595f6fb2935f0dd (patch)
treed6cde0e97036de5e7c1a1b325444d4540e995cd0
parent51badab96ddd4273595cf49e494375d7f2235708 (diff)
downloadpx4-firmware-574e76532126fea8ab0ac5fd0595f6fb2935f0dd.tar.gz
px4-firmware-574e76532126fea8ab0ac5fd0595f6fb2935f0dd.tar.bz2
px4-firmware-574e76532126fea8ab0ac5fd0595f6fb2935f0dd.zip
Moved all system commands to the new world
-rw-r--r--apps/systemcmds/boardinfo/.context0
-rw-r--r--apps/systemcmds/calibration/Makefile44
-rwxr-xr-xapps/systemcmds/calibration/calibration.c147
-rw-r--r--apps/systemcmds/calibration/calibration.h60
-rwxr-xr-xapps/systemcmds/calibration/channels_cal.c196
-rwxr-xr-xapps/systemcmds/calibration/range_cal.c224
-rw-r--r--apps/systemcmds/calibration/servo_cal.c264
-rw-r--r--apps/systemcmds/perf/.context0
-rw-r--r--apps/systemcmds/reboot/.context0
-rw-r--r--apps/systemcmds/top/.context0
-rw-r--r--apps/systemcmds/top/Makefile44
-rw-r--r--makefiles/config_px4fmu_default.mk22
-rw-r--r--src/modules/mavlink_onboard/module.mk2
-rw-r--r--src/systemcmds/bl_update/bl_update.c (renamed from apps/systemcmds/bl_update/bl_update.c)2
-rw-r--r--src/systemcmds/bl_update/module.mk (renamed from apps/systemcmds/bl_update/Makefile)11
-rw-r--r--src/systemcmds/boardinfo/boardinfo.c (renamed from apps/systemcmds/boardinfo/boardinfo.c)2
-rw-r--r--src/systemcmds/boardinfo/module.mk (renamed from apps/systemcmds/preflight_check/Makefile)11
-rw-r--r--src/systemcmds/eeprom/module.mk33
-rw-r--r--src/systemcmds/i2c/i2c.c (renamed from apps/systemcmds/i2c/i2c.c)2
-rw-r--r--src/systemcmds/i2c/module.mk (renamed from apps/systemcmds/i2c/Makefile)9
-rw-r--r--src/systemcmds/mixer/mixer.c (renamed from apps/systemcmds/mixer/mixer.c)0
-rw-r--r--src/systemcmds/mixer/module.mk (renamed from apps/systemcmds/mixer/Makefile)9
-rw-r--r--src/systemcmds/param/module.mk (renamed from apps/systemcmds/param/Makefile)10
-rw-r--r--src/systemcmds/param/param.c (renamed from apps/systemcmds/param/param.c)0
-rw-r--r--src/systemcmds/perf/module.mk (renamed from apps/systemcmds/perf/Makefile)9
-rw-r--r--src/systemcmds/perf/perf.c (renamed from apps/systemcmds/perf/perf.c)2
-rw-r--r--src/systemcmds/preflight_check/module.mk (renamed from apps/systemcmds/boardinfo/Makefile)12
-rw-r--r--src/systemcmds/preflight_check/preflight_check.c (renamed from apps/systemcmds/preflight_check/preflight_check.c)2
-rw-r--r--src/systemcmds/pwm/module.mk (renamed from apps/systemcmds/pwm/Makefile)9
-rw-r--r--src/systemcmds/pwm/pwm.c (renamed from apps/systemcmds/pwm/pwm.c)0
-rw-r--r--src/systemcmds/reboot/module.mk41
-rw-r--r--src/systemcmds/reboot/reboot.c (renamed from apps/systemcmds/reboot/reboot.c)0
-rw-r--r--src/systemcmds/top/module.mk (renamed from apps/systemcmds/reboot/Makefile)12
-rw-r--r--src/systemcmds/top/top.c (renamed from apps/systemcmds/top/top.c)0
34 files changed, 131 insertions, 1048 deletions
diff --git a/apps/systemcmds/boardinfo/.context b/apps/systemcmds/boardinfo/.context
deleted file mode 100644
index e69de29bb..000000000
--- a/apps/systemcmds/boardinfo/.context
+++ /dev/null
diff --git a/apps/systemcmds/calibration/Makefile b/apps/systemcmds/calibration/Makefile
deleted file mode 100644
index a1735962e..000000000
--- a/apps/systemcmds/calibration/Makefile
+++ /dev/null
@@ -1,44 +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 calibration tool
-#
-
-APPNAME = calibration
-PRIORITY = SCHED_PRIORITY_MAX - 1
-STACKSIZE = 4096
-
-include $(APPDIR)/mk/app.mk
-
-MAXOPTIMIZATION = -Os
diff --git a/apps/systemcmds/calibration/calibration.c b/apps/systemcmds/calibration/calibration.c
deleted file mode 100755
index 7f8b9240f..000000000
--- a/apps/systemcmds/calibration/calibration.c
+++ /dev/null
@@ -1,147 +0,0 @@
-/****************************************************************************
- * calibration.c
- *
- * Copyright (C) 2012 Ivan Ovinnikov. All rights reserved.
- * Authors: Nils Wenzler <wenzlern@ethz.ch>
- *
- * 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 NuttX 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.
- *
- ****************************************************************************/
-
-/****************************************************************************
- * Included Files
- ****************************************************************************/
-#include <stdio.h>
-#include <stdlib.h>
-#include <string.h>
-#include "calibration.h"
-
-/****************************************************************************
- * Private Function Prototypes
- ****************************************************************************/
-
-static int calibrate_help(int argc, char *argv[]);
-static int calibrate_all(int argc, char *argv[]);
-
-__EXPORT int calibration_main(int argc, char *argv[]);
-
-/****************************************************************************
- * Private Data
- ****************************************************************************/
-
-struct {
- const char *name;
- int (* fn)(int argc, char *argv[]);
- unsigned options;
-#define OPT_NOHELP (1<<0)
-#define OPT_NOALLTEST (1<<1)
-} calibrates[] = {
- {"range", range_cal, 0},
- {"servo", servo_cal, 0},
- {"all", calibrate_all, OPT_NOALLTEST},
- {"help", calibrate_help, OPT_NOALLTEST | OPT_NOHELP},
- {NULL, NULL}
-};
-
-/****************************************************************************
- * Public Data
- ****************************************************************************/
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-
-static int
-calibrate_help(int argc, char *argv[])
-{
- unsigned i;
-
- printf("Available calibration routines:\n");
-
- for (i = 0; calibrates[i].name; i++)
- printf(" %s\n", calibrates[i].name);
-
- return 0;
-}
-
-static int
-calibrate_all(int argc, char *argv[])
-{
- unsigned i;
- char *args[2] = {"all", NULL};
-
- printf("Running all calibration routines...\n\n");
-
- for (i = 0; calibrates[i].name; i++) {
- printf(" %s:\n", calibrates[i].name);
-
- if (calibrates[i].fn(1, args)) {
- printf(" FAIL\n");
-
- } else {
- printf(" DONE\n");
- }
- }
-
- return 0;
-}
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-void press_enter(void)
-{
- int c;
- printf("Press CTRL+ENTER to continue... \n");
- fflush(stdout);
-
- do c = getchar(); while ((c != '\n') && (c != EOF));
-}
-
-/****************************************************************************
- * Name: calibrate_main
- ****************************************************************************/
-
-int calibration_main(int argc, char *argv[])
-{
- unsigned i;
-
- if (argc < 2) {
- printf("calibration: missing name - 'calibration help' for a list of routines\n");
- return 1;
- }
-
- for (i = 0; calibrates[i].name; i++) {
- if (!strcmp(calibrates[i].name, argv[1]))
- return calibrates[i].fn(argc - 1, argv + 1);
- }
-
- printf("calibrate: no routines called '%s' - 'calibration help' for a list of routines\n", argv[1]);
- return 1;
-}
diff --git a/apps/systemcmds/calibration/calibration.h b/apps/systemcmds/calibration/calibration.h
deleted file mode 100644
index 028853ec8..000000000
--- a/apps/systemcmds/calibration/calibration.h
+++ /dev/null
@@ -1,60 +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.
- *
- ****************************************************************************/
-
-#ifndef _CALIBRATION_H
-#define _CALIBRATION_H
-
-/****************************************************************************
- * Included Files
- ****************************************************************************/
-
-/****************************************************************************
- * Definitions
- ****************************************************************************/
-
-/****************************************************************************
- * Public Types
- ****************************************************************************/
-
-/****************************************************************************
- * Public Variables
- ****************************************************************************/
-
-/****************************************************************************
- * Public Function Prototypes
- ****************************************************************************/
-
-extern int range_cal(int argc, char *argv[]);
-extern int servo_cal(int argc, char *argv[]);
-
-#endif
diff --git a/apps/systemcmds/calibration/channels_cal.c b/apps/systemcmds/calibration/channels_cal.c
deleted file mode 100755
index 575138b12..000000000
--- a/apps/systemcmds/calibration/channels_cal.c
+++ /dev/null
@@ -1,196 +0,0 @@
-/****************************************************************************
- * channels_cal.c
- *
- * Copyright (C) 2012 Nils Wenzler. All rights reserved.
- * Authors: Nils Wenzler <wenzlern@ethz.ch>
- *
- * 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 NuttX 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.
- *
- ****************************************************************************/
-
-/****************************************************************************
- * Included Files
- ****************************************************************************/
-#include <stdio.h>
-#include <string.h>
-#include <stdlib.h>
-#include "calibration.h"
-
-/****************************************************************************
- * Defines
- ****************************************************************************/
-#define ABS(a) (((a) < 0) ? -(a) : (a))
-#define MIN(a,b) (((a)<(b))?(a):(b))
-#define MAX(a,b) (((a)>(b))?(a):(b))
-
-/****************************************************************************
- * Private Data
- ****************************************************************************/
-//Store the values here before writing them to global_data_rc_channels
-uint16_t old_values[NR_CHANNELS];
-uint16_t cur_values[NR_CHANNELS];
-uint8_t function_map[NR_CHANNELS];
-char names[12][9];
-
-
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-void press_enter_2(void)
-{
- int c;
- printf("Press CTRL+ENTER to continue... \n");
- fflush(stdout);
-
- do c = getchar(); while ((c != '\n') && (c != EOF));
-}
-
-/**This gets all current values and writes them to min or max
- */
-uint8_t get_val(uint16_t *buffer)
-{
- if (0 == global_data_trylock(&global_data_rc_channels->access_conf)) {
- uint8_t i;
-
- for (i = 0; i < NR_CHANNELS; i++) {
- printf("Channel: %i\t RAW Value: %i: \n", i, global_data_rc_channels->chan[i].raw);
- buffer[i] = global_data_rc_channels->chan[i].raw;
- }
-
- global_data_unlock(&global_data_rc_channels->access_conf);
- return 0;
-
- } else
- return -1;
-}
-
-void set_channel(void)
-{
- static uint8_t j = 0;
- uint8_t i;
-
- for (i = 0; i < NR_CHANNELS; i++) {
- if (ABS(old_values - cur_values) > 50) {
- function_map[j] = i;
- strcpy(names[i], global_data_rc_channels->function_names[j]);
- j++;
- }
- }
-}
-
-void write_dat(void)
-{
- global_data_lock(&global_data_rc_channels->access_conf);
- uint8_t i;
-
- for (i = 0; i < NR_CHANNELS; i++) {
- global_data_rc_channels->function[i] = function_map[i];
- strcpy(global_data_rc_channels->chan[i].name, names[i]);
-
- printf("Channel %i\t Function %s\n", i,
- global_data_rc_channels->chan[i].name);
- }
-
- global_data_unlock(&global_data_rc_channels->access_conf);
-}
-
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-int channels_cal(int argc, char *argv[])
-{
-
- printf("This routine maps the input functions on the remote control\n");
- printf("to the corresponding function (Throttle, Roll,..)\n");
- printf("Always move the stick all the way\n");
- press_enter_2();
-
- printf("Pull the THROTTLE stick down\n");
- press_enter_2();
-
- while (get_val(old_values));
-
- printf("Move the THROTTLE stick up\n ");
- press_enter_2();
-
- while (get_val(cur_values));
-
- set_channel();
-
- printf("Pull the PITCH stick down\n");
- press_enter_2();
-
- while (get_val(old_values));
-
- printf("Move the PITCH stick up\n ");
- press_enter_2();
-
- while (get_val(cur_values));
-
- set_channel();
-
- printf("Put the ROLL stick to the left\n");
- press_enter_2();
-
- while (get_val(old_values));
-
- printf("Put the ROLL stick to the right\n ");
- press_enter_2();
-
- while (get_val(cur_values));
-
- set_channel();
-
- printf("Put the YAW stick to the left\n");
- press_enter_2();
-
- while (get_val(old_values));
-
- printf("Put the YAW stick to the right\n ");
- press_enter_2();
-
- while (get_val(cur_values));
-
- set_channel();
-
- uint8_t k;
-
- for (k = 5; k < NR_CHANNELS; k++) {
- function_map[k] = k;
- strcpy(names[k], global_data_rc_channels->function_names[k]);
- }
-
-//write the values to global_data_rc_channels
- write_dat();
-
- return 0;
-
-}
-
diff --git a/apps/systemcmds/calibration/range_cal.c b/apps/systemcmds/calibration/range_cal.c
deleted file mode 100755
index 159a0d06b..000000000
--- a/apps/systemcmds/calibration/range_cal.c
+++ /dev/null
@@ -1,224 +0,0 @@
-/****************************************************************************
- * range_cal.c
- *
- * Copyright (C) 2012 Nils Wenzler. All rights reserved.
- * Authors: Nils Wenzler <wenzlern@ethz.ch>
- *
- * 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 NuttX 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.
- *
- ****************************************************************************/
-
-/****************************************************************************
- * Included Files
- ****************************************************************************/
-#include <stdio.h>
-#include <stdlib.h>
-#include "calibration.h"
-
-/****************************************************************************
- * Defines
- ****************************************************************************/
-
-/****************************************************************************
- * Private Data
- ****************************************************************************/
-//Store the values here before writing them to global_data_rc_channels
-uint16_t max_values[NR_CHANNELS];
-uint16_t min_values[NR_CHANNELS];
-uint16_t mid_values[NR_CHANNELS];
-
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-
-/**This sets the middle values
- */
-uint8_t set_mid(void)
-{
- if (0 == global_data_trylock(&global_data_rc_channels->access_conf)) {
- uint8_t i;
-
- for (i = 0; i < NR_CHANNELS; i++) {
- if (i == global_data_rc_channels->function[ROLL] ||
- i == global_data_rc_channels->function[YAW] ||
- i == global_data_rc_channels->function[PITCH]) {
-
- mid_values[i] = global_data_rc_channels->chan[i].raw;
-
- } else {
- mid_values[i] = (max_values[i] + min_values[i]) / 2;
- }
-
- }
-
- global_data_unlock(&global_data_rc_channels->access_conf);
- return 0;
-
- } else
- return -1;
-}
-
-/**This gets all current values and writes them to min or max
- */
-uint8_t get_value(void)
-{
- if (0 == global_data_trylock(&global_data_rc_channels->access_conf)) {
- uint8_t i;
-
- for (i = 0; i < NR_CHANNELS; i++) {
- //see if the value is bigger or smaller than 1500 (roughly neutral)
- //and write to the appropriate array
- if (global_data_rc_channels->chan[i].raw != 0 &&
- global_data_rc_channels->chan[i].raw < 1500) {
- min_values[i] = global_data_rc_channels->chan[i].raw;
-
- } else if (global_data_rc_channels->chan[i].raw != 0 &&
- global_data_rc_channels->chan[i].raw > 1500) {
- max_values[i] = global_data_rc_channels->chan[i].raw;
-
- } else {
- max_values[i] = 0;
- min_values[i] = 0;
- }
- }
-
- global_data_unlock(&global_data_rc_channels->access_conf);
- return 0;
-
- } else
- return -1;
-}
-
-
-void write_data(void)
-{
- // global_data_lock(&global_data_rc_channels->access_conf);
- // uint8_t i;
- // for(i=0; i < NR_CHANNELS; i++){
- // //Write the data to global_data_rc_channels (if not 0)
- // if(mid_values[i]!=0 && min_values[i]!=0 && max_values[i]!=0){
- // global_data_rc_channels->chan[i].scaling_factor =
- // 10000/((max_values[i] - min_values[i])/2);
- //
- // global_data_rc_channels->chan[i].mid = mid_values[i];
- // }
- //
- // printf("Channel %i\t Function %s \t\t Min %i\t\t Max %i\t\t Scaling Factor: %i\t Middle Value %i\n",
- // i,
- // global_data_rc_channels->function_name[global_data_rc_channels->function[i]],
- // min_values[i], max_values[i],
- // global_data_rc_channels->chan[i].scaling_factor,
- // global_data_rc_channels->chan[i].mid);
- // }
- // global_data_unlock(&global_data_rc_channels->access_conf);
-
- //Write to the Parameter storage
-
- global_data_parameter_storage->pm.param_values[PARAM_RC1_MIN] = min_values[0];
- global_data_parameter_storage->pm.param_values[PARAM_RC2_MIN] = min_values[1];
- global_data_parameter_storage->pm.param_values[PARAM_RC3_MIN] = min_values[2];
- global_data_parameter_storage->pm.param_values[PARAM_RC4_MIN] = min_values[3];
- global_data_parameter_storage->pm.param_values[PARAM_RC5_MIN] = min_values[4];
- global_data_parameter_storage->pm.param_values[PARAM_RC6_MIN] = min_values[5];
- global_data_parameter_storage->pm.param_values[PARAM_RC7_MIN] = min_values[6];
- global_data_parameter_storage->pm.param_values[PARAM_RC8_MIN] = min_values[7];
-
-
- global_data_parameter_storage->pm.param_values[PARAM_RC1_MAX] = max_values[0];
- global_data_parameter_storage->pm.param_values[PARAM_RC2_MAX] = max_values[1];
- global_data_parameter_storage->pm.param_values[PARAM_RC3_MAX] = max_values[2];
- global_data_parameter_storage->pm.param_values[PARAM_RC4_MAX] = max_values[3];
- global_data_parameter_storage->pm.param_values[PARAM_RC5_MAX] = max_values[4];
- global_data_parameter_storage->pm.param_values[PARAM_RC6_MAX] = max_values[5];
- global_data_parameter_storage->pm.param_values[PARAM_RC7_MAX] = max_values[6];
- global_data_parameter_storage->pm.param_values[PARAM_RC8_MAX] = max_values[7];
-
-
- global_data_parameter_storage->pm.param_values[PARAM_RC1_TRIM] = mid_values[0];
- global_data_parameter_storage->pm.param_values[PARAM_RC2_TRIM] = mid_values[1];
- global_data_parameter_storage->pm.param_values[PARAM_RC3_TRIM] = mid_values[2];
- global_data_parameter_storage->pm.param_values[PARAM_RC4_TRIM] = mid_values[3];
- global_data_parameter_storage->pm.param_values[PARAM_RC5_TRIM] = mid_values[4];
- global_data_parameter_storage->pm.param_values[PARAM_RC6_TRIM] = mid_values[5];
- global_data_parameter_storage->pm.param_values[PARAM_RC7_TRIM] = mid_values[6];
- global_data_parameter_storage->pm.param_values[PARAM_RC8_TRIM] = mid_values[7];
-
- usleep(3e6);
- uint8_t i;
-
- for (i = 0; i < NR_CHANNELS; i++) {
- printf("Channel %i:\t\t Min %i\t\t Max %i\t\t Scaling Factor: %i\t Middle Value %i\n",
- i,
- min_values[i], max_values[i],
- global_data_rc_channels->chan[i].scaling_factor,
- global_data_rc_channels->chan[i].mid);
- }
-
-
-}
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-int range_cal(int argc, char *argv[])
-{
-
- printf("The range calibration routine assumes you already did the channel\n");
- printf("assignment\n");
- printf("This routine chooses the minimum, maximum and middle\n");
- printf("value for each channel separatly. The ROLL, PITCH and YAW function\n");
- printf("get their middle value from the RC direct, for the rest it is\n");
- printf("calculated out of the min and max values.\n");
- press_enter();
-
- printf("Hold both sticks in lower left corner and continue\n ");
- press_enter();
- usleep(500000);
-
- while (get_value());
-
- printf("Hold both sticks in upper right corner and continue\n");
- press_enter();
- usleep(500000);
-
- while (get_value());
-
- printf("Set the trim to 0 and leave the sticks in the neutral position\n");
- press_enter();
-
- //Loop until successfull
- while (set_mid());
-
- //write the values to global_data_rc_channels
- write_data();
-
- return 0;
-
-}
-
diff --git a/apps/systemcmds/calibration/servo_cal.c b/apps/systemcmds/calibration/servo_cal.c
deleted file mode 100644
index 96b3045a9..000000000
--- a/apps/systemcmds/calibration/servo_cal.c
+++ /dev/null
@@ -1,264 +0,0 @@
-/****************************************************************************
- * servo_cal.c
- *
- * Copyright (C) 2012 Nils Wenzler. All rights reserved.
- * Authors: Nils Wenzler <wenzlern@ethz.ch>
- *
- * 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 NuttX 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.
- *
- ****************************************************************************/
-
-/****************************************************************************
- * Included Files
- ****************************************************************************/
-#include <stdio.h>
-#include <stdlib.h>
-#include <arch/board/drv_pwm_servo.h>
-#include <fcntl.h>
-#include "calibration.h"
-
-/****************************************************************************
- * Defines
- ****************************************************************************/
-
-/****************************************************************************
- * Private Data
- ****************************************************************************/
-//Store the values here before writing them to global_data_rc_channels
-uint16_t max_values_servo[PWM_SERVO_MAX_CHANNELS];
-uint16_t min_values_servo[PWM_SERVO_MAX_CHANNELS];
-uint16_t mid_values_servo[PWM_SERVO_MAX_CHANNELS];
-
-// Servo loop thread
-
-pthread_t servo_calib_thread;
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-
-/**This sets the middle values
- */
-uint8_t set_mid_s(void)
-{
- if (0 == global_data_trylock(&global_data_rc_channels->access_conf)) {
- uint8_t i;
-
- for (i = 0; i < PWM_SERVO_MAX_CHANNELS; i++) {
- if (i == global_data_rc_channels->function[ROLL] ||
- i == global_data_rc_channels->function[YAW] ||
- i == global_data_rc_channels->function[PITCH]) {
-
- mid_values_servo[i] = global_data_rc_channels->chan[i].raw;
-
- } else {
- mid_values_servo[i] = (max_values_servo[i] + min_values_servo[i]) / 2;
- }
-
- }
-
- global_data_unlock(&global_data_rc_channels->access_conf);
- return 0;
-
- } else
- return -1;
-}
-
-/**This gets all current values and writes them to min or max
- */
-uint8_t get_value_s(void)
-{
- if (0 == global_data_trylock(&global_data_rc_channels->access_conf)) {
- uint8_t i;
-
- for (i = 0; i < PWM_SERVO_MAX_CHANNELS; i++) {
- //see if the value is bigger or smaller than 1500 (roughly neutral)
- //and write to the appropriate array
- if (global_data_rc_channels->chan[i].raw != 0 &&
- global_data_rc_channels->chan[i].raw < 1500) {
- min_values_servo[i] = global_data_rc_channels->chan[i].raw;
-
- } else if (global_data_rc_channels->chan[i].raw != 0 &&
- global_data_rc_channels->chan[i].raw > 1500) {
- max_values_servo[i] = global_data_rc_channels->chan[i].raw;
-
- } else {
- max_values_servo[i] = 0;
- min_values_servo[i] = 0;
- }
- }
-
- global_data_unlock(&global_data_rc_channels->access_conf);
- return 0;
-
- } else
- return -1;
-}
-
-
-void write_data_s(void)
-{
- // global_data_lock(&global_data_rc_channels->access_conf);
- // uint8_t i;
- // for(i=0; i < NR_CHANNELS; i++){
- // //Write the data to global_data_rc_channels (if not 0)
- // if(mid_values_servo[i]!=0 && min_values_servo[i]!=0 && max_values_servo[i]!=0){
- // global_data_rc_channels->chan[i].scaling_factor =
- // 10000/((max_values_servo[i] - min_values_servo[i])/2);
- //
- // global_data_rc_channels->chan[i].mid = mid_values_servo[i];
- // }
- //
- // printf("Channel %i\t Function %s \t\t Min %i\t\t Max %i\t\t Scaling Factor: %i\t Middle Value %i\n",
- // i,
- // global_data_rc_channels->function_name[global_data_rc_channels->function[i]],
- // min_values_servo[i], max_values_servo[i],
- // global_data_rc_channels->chan[i].scaling_factor,
- // global_data_rc_channels->chan[i].mid);
- // }
- // global_data_unlock(&global_data_rc_channels->access_conf);
-
- //Write to the Parameter storage
-
-
-
- global_data_lock(&global_data_parameter_storage->access_conf);
-
- global_data_parameter_storage->pm.param_values[PARAM_SERVO1_MIN] = min_values_servo[0];
- global_data_parameter_storage->pm.param_values[PARAM_SERVO2_MIN] = min_values_servo[1];
- global_data_parameter_storage->pm.param_values[PARAM_SERVO3_MIN] = min_values_servo[2];
- global_data_parameter_storage->pm.param_values[PARAM_SERVO4_MIN] = min_values_servo[3];
-
- global_data_parameter_storage->pm.param_values[PARAM_SERVO1_MAX] = max_values_servo[0];
- global_data_parameter_storage->pm.param_values[PARAM_SERVO2_MAX] = max_values_servo[1];
- global_data_parameter_storage->pm.param_values[PARAM_SERVO3_MAX] = max_values_servo[2];
- global_data_parameter_storage->pm.param_values[PARAM_SERVO4_MAX] = max_values_servo[3];
-
- global_data_parameter_storage->pm.param_values[PARAM_SERVO1_TRIM] = mid_values_servo[0];
- global_data_parameter_storage->pm.param_values[PARAM_SERVO2_TRIM] = mid_values_servo[1];
- global_data_parameter_storage->pm.param_values[PARAM_SERVO3_TRIM] = mid_values_servo[2];
- global_data_parameter_storage->pm.param_values[PARAM_SERVO4_TRIM] = mid_values_servo[3];
-
- global_data_unlock(&global_data_parameter_storage->access_conf);
-
- usleep(3e6);
- uint8_t i;
-
- for (i = 0; i < NR_CHANNELS; i++) {
- printf("Channel %i:\t\t Min %i\t\t Max %i\t\t Scaling Factor: %i\t Middle Value %i\n",
- i,
- min_values_servo[i], max_values_servo[i],
- global_data_rc_channels->chan[i].scaling_factor,
- global_data_rc_channels->chan[i].mid);
- }
-
-}
-
-static void *servo_loop(void *arg)
-{
-
- // Set thread name
- prctl(1, "calibration servo", getpid());
-
- // initialize servos
- int fd;
- servo_position_t data[PWM_SERVO_MAX_CHANNELS];
-
- fd = open("/dev/pwm_servo", O_RDWR);
-
- if (fd < 0) {
- printf("failed opening /dev/pwm_servo\n");
- }
-
- ioctl(fd, PWM_SERVO_ARM, 0);
-
- while (1) {
- int i;
-
- for (i = 0; i < 4; i++) {
- data[i] = global_data_rc_channels->chan[global_data_rc_channels->function[THROTTLE]].raw;
- }
-
- int result = write(fd, &data, sizeof(data));
-
- if (result != sizeof(data)) {
- printf("failed bulk-reading channel values\n");
- }
-
- // 5Hz loop
- usleep(200000);
- }
-
- return NULL;
-}
-
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-int servo_cal(int argc, char *argv[])
-{
- // pthread_attr_t servo_loop_attr;
- // pthread_attr_init(&servo_loop_attr);
- // pthread_attr_setstacksize(&servo_loop_attr, 1024);
- pthread_create(&servo_calib_thread, NULL, servo_loop, NULL);
- pthread_join(servo_calib_thread, NULL);
-
- printf("The servo calibration routine assumes you already did the channel\n");
- printf("assignment with 'calibration channels'\n");
- printf("This routine chooses the minimum, maximum and middle\n");
- printf("value for each channel separately. The ROLL, PITCH and YAW function\n");
- printf("get their middle value from the RC direct, for the rest it is\n");
- printf("calculated out of the min and max values.\n");
- press_enter();
-
- printf("Hold both sticks in lower left corner and continue\n ");
- press_enter();
- usleep(500000);
-
- while (get_value_s());
-
- printf("Hold both sticks in upper right corner and continue\n");
- press_enter();
- usleep(500000);
-
- while (get_value_s());
-
- printf("Set the trim to 0 and leave the sticks in the neutral position\n");
- press_enter();
-
- //Loop until successfull
- while (set_mid_s());
-
- //write the values to global_data_rc_channels
- write_data_s();
-
- return 0;
-
-}
-
diff --git a/apps/systemcmds/perf/.context b/apps/systemcmds/perf/.context
deleted file mode 100644
index e69de29bb..000000000
--- a/apps/systemcmds/perf/.context
+++ /dev/null
diff --git a/apps/systemcmds/reboot/.context b/apps/systemcmds/reboot/.context
deleted file mode 100644
index e69de29bb..000000000
--- a/apps/systemcmds/reboot/.context
+++ /dev/null
diff --git a/apps/systemcmds/top/.context b/apps/systemcmds/top/.context
deleted file mode 100644
index e69de29bb..000000000
--- a/apps/systemcmds/top/.context
+++ /dev/null
diff --git a/apps/systemcmds/top/Makefile b/apps/systemcmds/top/Makefile
deleted file mode 100644
index f58f9212e..000000000
--- a/apps/systemcmds/top/Makefile
+++ /dev/null
@@ -1,44 +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.
-#
-############################################################################
-
-#
-# realtime system performance display
-#
-
-APPNAME = top
-PRIORITY = SCHED_PRIORITY_DEFAULT - 10
-STACKSIZE = 3000
-
-include $(APPDIR)/mk/app.mk
-
-MAXOPTIMIZATION = -Os
diff --git a/makefiles/config_px4fmu_default.mk b/makefiles/config_px4fmu_default.mk
index 44e35bdf9..b3ebe4553 100644
--- a/makefiles/config_px4fmu_default.mk
+++ b/makefiles/config_px4fmu_default.mk
@@ -16,9 +16,19 @@ MODULES += drivers/l3gd20
MODULES += drivers/ardrone_interface
#
-# System utilities
+# System commands
#
MODULES += systemcmds/eeprom
+MODULES += systemcmds/bl_update
+MODULES += systemcmds/boardinfo
+MODULES += systemcmds/i2c
+MODULES += systemcmds/mixer
+MODULES += systemcmds/param
+MODULES += systemcmds/perf
+MODULES += systemcmds/preflight_check
+MODULES += systemcmds/pwm
+MODULES += systemcmds/reboot
+MODULES += systemcmds/top
MODULES += systemcmds/tests
#
@@ -48,12 +58,9 @@ endef
# command priority stack entrypoint
BUILTIN_COMMANDS := \
$(call _B, adc, , 2048, adc_main ) \
- $(call _B, bl_update, , 4096, bl_update_main ) \
$(call _B, blinkm, , 2048, blinkm_main ) \
$(call _B, bma180, , 2048, bma180_main ) \
- $(call _B, boardinfo, , 2048, boardinfo_main ) \
$(call _B, control_demo, , 2048, control_demo_main ) \
- $(call _B, delay_test, , 2048, delay_test_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 ) \
@@ -62,22 +69,15 @@ BUILTIN_COMMANDS := \
$(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, mixer, , 4096, mixer_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, param, , 4096, param_main ) \
- $(call _B, perf, , 2048, perf_main ) \
$(call _B, position_estimator, , 4096, position_estimator_main ) \
- $(call _B, preflight_check, , 2048, preflight_check_main ) \
$(call _B, px4io, , 2048, px4io_main ) \
- $(call _B, reboot, , 2048, reboot_main ) \
$(call _B, sdlog, SCHED_PRIORITY_MAX-30, 2048, sdlog_main ) \
$(call _B, sensors, SCHED_PRIORITY_MAX-5, 4096, sensors_main ) \
$(call _B, sercon, , 2048, sercon_main ) \
$(call _B, serdis, , 2048, serdis_main ) \
$(call _B, tone_alarm, , 2048, tone_alarm_main ) \
- $(call _B, top, SCHED_PRIORITY_DEFAULT-10, 3000, top_main ) \
- $(call _B, param, SCHED_PRIORITY_DEFAULT-10, 2048, param_main ) \
$(call _B, uorb, , 4096, uorb_main )
diff --git a/src/modules/mavlink_onboard/module.mk b/src/modules/mavlink_onboard/module.mk
index c40fa042e..a7a4980fa 100644
--- a/src/modules/mavlink_onboard/module.mk
+++ b/src/modules/mavlink_onboard/module.mk
@@ -37,6 +37,6 @@
MODULE_COMMAND = mavlink_onboard
SRCS = mavlink.c \
- mavlink_receiver.c
+ mavlink_receiver.c
INCLUDE_DIRS += $(MAVLINK_SRC)/include/mavlink
diff --git a/apps/systemcmds/bl_update/bl_update.c b/src/systemcmds/bl_update/bl_update.c
index 45715b791..0569d89f5 100644
--- a/apps/systemcmds/bl_update/bl_update.c
+++ b/src/systemcmds/bl_update/bl_update.c
@@ -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/systemcmds/bl_update/Makefile b/src/systemcmds/bl_update/module.mk
index d05493577..e8eea045e 100644
--- a/apps/systemcmds/bl_update/Makefile
+++ b/src/systemcmds/bl_update/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,13 +32,12 @@
############################################################################
#
-# Build the eeprom tool.
+# Bootloader updater (flashes the FMU USB bootloader software)
#
-APPNAME = bl_update
-PRIORITY = SCHED_PRIORITY_DEFAULT
-STACKSIZE = 4096
+MODULE_COMMAND = bl_update
+SRCS = bl_update.c
-include $(APPDIR)/mk/app.mk
+MODULE_STACKSIZE = 4096
MAXOPTIMIZATION = -Os
diff --git a/apps/systemcmds/boardinfo/boardinfo.c b/src/systemcmds/boardinfo/boardinfo.c
index fb8b07ef4..3ff5a066c 100644
--- a/apps/systemcmds/boardinfo/boardinfo.c
+++ b/src/systemcmds/boardinfo/boardinfo.c
@@ -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/systemcmds/preflight_check/Makefile b/src/systemcmds/boardinfo/module.mk
index 98aadaa86..6851d229b 100644
--- a/apps/systemcmds/preflight_check/Makefile
+++ b/src/systemcmds/boardinfo/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,13 +32,10 @@
############################################################################
#
-# Reboot command.
+# Information about FMU and IO boards connected
#
-APPNAME = preflight_check
-PRIORITY = SCHED_PRIORITY_DEFAULT
-STACKSIZE = 2048
-
-include $(APPDIR)/mk/app.mk
+MODULE_COMMAND = boardinfo
+SRCS = boardinfo.c
MAXOPTIMIZATION = -Os
diff --git a/src/systemcmds/eeprom/module.mk b/src/systemcmds/eeprom/module.mk
index 3b4fc0479..07f3945be 100644
--- a/src/systemcmds/eeprom/module.mk
+++ b/src/systemcmds/eeprom/module.mk
@@ -1,3 +1,36 @@
+############################################################################
+#
+# 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.
+#
+############################################################################
+
#
# EEPROM file system driver
#
diff --git a/apps/systemcmds/i2c/i2c.c b/src/systemcmds/i2c/i2c.c
index e1babdc12..4da238039 100644
--- a/apps/systemcmds/i2c/i2c.c
+++ b/src/systemcmds/i2c/i2c.c
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
* Author: Lorenz Meier <lm@inf.ethz.ch>
*
* Redistribution and use in source and binary forms, with or without
diff --git a/apps/systemcmds/i2c/Makefile b/src/systemcmds/i2c/module.mk
index 046e74757..ab2357c7d 100644
--- a/apps/systemcmds/i2c/Makefile
+++ b/src/systemcmds/i2c/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,7 @@
# Build the i2c test tool.
#
-APPNAME = i2c
-PRIORITY = SCHED_PRIORITY_DEFAULT
-STACKSIZE = 4096
+MODULE_COMMAND = i2c
+SRCS = i2c.c
-include $(APPDIR)/mk/app.mk
+MAXOPTIMIZATION = -Os
diff --git a/apps/systemcmds/mixer/mixer.c b/src/systemcmds/mixer/mixer.c
index 55c4f0836..55c4f0836 100644
--- a/apps/systemcmds/mixer/mixer.c
+++ b/src/systemcmds/mixer/mixer.c
diff --git a/apps/systemcmds/mixer/Makefile b/src/systemcmds/mixer/module.mk
index 3d8ac38cb..d5a3f9f77 100644
--- a/apps/systemcmds/mixer/Makefile
+++ b/src/systemcmds/mixer/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,9 @@
# Build the mixer tool.
#
-APPNAME = mixer
-PRIORITY = SCHED_PRIORITY_DEFAULT
-STACKSIZE = 4096
+MODULE_COMMAND = mixer
+SRCS = mixer.c
-include $(APPDIR)/mk/app.mk
+MODULE_STACKSIZE = 4096
MAXOPTIMIZATION = -Os
diff --git a/apps/systemcmds/param/Makefile b/src/systemcmds/param/module.mk
index f19cadbb6..63f15ad28 100644
--- a/apps/systemcmds/param/Makefile
+++ b/src/systemcmds/param/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 @@
# Build the parameters tool.
#
-APPNAME = param
-PRIORITY = SCHED_PRIORITY_DEFAULT
-STACKSIZE = 4096
+MODULE_COMMAND = param
+SRCS = param.c
-include $(APPDIR)/mk/app.mk
+MODULE_STACKSIZE = 4096
MAXOPTIMIZATION = -Os
+
diff --git a/apps/systemcmds/param/param.c b/src/systemcmds/param/param.c
index 56f5317e3..56f5317e3 100644
--- a/apps/systemcmds/param/param.c
+++ b/src/systemcmds/param/param.c
diff --git a/apps/systemcmds/perf/Makefile b/src/systemcmds/perf/module.mk
index f8bab41b6..77952842b 100644
--- a/apps/systemcmds/perf/Makefile
+++ b/src/systemcmds/perf/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,7 @@
# perf_counter reporting tool
#
-APPNAME = perf
-PRIORITY = SCHED_PRIORITY_DEFAULT
-STACKSIZE = 2048
-
-include $(APPDIR)/mk/app.mk
+MODULE_COMMAND = perf
+SRCS = perf.c
MAXOPTIMIZATION = -Os
diff --git a/apps/systemcmds/perf/perf.c b/src/systemcmds/perf/perf.c
index 64443d019..b69ea597b 100644
--- a/apps/systemcmds/perf/perf.c
+++ b/src/systemcmds/perf/perf.c
@@ -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/systemcmds/boardinfo/Makefile b/src/systemcmds/preflight_check/module.mk
index 6f1be149c..7c3c88783 100644
--- a/apps/systemcmds/boardinfo/Makefile
+++ b/src/systemcmds/preflight_check/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,13 +32,11 @@
############################################################################
#
-# Build the boardinfo tool.
+# Pre-flight check. Locks down system for a few systems with blinking leds
+# and buzzer if the sensors do not report an OK status.
#
-APPNAME = boardinfo
-PRIORITY = SCHED_PRIORITY_DEFAULT
-STACKSIZE = 2048
-
-include $(APPDIR)/mk/app.mk
+MODULE_COMMAND = preflight_check
+SRCS = preflight_check.c
MAXOPTIMIZATION = -Os
diff --git a/apps/systemcmds/preflight_check/preflight_check.c b/src/systemcmds/preflight_check/preflight_check.c
index 9ac6f0b5e..42256be61 100644
--- a/apps/systemcmds/preflight_check/preflight_check.c
+++ b/src/systemcmds/preflight_check/preflight_check.c
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
* Author: @author Lorenz Meier <lm@inf.ethz.ch>
*
* Redistribution and use in source and binary forms, with or without
diff --git a/apps/systemcmds/pwm/Makefile b/src/systemcmds/pwm/module.mk
index 5ab105ed1..4a23bba90 100644
--- a/apps/systemcmds/pwm/Makefile
+++ b/src/systemcmds/pwm/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,7 @@
# Build the pwm tool.
#
-APPNAME = pwm
-PRIORITY = SCHED_PRIORITY_DEFAULT
-STACKSIZE = 4096
+MODULE_COMMAND = pwm
+SRCS = pwm.c
-include $(APPDIR)/mk/app.mk
+MODULE_STACKSIZE = 4096
diff --git a/apps/systemcmds/pwm/pwm.c b/src/systemcmds/pwm/pwm.c
index de7a53199..de7a53199 100644
--- a/apps/systemcmds/pwm/pwm.c
+++ b/src/systemcmds/pwm/pwm.c
diff --git a/src/systemcmds/reboot/module.mk b/src/systemcmds/reboot/module.mk
new file mode 100644
index 000000000..19f64af54
--- /dev/null
+++ b/src/systemcmds/reboot/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.
+#
+############################################################################
+
+#
+# reboot command.
+#
+
+MODULE_COMMAND = reboot
+SRCS = reboot.c
+
+MAXOPTIMIZATION = -Os
diff --git a/apps/systemcmds/reboot/reboot.c b/src/systemcmds/reboot/reboot.c
index 47d3cd948..47d3cd948 100644
--- a/apps/systemcmds/reboot/reboot.c
+++ b/src/systemcmds/reboot/reboot.c
diff --git a/apps/systemcmds/reboot/Makefile b/src/systemcmds/top/module.mk
index 15dd19982..9239aafc3 100644
--- a/apps/systemcmds/reboot/Makefile
+++ b/src/systemcmds/top/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,13 +32,13 @@
############################################################################
#
-# Reboot command.
+# Build top memory / cpu status tool.
#
-APPNAME = reboot
-PRIORITY = SCHED_PRIORITY_DEFAULT
-STACKSIZE = 2048
+MODULE_COMMAND = top
+SRCS = top.c
-include $(APPDIR)/mk/app.mk
+MODULE_STACKSIZE = 3000
MAXOPTIMIZATION = -Os
+
diff --git a/apps/systemcmds/top/top.c b/src/systemcmds/top/top.c
index 59d2bc8f1..59d2bc8f1 100644
--- a/apps/systemcmds/top/top.c
+++ b/src/systemcmds/top/top.c