aboutsummaryrefslogtreecommitdiff
path: root/src/systemcmds
diff options
context:
space:
mode:
authormazahner <mazahner@student.ethz.ch>2014-11-10 17:39:04 +0100
committermazahner <mazahner@student.ethz.ch>2014-11-10 17:39:04 +0100
commit6ec08335459457c82158d2df06050bd30fb8cc59 (patch)
tree3d5407b6bc88533eacedb3bebfc9e0c9b23609ea /src/systemcmds
parentd15203de91cc07530809060f949374bb8918daea (diff)
parent4e8e6e653beb21808f532b83c6c6e827103ea379 (diff)
downloadpx4-firmware-6ec08335459457c82158d2df06050bd30fb8cc59.tar.gz
px4-firmware-6ec08335459457c82158d2df06050bd30fb8cc59.tar.bz2
px4-firmware-6ec08335459457c82158d2df06050bd30fb8cc59.zip
Merge branch 'master' of https://github.com/mazahner/Firmware
Diffstat (limited to 'src/systemcmds')
-rw-r--r--src/systemcmds/esc_calib/module.mk2
-rw-r--r--src/systemcmds/motor_test/module.mk41
-rw-r--r--src/systemcmds/motor_test/motor_test.c128
-rw-r--r--src/systemcmds/mtd/24xxxx_mtd.c15
-rw-r--r--src/systemcmds/mtd/module.mk2
-rw-r--r--src/systemcmds/nshterm/module.mk6
-rw-r--r--src/systemcmds/nshterm/nshterm.c4
-rw-r--r--src/systemcmds/pwm/module.mk2
-rw-r--r--src/systemcmds/pwm/pwm.c21
-rw-r--r--src/systemcmds/tests/test_sensors.c2
-rw-r--r--src/systemcmds/tests/tests_main.c2
11 files changed, 217 insertions, 8 deletions
diff --git a/src/systemcmds/esc_calib/module.mk b/src/systemcmds/esc_calib/module.mk
index 990c56768..ce87eb3e2 100644
--- a/src/systemcmds/esc_calib/module.mk
+++ b/src/systemcmds/esc_calib/module.mk
@@ -39,3 +39,5 @@ MODULE_COMMAND = esc_calib
SRCS = esc_calib.c
MODULE_STACKSIZE = 4096
+
+MAXOPTIMIZATION = -Os
diff --git a/src/systemcmds/motor_test/module.mk b/src/systemcmds/motor_test/module.mk
new file mode 100644
index 000000000..eb36d2ded
--- /dev/null
+++ b/src/systemcmds/motor_test/module.mk
@@ -0,0 +1,41 @@
+############################################################################
+#
+# Copyright (c) 2014 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 motor_test tool.
+#
+
+MODULE_COMMAND = motor_test
+SRCS = motor_test.c
+
+MODULE_STACKSIZE = 4096
diff --git a/src/systemcmds/motor_test/motor_test.c b/src/systemcmds/motor_test/motor_test.c
new file mode 100644
index 000000000..079f99674
--- /dev/null
+++ b/src/systemcmds/motor_test/motor_test.c
@@ -0,0 +1,128 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2014 PX4 Development Team. All rights reserved.
+ * Author: Holger Steinhaus <hsteinhaus@gmx.de>
+ *
+ * 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 motor_test.c
+ *
+ * Tool for drive testing
+ */
+
+#include <nuttx/config.h>
+
+#include <stdio.h>
+#include <stdlib.h>
+#include <string.h>
+#include <unistd.h>
+
+#include <arch/board/board.h>
+#include <drivers/drv_hrt.h>
+#include <uORB/topics/test_motor.h>
+
+
+#include "systemlib/systemlib.h"
+#include "systemlib/err.h"
+
+
+__EXPORT int motor_test_main(int argc, char *argv[]);
+static void motor_test(unsigned channel, float value);
+static void usage(const char *reason);
+
+void motor_test(unsigned channel, float value)
+{
+ orb_advert_t _test_motor_pub;
+ struct test_motor_s _test_motor;
+
+ _test_motor.motor_number = channel;
+ _test_motor.timestamp = hrt_absolute_time();
+ _test_motor.value = value;
+
+ if (_test_motor_pub > 0) {
+ /* publish armed state */
+ orb_publish(ORB_ID(test_motor), _test_motor_pub, &_test_motor);
+ } else {
+ /* advertise and publish */
+ _test_motor_pub = orb_advertise(ORB_ID(test_motor), &_test_motor);
+ }
+}
+
+static void usage(const char *reason)
+{
+ if (reason != NULL)
+ warnx("%s", reason);
+
+ errx(1,
+ "usage:\n"
+ "motor_test\n"
+ " -m <channel> Motor to test (0..7)\n"
+ " -p <power> Power (0..100)\n");
+}
+
+int motor_test_main(int argc, char *argv[])
+{
+ unsigned long channel, lval;
+ float value;
+ int ch;
+
+ if (argc != 5) {
+ usage("please specify motor and power");
+ }
+
+ while ((ch = getopt(argc, argv, "m:p:")) != EOF) {
+ switch (ch) {
+
+ case 'm':
+ /* Read in channels supplied as one int and convert to mask: 1234 -> 0xF */
+ channel = strtoul(optarg, NULL, 0);
+ break;
+
+ case 'p':
+ /* Read in custom low value */
+ lval = strtoul(optarg, NULL, 0);
+
+ if (lval > 100)
+ usage("value invalid");
+
+ value = (float)lval/100.f;
+ break;
+ default:
+ usage(NULL);
+ }
+ }
+
+ motor_test(channel, value);
+
+ printf("motor %d set to %.2f\n", channel, value);
+
+ exit(0);
+}
diff --git a/src/systemcmds/mtd/24xxxx_mtd.c b/src/systemcmds/mtd/24xxxx_mtd.c
index 991363797..f85ed8e2d 100644
--- a/src/systemcmds/mtd/24xxxx_mtd.c
+++ b/src/systemcmds/mtd/24xxxx_mtd.c
@@ -80,11 +80,17 @@
/* As a minimum, the size of the AT24 part and its 7-bit I2C address are required. */
#ifndef CONFIG_AT24XX_SIZE
-# warning "Assuming AT24 size 64"
+/* XXX this is a well vetted special case,
+ * do not issue a warning any more
+ * # warning "Assuming AT24 size 64"
+ */
# define CONFIG_AT24XX_SIZE 64
#endif
#ifndef CONFIG_AT24XX_ADDR
-# warning "Assuming AT24 address of 0x50"
+/* XXX this is a well vetted special case,
+ * do not issue a warning any more
+ * # warning "Assuming AT24 address of 0x50"
+ */
# define CONFIG_AT24XX_ADDR 0x50
#endif
@@ -115,7 +121,10 @@
*/
#ifndef CONFIG_AT24XX_MTD_BLOCKSIZE
-# warning "Assuming driver block size is the same as the FLASH page size"
+/* XXX this is a well vetted special case,
+ * do not issue a warning any more
+ * # warning "Assuming driver block size is the same as the FLASH page size"
+ */
# define CONFIG_AT24XX_MTD_BLOCKSIZE AT24XX_PAGESIZE
#endif
diff --git a/src/systemcmds/mtd/module.mk b/src/systemcmds/mtd/module.mk
index b3fceceb5..1bc4f414e 100644
--- a/src/systemcmds/mtd/module.mk
+++ b/src/systemcmds/mtd/module.mk
@@ -4,3 +4,5 @@
MODULE_COMMAND = mtd
SRCS = mtd.c 24xxxx_mtd.c
+
+MAXOPTIMIZATION = -Os
diff --git a/src/systemcmds/nshterm/module.mk b/src/systemcmds/nshterm/module.mk
index e2fa0ff80..a12bc369e 100644
--- a/src/systemcmds/nshterm/module.mk
+++ b/src/systemcmds/nshterm/module.mk
@@ -38,4 +38,8 @@
MODULE_COMMAND = nshterm
SRCS = nshterm.c
-MODULE_STACKSIZE = 1400
+MODULE_STACKSIZE = 1600
+
+MAXOPTIMIZATION = -Os
+
+MODULE_PRIORITY = "SCHED_PRIORITY_DEFAULT-30"
diff --git a/src/systemcmds/nshterm/nshterm.c b/src/systemcmds/nshterm/nshterm.c
index fca1798e6..f06c49552 100644
--- a/src/systemcmds/nshterm/nshterm.c
+++ b/src/systemcmds/nshterm/nshterm.c
@@ -87,7 +87,7 @@ nshterm_main(int argc, char *argv[])
/* 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);
+ warnx("ERR get config %s: %d\n", argv[1], termios_state);
close(fd);
return -1;
}
@@ -96,7 +96,7 @@ nshterm_main(int argc, char *argv[])
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]);
+ warnx("ERR set config %s\n", argv[1]);
close(fd);
return -1;
}
diff --git a/src/systemcmds/pwm/module.mk b/src/systemcmds/pwm/module.mk
index 13a24150f..a51ac8e0c 100644
--- a/src/systemcmds/pwm/module.mk
+++ b/src/systemcmds/pwm/module.mk
@@ -39,3 +39,5 @@ MODULE_COMMAND = pwm
SRCS = pwm.c
MODULE_STACKSIZE = 1800
+
+MAXOPTIMIZATION = -Os
diff --git a/src/systemcmds/pwm/pwm.c b/src/systemcmds/pwm/pwm.c
index c8d698b86..478c2a772 100644
--- a/src/systemcmds/pwm/pwm.c
+++ b/src/systemcmds/pwm/pwm.c
@@ -654,9 +654,28 @@ pwm_main(int argc, char *argv[])
}
}
exit(0);
+ } else if (!strcmp(argv[1], "terminatefail")) {
+
+ if (argc < 3) {
+ errx(1, "arg missing [on|off]");
+ } else {
+
+ if (!strcmp(argv[2], "on")) {
+ /* force failsafe */
+ ret = ioctl(fd, PWM_SERVO_SET_TERMINATION_FAILSAFE, 1);
+ } else {
+ /* force failsafe */
+ ret = ioctl(fd, PWM_SERVO_SET_TERMINATION_FAILSAFE, 0);
+ }
+
+ if (ret != OK) {
+ warnx("FAILED setting termination failsafe %s", argv[2]);
+ }
+ }
+ exit(0);
}
- usage("specify arm|disarm|rate|failsafe|disarmed|min|max|test|info|forcefail");
+ usage("specify arm|disarm|rate|failsafe\n\t\tdisarmed|min|max|test|info|forcefail|terminatefail");
return 0;
}
diff --git a/src/systemcmds/tests/test_sensors.c b/src/systemcmds/tests/test_sensors.c
index a4f17eebd..e005bf9c1 100644
--- a/src/systemcmds/tests/test_sensors.c
+++ b/src/systemcmds/tests/test_sensors.c
@@ -331,7 +331,7 @@ mag(int argc, char *argv[])
float len = sqrtf(buf.x * buf.x + buf.y * buf.y + buf.z * buf.z);
- if (len < 1.0f || len > 3.0f) {
+ if (len < 0.25f || len > 3.0f) {
warnx("MAG scale error!");
return ERROR;
}
diff --git a/src/systemcmds/tests/tests_main.c b/src/systemcmds/tests/tests_main.c
index e3f26924f..0f56704e6 100644
--- a/src/systemcmds/tests/tests_main.c
+++ b/src/systemcmds/tests/tests_main.c
@@ -110,7 +110,9 @@ const struct {
{"conv", test_conv, OPT_NOJIGTEST | OPT_NOALLTEST},
{"mount", test_mount, OPT_NOJIGTEST | OPT_NOALLTEST},
{"mtd", test_mtd, 0},
+#ifndef TESTS_MATHLIB_DISABLE
{"mathlib", test_mathlib, 0},
+#endif
{"help", test_help, OPT_NOALLTEST | OPT_NOHELP | OPT_NOJIGTEST},
{NULL, NULL, 0}
};