aboutsummaryrefslogtreecommitdiff
path: root/src/systemcmds
diff options
context:
space:
mode:
Diffstat (limited to 'src/systemcmds')
-rw-r--r--src/systemcmds/config/config.c189
-rw-r--r--src/systemcmds/eeprom/eeprom.c2
-rw-r--r--src/systemcmds/esc_calib/esc_calib.c250
-rw-r--r--src/systemcmds/esc_calib/module.mk41
-rw-r--r--src/systemcmds/i2c/i2c.c2
-rw-r--r--src/systemcmds/nshterm/module.mk41
-rw-r--r--src/systemcmds/nshterm/nshterm.c115
-rw-r--r--src/systemcmds/preflight_check/preflight_check.c99
-rw-r--r--src/systemcmds/pwm/pwm.c48
-rw-r--r--src/systemcmds/reboot/reboot.c19
-rw-r--r--src/systemcmds/top/top.c18
11 files changed, 625 insertions, 199 deletions
diff --git a/src/systemcmds/config/config.c b/src/systemcmds/config/config.c
index 5a02fd620..188dafa4e 100644
--- a/src/systemcmds/config/config.c
+++ b/src/systemcmds/config/config.c
@@ -2,6 +2,7 @@
*
* Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
* Author: Lorenz Meier <lm@inf.ethz.ch>
+ * Author: Julian Oes <joes@student.ethz.ch>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -35,6 +36,7 @@
/**
* @file config.c
* @author Lorenz Meier <lm@inf.ethz.ch>
+ * @author Julian Oes <joes@student.ethz.ch>
*
* config tool.
*/
@@ -69,27 +71,15 @@ config_main(int argc, char *argv[])
{
if (argc >= 2) {
if (!strcmp(argv[1], "gyro")) {
- if (argc >= 3) {
- do_gyro(argc - 2, argv + 2);
- } else {
- errx(1, "not enough parameters.");
- }
+ do_gyro(argc - 2, argv + 2);
}
if (!strcmp(argv[1], "accel")) {
- if (argc >= 3) {
- do_accel(argc - 2, argv + 2);
- } else {
- errx(1, "not enough parameters.");
- }
+ do_accel(argc - 2, argv + 2);
}
if (!strcmp(argv[1], "mag")) {
- if (argc >= 3) {
- do_mag(argc - 2, argv + 2);
- } else {
- errx(1, "not enough parameters.");
- }
+ do_mag(argc - 2, argv + 2);
}
}
@@ -100,6 +90,7 @@ static void
do_gyro(int argc, char *argv[])
{
int fd;
+ int ret;
fd = open(GYRO_DEVICE_PATH, 0);
@@ -109,44 +100,45 @@ do_gyro(int argc, char *argv[])
} else {
- if (argc >= 2) {
+ if (argc == 2 && !strcmp(argv[0], "sampling")) {
- char* end;
- int i = strtol(argv[1],&end,10);
+ /* set the gyro internal sampling rate up to at least i Hz */
+ ret = ioctl(fd, GYROIOCSSAMPLERATE, strtoul(argv[1], NULL, 0));
- if (!strcmp(argv[0], "sampling")) {
+ if (ret)
+ errx(ret,"sampling rate could not be set");
- /* set the accel internal sampling rate up to at leat i Hz */
- ioctl(fd, GYROIOCSSAMPLERATE, i);
+ } else if (argc == 2 && !strcmp(argv[0], "rate")) {
- } else if (!strcmp(argv[0], "rate")) {
+ /* set the driver to poll at i Hz */
+ ret = ioctl(fd, SENSORIOCSPOLLRATE, strtoul(argv[1], NULL, 0));
- /* set the driver to poll at i Hz */
- ioctl(fd, SENSORIOCSPOLLRATE, i);
- } else if (!strcmp(argv[0], "range")) {
+ if (ret)
+ errx(ret,"pollrate could not be set");
- /* set the range to i dps */
- ioctl(fd, GYROIOCSRANGE, i);
- }
+ } else if (argc == 2 && !strcmp(argv[0], "range")) {
+
+ /* set the range to i dps */
+ ret = ioctl(fd, GYROIOCSRANGE, strtoul(argv[1], NULL, 0));
- } else if (argc > 0) {
+ if (ret)
+ errx(ret,"range could not be set");
- if(!strcmp(argv[0], "check")) {
- int ret = ioctl(fd, GYROIOCSELFTEST, 0);
+ } else if(argc == 1 && !strcmp(argv[0], "check")) {
+ ret = ioctl(fd, GYROIOCSELFTEST, 0);
- if (ret) {
- warnx("gyro self test FAILED! Check calibration:");
- struct gyro_scale scale;
- ret = ioctl(fd, GYROIOCGSCALE, (long unsigned int)&scale);
- warnx("offsets: X: % 9.6f Y: % 9.6f Z: % 9.6f", scale.x_offset, scale.y_offset, scale.z_offset);
- warnx("scale: X: % 9.6f Y: % 9.6f Z: % 9.6f", scale.x_scale, scale.y_scale, scale.z_scale);
- } else {
- warnx("gyro calibration and self test OK");
- }
+ if (ret) {
+ warnx("gyro self test FAILED! Check calibration:");
+ struct gyro_scale scale;
+ ret = ioctl(fd, GYROIOCGSCALE, (long unsigned int)&scale);
+ warnx("offsets: X: % 9.6f Y: % 9.6f Z: % 9.6f", scale.x_offset, scale.y_offset, scale.z_offset);
+ warnx("scale: X: % 9.6f Y: % 9.6f Z: % 9.6f", scale.x_scale, scale.y_scale, scale.z_scale);
+ } else {
+ warnx("gyro calibration and self test OK");
}
} else {
- warnx("no arguments given. Try: \n\n\t'sampling 500' to set sampling to 500 Hz\n\t'rate 500' to set publication rate to 500 Hz\n\t'range 2000' to set measurement range to 2000 dps\n\t");
+ errx(1, "wrong or no arguments given. Try: \n\n\t'check' for the self test\n\t'sampling 500' to set sampling to 500 Hz\n\t'rate 500' to set publication rate to 500 Hz\n\t'range 2000' to set measurement range to 2000 dps\n\t");
}
int srate = ioctl(fd, GYROIOCGSAMPLERATE, 0);
@@ -165,6 +157,7 @@ static void
do_mag(int argc, char *argv[])
{
int fd;
+ int ret;
fd = open(MAG_DEVICE_PATH, 0);
@@ -174,31 +167,52 @@ do_mag(int argc, char *argv[])
} else {
- if (argc > 0) {
+ if (argc == 2 && !strcmp(argv[0], "sampling")) {
+
+ /* set the mag internal sampling rate up to at least i Hz */
+ ret = ioctl(fd, MAGIOCSSAMPLERATE, strtoul(argv[1], NULL, 0));
+
+ if (ret)
+ errx(ret,"sampling rate could not be set");
+
+ } else if (argc == 2 && !strcmp(argv[0], "rate")) {
- if (!strcmp(argv[0], "check")) {
- int ret = ioctl(fd, MAGIOCSELFTEST, 0);
+ /* set the driver to poll at i Hz */
+ ret = ioctl(fd, SENSORIOCSPOLLRATE, strtoul(argv[1], NULL, 0));
- if (ret) {
- warnx("mag self test FAILED! Check calibration.");
- struct mag_scale scale;
- ret = ioctl(fd, MAGIOCGSCALE, (long unsigned int)&scale);
- warnx("offsets: X: % 9.6f Y: % 9.6f Z: % 9.6f", scale.x_offset, scale.y_offset, scale.z_offset);
- warnx("scale: X: % 9.6f Y: % 9.6f Z: % 9.6f", scale.x_scale, scale.y_scale, scale.z_scale);
- } else {
- warnx("mag calibration and self test OK");
- }
+ if (ret)
+ errx(ret,"pollrate could not be set");
+
+ } else if (argc == 2 && !strcmp(argv[0], "range")) {
+
+ /* set the range to i G */
+ ret = ioctl(fd, MAGIOCSRANGE, strtoul(argv[1], NULL, 0));
+
+ if (ret)
+ errx(ret,"range could not be set");
+
+ } else if(argc == 1 && !strcmp(argv[0], "check")) {
+ ret = ioctl(fd, MAGIOCSELFTEST, 0);
+
+ if (ret) {
+ warnx("mag self test FAILED! Check calibration:");
+ struct mag_scale scale;
+ ret = ioctl(fd, MAGIOCGSCALE, (long unsigned int)&scale);
+ warnx("offsets: X: % 9.6f Y: % 9.6f Z: % 9.6f", scale.x_offset, scale.y_offset, scale.z_offset);
+ warnx("scale: X: % 9.6f Y: % 9.6f Z: % 9.6f", scale.x_scale, scale.y_scale, scale.z_scale);
+ } else {
+ warnx("mag calibration and self test OK");
}
} else {
- warnx("no arguments given. Try: \n\n\t'check' or 'info'\n\t");
+ errx(1, "wrong or no arguments given. Try: \n\n\t'check' for the self test\n\t");
}
- int srate = -1;//ioctl(fd, MAGIOCGSAMPLERATE, 0);
+ int srate = ioctl(fd, MAGIOCGSAMPLERATE, 0);
int prate = ioctl(fd, SENSORIOCGPOLLRATE, 0);
- int range = -1;//ioctl(fd, MAGIOCGRANGE, 0);
+ int range = ioctl(fd, MAGIOCGRANGE, 0);
- warnx("mag: \n\tsample rate:\t%d Hz\n\tread rate:\t%d Hz\n\trange:\t%d gauss", srate, prate, range);
+ warnx("mag: \n\tsample rate:\t%d Hz\n\tread rate:\t%d Hz\n\trange:\t%d Ga", srate, prate, range);
close(fd);
}
@@ -210,6 +224,7 @@ static void
do_accel(int argc, char *argv[])
{
int fd;
+ int ret;
fd = open(ACCEL_DEVICE_PATH, 0);
@@ -219,50 +234,52 @@ do_accel(int argc, char *argv[])
} else {
- if (argc >= 2) {
+ if (argc == 2 && !strcmp(argv[0], "sampling")) {
- char* end;
- int i = strtol(argv[1],&end,10);
+ /* set the accel internal sampling rate up to at least i Hz */
+ ret = ioctl(fd, ACCELIOCSSAMPLERATE, strtoul(argv[1], NULL, 0));
- if (!strcmp(argv[0], "sampling")) {
+ if (ret)
+ errx(ret,"sampling rate could not be set");
- /* set the accel internal sampling rate up to at leat i Hz */
- ioctl(fd, ACCELIOCSSAMPLERATE, i);
+ } else if (argc == 2 && !strcmp(argv[0], "rate")) {
- } else if (!strcmp(argv[0], "rate")) {
+ /* set the driver to poll at i Hz */
+ ret = ioctl(fd, SENSORIOCSPOLLRATE, strtoul(argv[1], NULL, 0));
- /* set the driver to poll at i Hz */
- ioctl(fd, SENSORIOCSPOLLRATE, i);
- } else if (!strcmp(argv[0], "range")) {
+ if (ret)
+ errx(ret,"pollrate could not be set");
- /* set the range to i dps */
- ioctl(fd, ACCELIOCSRANGE, i);
- }
- } else if (argc > 0) {
-
- if (!strcmp(argv[0], "check")) {
- int ret = ioctl(fd, ACCELIOCSELFTEST, 0);
-
- if (ret) {
- warnx("accel self test FAILED! Check calibration.");
- struct accel_scale scale;
- ret = ioctl(fd, ACCELIOCGSCALE, (long unsigned int)&scale);
- warnx("offsets: X: % 9.6f Y: % 9.6f Z: % 9.6f", scale.x_offset, scale.y_offset, scale.z_offset);
- warnx("scale: X: % 9.6f Y: % 9.6f Z: % 9.6f", scale.x_scale, scale.y_scale, scale.z_scale);
- } else {
- warnx("accel calibration and self test OK");
- }
+ } else if (argc == 2 && !strcmp(argv[0], "range")) {
+
+ /* set the range to i G */
+ ret = ioctl(fd, ACCELIOCSRANGE, strtoul(argv[1], NULL, 0));
+
+ if (ret)
+ errx(ret,"range could not be set");
+
+ } else if(argc == 1 && !strcmp(argv[0], "check")) {
+ ret = ioctl(fd, ACCELIOCSELFTEST, 0);
+
+ if (ret) {
+ warnx("accel self test FAILED! Check calibration:");
+ struct accel_scale scale;
+ ret = ioctl(fd, ACCELIOCGSCALE, (long unsigned int)&scale);
+ warnx("offsets: X: % 9.6f Y: % 9.6f Z: % 9.6f", scale.x_offset, scale.y_offset, scale.z_offset);
+ warnx("scale: X: % 9.6f Y: % 9.6f Z: % 9.6f", scale.x_scale, scale.y_scale, scale.z_scale);
+ } else {
+ warnx("accel calibration and self test OK");
}
} else {
- warnx("no arguments given. Try: \n\n\t'sampling 500' to set sampling to 500 Hz\n\t'rate 500' to set publication rate to 500 Hz\n\t'range 2' to set measurement range to 2 G\n\t");
+ errx(1,"no arguments given. Try: \n\n\t'sampling 500' to set sampling to 500 Hz\n\t'rate 500' to set publication rate to 500 Hz\n\t'range 2' to set measurement range to 4 G\n\t");
}
int srate = ioctl(fd, ACCELIOCGSAMPLERATE, 0);
int prate = ioctl(fd, SENSORIOCGPOLLRATE, 0);
int range = ioctl(fd, ACCELIOCGRANGE, 0);
- warnx("accel: \n\tsample rate:\t%d Hz\n\tread rate:\t%d Hz\n\trange:\t%d m/s", srate, prate, range);
+ warnx("accel: \n\tsample rate:\t%d Hz\n\tread rate:\t%d Hz\n\trange:\t%d G", srate, prate, range);
close(fd);
}
diff --git a/src/systemcmds/eeprom/eeprom.c b/src/systemcmds/eeprom/eeprom.c
index 49da51358..2aed80e01 100644
--- a/src/systemcmds/eeprom/eeprom.c
+++ b/src/systemcmds/eeprom/eeprom.c
@@ -55,7 +55,7 @@
#include <nuttx/fs/nxffs.h>
#include <nuttx/fs/ioctl.h>
-#include <arch/board/board.h>
+#include <board_config.h>
#include "systemlib/systemlib.h"
#include "systemlib/param/param.h"
diff --git a/src/systemcmds/esc_calib/esc_calib.c b/src/systemcmds/esc_calib/esc_calib.c
new file mode 100644
index 000000000..188fa4e37
--- /dev/null
+++ b/src/systemcmds/esc_calib/esc_calib.c
@@ -0,0 +1,250 @@
+/****************************************************************************
+ *
+ * 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
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file esc_calib.c
+ *
+ * Tool for ESC calibration
+ */
+
+#include <nuttx/config.h>
+
+#include <stdio.h>
+#include <stdlib.h>
+#include <string.h>
+#include <stdbool.h>
+#include <unistd.h>
+#include <fcntl.h>
+#include <sys/mount.h>
+#include <sys/ioctl.h>
+#include <sys/stat.h>
+
+#include <nuttx/i2c.h>
+#include <nuttx/mtd.h>
+#include <nuttx/fs/nxffs.h>
+#include <nuttx/fs/ioctl.h>
+
+#include <arch/board/board.h>
+
+#include "systemlib/systemlib.h"
+#include "systemlib/err.h"
+#include "drivers/drv_pwm_output.h"
+
+static void usage(const char *reason);
+__EXPORT int esc_calib_main(int argc, char *argv[]);
+
+#define MAX_CHANNELS 8
+
+static void
+usage(const char *reason)
+{
+ if (reason != NULL)
+ warnx("%s", reason);
+ errx(1,
+ "usage:\n"
+ "esc_calib [-d <device>] <channels>\n"
+ " <device> PWM output device (defaults to " PWM_OUTPUT_DEVICE_PATH ")\n"
+ " <channels> Provide channels (e.g.: 1 2 3 4)\n"
+ );
+
+}
+
+int
+esc_calib_main(int argc, char *argv[])
+{
+ const char *dev = PWM_OUTPUT_DEVICE_PATH;
+ char *ep;
+ bool channels_selected[MAX_CHANNELS] = {false};
+ int ch;
+ int ret;
+ char c;
+
+ if (argc < 2)
+ usage(NULL);
+
+ while ((ch = getopt(argc, argv, "d:")) != EOF) {
+ switch (ch) {
+
+ case 'd':
+ dev = optarg;
+ argc--;
+ break;
+
+ default:
+ usage(NULL);
+ }
+ }
+
+ if(argc < 1) {
+ usage("no channels provided");
+ }
+
+ while (--argc) {
+ const char *arg = argv[argc];
+ unsigned channel_number = strtol(arg, &ep, 0);
+
+ if (*ep == '\0') {
+ if (channel_number > MAX_CHANNELS || channel_number <= 0) {
+ err(1, "invalid channel number: %d", channel_number);
+ } else {
+ channels_selected[channel_number-1] = true;
+
+ }
+ }
+ }
+
+ /* Wait for confirmation */
+ int console = open("/dev/console", O_NONBLOCK | O_RDONLY | O_NOCTTY);
+ if (!console)
+ err(1, "failed opening console");
+
+ warnx("ATTENTION, please remove or fix props before starting calibration!\n"
+ "\n"
+ "Also press the arming switch first for safety off\n"
+ "\n"
+ "Do you really want to start calibration: y or n?\n");
+
+ /* wait for user input */
+ while (1) {
+
+ if (read(console, &c, 1) == 1) {
+ if (c == 'y' || c == 'Y') {
+
+ break;
+ } else if (c == 0x03 || c == 0x63 || c == 'q') {
+ warnx("ESC calibration exited");
+ close(console);
+ exit(0);
+ } else if (c == 'n' || c == 'N') {
+ warnx("ESC calibration aborted");
+ close(console);
+ exit(0);
+ } else {
+ warnx("Unknown input, ESC calibration aborted");
+ close(console);
+ exit(0);
+ }
+ }
+ /* rate limit to ~ 20 Hz */
+ usleep(50000);
+ }
+
+ /* open for ioctl only */
+ int fd = open(dev, 0);
+ if (fd < 0)
+ err(1, "can't open %s", dev);
+
+ // XXX arming not necessaire at the moment
+ // /* Then arm */
+ // ret = ioctl(fd, PWM_SERVO_SET_ARM_OK, 0);
+ // if (ret != OK)
+ // err(1, "PWM_SERVO_SET_ARM_OK");
+
+ // ret = ioctl(fd, PWM_SERVO_ARM, 0);
+ // if (ret != OK)
+ // err(1, "PWM_SERVO_ARM");
+
+
+
+
+ /* Wait for user confirmation */
+ warnx("Set high PWM\n"
+ "Connect battery now and hit ENTER after the ESCs confirm the first calibration step");
+
+ while (1) {
+
+ /* First set high PWM */
+ for (unsigned i = 0; i<MAX_CHANNELS; i++) {
+ if(channels_selected[i]) {
+ ret = ioctl(fd, PWM_SERVO_SET(i), 2100);
+ if (ret != OK)
+ err(1, "PWM_SERVO_SET(%d)", i);
+ }
+ }
+
+ if (read(console, &c, 1) == 1) {
+ if (c == 13) {
+
+ break;
+ } else if (c == 0x03 || c == 0x63 || c == 'q') {
+ warnx("ESC calibration exited");
+ close(console);
+ exit(0);
+ }
+ }
+ /* rate limit to ~ 20 Hz */
+ usleep(50000);
+ }
+
+ /* we don't need any more user input */
+
+
+ warnx("Set low PWM, hit ENTER when finished");
+
+ while (1) {
+
+ /* Then set low PWM */
+ for (unsigned i = 0; i<MAX_CHANNELS; i++) {
+ if(channels_selected[i]) {
+ ret = ioctl(fd, PWM_SERVO_SET(i), 900);
+ if (ret != OK)
+ err(1, "PWM_SERVO_SET(%d)", i);
+ }
+ }
+
+ if (read(console, &c, 1) == 1) {
+ if (c == 13) {
+
+ break;
+ } else if (c == 0x03 || c == 0x63 || c == 'q') {
+ warnx("ESC calibration exited");
+ close(console);
+ exit(0);
+ }
+ }
+ /* rate limit to ~ 20 Hz */
+ usleep(50000);
+ }
+
+
+ warnx("ESC calibration finished");
+ close(console);
+
+ // XXX disarming not necessaire at the moment
+ /* Now disarm again */
+ // ret = ioctl(fd, PWM_SERVO_DISARM, 0);
+
+
+
+ exit(0);
+} \ No newline at end of file
diff --git a/src/systemcmds/esc_calib/module.mk b/src/systemcmds/esc_calib/module.mk
new file mode 100644
index 000000000..990c56768
--- /dev/null
+++ b/src/systemcmds/esc_calib/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 the esc_calib tool.
+#
+
+MODULE_COMMAND = esc_calib
+SRCS = esc_calib.c
+
+MODULE_STACKSIZE = 4096
diff --git a/src/systemcmds/i2c/i2c.c b/src/systemcmds/i2c/i2c.c
index 4da238039..34405c496 100644
--- a/src/systemcmds/i2c/i2c.c
+++ b/src/systemcmds/i2c/i2c.c
@@ -52,7 +52,7 @@
#include <nuttx/i2c.h>
-#include <arch/board/board.h>
+#include <board_config.h>
#include "systemlib/systemlib.h"
#include "systemlib/err.h"
diff --git a/src/systemcmds/nshterm/module.mk b/src/systemcmds/nshterm/module.mk
new file mode 100644
index 000000000..a48588535
--- /dev/null
+++ b/src/systemcmds/nshterm/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 nshterm utility
+#
+
+MODULE_COMMAND = nshterm
+SRCS = nshterm.c
+
+MODULE_STACKSIZE = 3000
diff --git a/src/systemcmds/nshterm/nshterm.c b/src/systemcmds/nshterm/nshterm.c
new file mode 100644
index 000000000..458bb2259
--- /dev/null
+++ b/src/systemcmds/nshterm/nshterm.c
@@ -0,0 +1,115 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
+ * Author: Andrew Tridgell
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file nshterm.c
+ * start a nsh terminal on a given port. This can be useful for error
+ * handling in startup scripts to start a nsh shell on /dev/ttyACM0
+ * for diagnostics
+ */
+
+#include <nuttx/config.h>
+#include <termios.h>
+#include <stdbool.h>
+#include <stdio.h>
+#include <stdarg.h>
+#include <unistd.h>
+#include <stdlib.h>
+#include <errno.h>
+#include <apps/nsh.h>
+#include <fcntl.h>
+#include <systemlib/err.h>
+
+__EXPORT int nshterm_main(int argc, char *argv[]);
+
+int
+nshterm_main(int argc, char *argv[])
+{
+ if (argc < 2) {
+ printf("Usage: nshterm <device>\n");
+ exit(1);
+ }
+ uint8_t retries = 0;
+ int fd = -1;
+ while (retries < 50) {
+ /* the retries are to cope with the behaviour of /dev/ttyACM0 */
+ /* which may not be ready immediately. */
+ fd = open(argv[1], O_RDWR);
+ if (fd != -1) {
+ break;
+ }
+ usleep(100000);
+ retries++;
+ }
+ if (fd == -1) {
+ perror(argv[1]);
+ exit(1);
+ }
+
+ /* set up the serial port with output processing */
+
+ /* Try to set baud rate */
+ struct termios uart_config;
+ int termios_state;
+
+ /* Back up the original uart configuration to restore it after exit */
+ if ((termios_state = tcgetattr(fd, &uart_config)) < 0) {
+ warnx("ERROR get termios config %s: %d\n", argv[1], termios_state);
+ close(fd);
+ return -1;
+ }
+
+ /* Set ONLCR flag (which appends a CR for every LF) */
+ uart_config.c_oflag |= (ONLCR | OPOST/* | OCRNL*/);
+
+ if ((termios_state = tcsetattr(fd, TCSANOW, &uart_config)) < 0) {
+ warnx("ERROR setting baudrate / termios config for %s (tcsetattr)\n", argv[1]);
+ close(fd);
+ return -1;
+ }
+
+ /* setup standard file descriptors */
+ close(0);
+ close(1);
+ close(2);
+ dup2(fd, 0);
+ dup2(fd, 1);
+ dup2(fd, 2);
+
+ nsh_consolemain(0, NULL);
+
+ close(fd);
+
+ return OK;
+}
diff --git a/src/systemcmds/preflight_check/preflight_check.c b/src/systemcmds/preflight_check/preflight_check.c
index d1dd85d47..4c19dcffb 100644
--- a/src/systemcmds/preflight_check/preflight_check.c
+++ b/src/systemcmds/preflight_check/preflight_check.c
@@ -57,6 +57,7 @@
#include <drivers/drv_baro.h>
#include <mavlink/mavlink_log.h>
+#include <systemlib/rc_check.h>
__EXPORT int preflight_check_main(int argc, char *argv[]);
static int led_toggle(int leds, int led);
@@ -139,101 +140,7 @@ int preflight_check_main(int argc, char *argv[])
/* ---- RC CALIBRATION ---- */
- param_t _parameter_handles_min, _parameter_handles_trim, _parameter_handles_max,
- _parameter_handles_rev, _parameter_handles_dz;
-
- float param_min, param_max, param_trim, param_rev, param_dz;
-
- bool rc_ok = true;
- char nbuf[20];
-
- /* first check channel mappings */
- /* check which map param applies */
- // if (map_by_channel[i] >= MAX_CONTROL_CHANNELS) {
- // mavlink_log_critical(mavlink_fd, "ERR: RC_%d_MAP >= # CHANS", i+1);
- // /* give system time to flush error message in case there are more */
- // usleep(100000);
- // count++;
- // }
-
- for (int i = 0; i < 12; i++) {
- /* should the channel be enabled? */
- uint8_t count = 0;
-
- /* min values */
- sprintf(nbuf, "RC%d_MIN", i + 1);
- _parameter_handles_min = param_find(nbuf);
- param_get(_parameter_handles_min, &param_min);
-
- /* trim values */
- sprintf(nbuf, "RC%d_TRIM", i + 1);
- _parameter_handles_trim = param_find(nbuf);
- param_get(_parameter_handles_trim, &param_trim);
-
- /* max values */
- sprintf(nbuf, "RC%d_MAX", i + 1);
- _parameter_handles_max = param_find(nbuf);
- param_get(_parameter_handles_max, &param_max);
-
- /* channel reverse */
- sprintf(nbuf, "RC%d_REV", i + 1);
- _parameter_handles_rev = param_find(nbuf);
- param_get(_parameter_handles_rev, &param_rev);
-
- /* channel deadzone */
- sprintf(nbuf, "RC%d_DZ", i + 1);
- _parameter_handles_dz = param_find(nbuf);
- param_get(_parameter_handles_dz, &param_dz);
-
- /* assert min..center..max ordering */
- if (param_min < 500) {
- count++;
- mavlink_log_critical(mavlink_fd, "ERR: RC_%d_MIN < 500", i+1);
- /* give system time to flush error message in case there are more */
- usleep(100000);
- }
- if (param_max > 2500) {
- count++;
- mavlink_log_critical(mavlink_fd, "ERR: RC_%d_MAX > 2500", i+1);
- /* give system time to flush error message in case there are more */
- usleep(100000);
- }
- if (param_trim < param_min) {
- count++;
- mavlink_log_critical(mavlink_fd, "ERR: RC_%d_TRIM < MIN", i+1);
- /* give system time to flush error message in case there are more */
- usleep(100000);
- }
- if (param_trim > param_max) {
- count++;
- mavlink_log_critical(mavlink_fd, "ERR: RC_%d_TRIM > MAX", i+1);
- /* give system time to flush error message in case there are more */
- usleep(100000);
- }
-
- /* assert deadzone is sane */
- if (param_dz > 500) {
- mavlink_log_critical(mavlink_fd, "ERR: RC_%d_DZ > 500", i+1);
- /* give system time to flush error message in case there are more */
- usleep(100000);
- count++;
- }
-
- /* check which map param applies */
- // if (map_by_channel[i] >= MAX_CONTROL_CHANNELS) {
- // mavlink_log_critical(mavlink_fd, "ERR: RC_%d_MAP >= # CHANS", i+1);
- // /* give system time to flush error message in case there are more */
- // usleep(100000);
- // count++;
- // }
-
- /* sanity checks pass, enable channel */
- if (count) {
- mavlink_log_critical(mavlink_fd, "ERROR: %d config error(s) for RC channel %d.", count, (i + 1));
- usleep(100000);
- rc_ok = false;
- }
- }
+ bool rc_ok = (OK == rc_calibration_check());
/* require RC ok to keep system_ok */
system_ok &= rc_ok;
@@ -263,7 +170,7 @@ system_eval:
led_toggle(leds, LED_BLUE);
/* display and sound error */
- for (int i = 0; i < 150; i++)
+ for (int i = 0; i < 50; i++)
{
led_toggle(leds, LED_BLUE);
led_toggle(leds, LED_AMBER);
diff --git a/src/systemcmds/pwm/pwm.c b/src/systemcmds/pwm/pwm.c
index e150b5a74..c42a36c7f 100644
--- a/src/systemcmds/pwm/pwm.c
+++ b/src/systemcmds/pwm/pwm.c
@@ -180,7 +180,8 @@ pwm_main(int argc, char *argv[])
}
/* iterate remaining arguments */
- unsigned channel = 0;
+ unsigned nchannels = 0;
+ unsigned channel[8] = {0};
while (argc--) {
const char *arg = argv[0];
argv++;
@@ -204,13 +205,15 @@ pwm_main(int argc, char *argv[])
}
unsigned pwm_value = strtol(arg, &ep, 0);
if (*ep == '\0') {
- ret = ioctl(fd, PWM_SERVO_SET(channel), pwm_value);
- if (ret != OK)
- err(1, "PWM_SERVO_SET(%d)", channel);
- channel++;
+ if (nchannels > sizeof(channel) / sizeof(channel[0]))
+ err(1, "too many pwm values (max %d)", sizeof(channel) / sizeof(channel[0]));
+
+ channel[nchannels] = pwm_value;
+ nchannels++;
+
continue;
}
- usage("unrecognised option");
+ usage("unrecognized option");
}
/* print verbose info */
@@ -250,5 +253,38 @@ pwm_main(int argc, char *argv[])
}
fflush(stdout);
}
+
+ /* perform PWM output */
+ if (nchannels) {
+
+ /* Open console directly to grab CTRL-C signal */
+ int console = open("/dev/console", O_NONBLOCK | O_RDONLY | O_NOCTTY);
+ if (!console)
+ err(1, "failed opening console");
+
+ warnx("Press CTRL-C or 'c' to abort.");
+
+ while (1) {
+ for (int i = 0; i < nchannels; i++) {
+ ret = ioctl(fd, PWM_SERVO_SET(i), channel[i]);
+ if (ret != OK)
+ err(1, "PWM_SERVO_SET(%d)", i);
+ }
+
+ /* abort on user request */
+ char c;
+ if (read(console, &c, 1) == 1) {
+ if (c == 0x03 || c == 0x63 || c == 'q') {
+ warnx("User abort\n");
+ close(console);
+ exit(0);
+ }
+ }
+
+ /* rate limit to ~ 20 Hz */
+ usleep(50000);
+ }
+ }
+
exit(0);
} \ No newline at end of file
diff --git a/src/systemcmds/reboot/reboot.c b/src/systemcmds/reboot/reboot.c
index 47d3cd948..91a2c2eb8 100644
--- a/src/systemcmds/reboot/reboot.c
+++ b/src/systemcmds/reboot/reboot.c
@@ -40,14 +40,31 @@
#include <nuttx/config.h>
#include <unistd.h>
#include <stdio.h>
+#include <getopt.h>
#include <systemlib/systemlib.h>
+#include <systemlib/err.h>
__EXPORT int reboot_main(int argc, char *argv[]);
int reboot_main(int argc, char *argv[])
{
- up_systemreset();
+ int ch;
+ bool to_bootloader = false;
+
+ while ((ch = getopt(argc, argv, "b")) != -1) {
+ switch (ch) {
+ case 'b':
+ to_bootloader = true;
+ break;
+ default:
+ errx(1, "usage: reboot [-b]\n"
+ " -b reboot into the bootloader");
+
+ }
+ }
+
+ systemreset(to_bootloader);
}
diff --git a/src/systemcmds/top/top.c b/src/systemcmds/top/top.c
index 0d064a05e..1ca3fc928 100644
--- a/src/systemcmds/top/top.c
+++ b/src/systemcmds/top/top.c
@@ -107,9 +107,6 @@ top_main(void)
float interval_time_ms_inv = 0.f;
- /* Open console directly to grab CTRL-C signal */
- int console = open("/dev/console", O_NONBLOCK | O_RDONLY | O_NOCTTY);
-
/* clear screen */
printf("\033[2J");
@@ -256,17 +253,24 @@ top_main(void)
interval_start_time = new_time;
/* Sleep 200 ms waiting for user input five times ~ 1s */
- /* XXX use poll ... */
for (int k = 0; k < 5; k++) {
char c;
- if (read(console, &c, 1) == 1) {
+ struct pollfd fds;
+ int ret;
+ fds.fd = 0; /* stdin */
+ fds.events = POLLIN;
+ ret = poll(&fds, 1, 0);
+
+ if (ret > 0) {
+
+ read(0, &c, 1);
+
switch (c) {
case 0x03: // ctrl-c
case 0x1b: // esc
case 'c':
case 'q':
- close(console);
return OK;
/* not reached */
}
@@ -278,7 +282,5 @@ top_main(void)
new_time = hrt_absolute_time();
}
- close(console);
-
return OK;
}