diff options
author | Lorenz Meier <lm@inf.ethz.ch> | 2014-07-07 00:05:29 +0200 |
---|---|---|
committer | Lorenz Meier <lm@inf.ethz.ch> | 2014-07-07 00:05:29 +0200 |
commit | 5559e568b6e5502ad51ec96fd531876c1191d641 (patch) | |
tree | bc6356b5bed0481cced4a7d7e7ef99bd225d91a7 /src/systemcmds | |
parent | 863385dbc4243c8ecb19890a0dfce4a0b7ead9d6 (diff) | |
parent | d67089b23f58ac152253f58c5deaebbd57db0362 (diff) | |
download | px4-firmware-safelink.tar.gz px4-firmware-safelink.tar.bz2 px4-firmware-safelink.zip |
Merged master into safelinksafelink
Diffstat (limited to 'src/systemcmds')
38 files changed, 1103 insertions, 177 deletions
diff --git a/src/systemcmds/config/config.c b/src/systemcmds/config/config.c index 476015f3e..4a97d328c 100644 --- a/src/systemcmds/config/config.c +++ b/src/systemcmds/config/config.c @@ -1,8 +1,6 @@ /**************************************************************************** * - * Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved. - * Author: Lorenz Meier <lm@inf.ethz.ch> - * Author: Julian Oes <joes@student.ethz.ch> + * Copyright (c) 2012-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 @@ -94,7 +92,6 @@ do_device(int argc, char *argv[]) } int fd; - int ret; fd = open(argv[0], 0); @@ -104,6 +101,8 @@ do_device(int argc, char *argv[]) } else { + int ret; + if (argc == 2 && !strcmp(argv[1], "block")) { /* disable the device publications */ @@ -121,7 +120,7 @@ do_device(int argc, char *argv[]) errx(ret,"uORB publications could not be unblocked"); } else { - errx("no valid command: %s", argv[1]); + errx(1, "no valid command: %s", argv[1]); } } @@ -132,7 +131,6 @@ static void do_gyro(int argc, char *argv[]) { int fd; - int ret; fd = open(GYRO_DEVICE_PATH, 0); @@ -142,6 +140,8 @@ do_gyro(int argc, char *argv[]) } else { + int ret; + if (argc == 2 && !strcmp(argv[0], "sampling")) { /* set the gyro internal sampling rate up to at least i Hz */ @@ -173,8 +173,13 @@ do_gyro(int argc, char *argv[]) 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); + + if (ret) { + err(1, "failed getting gyro scale"); + } + + warnx("offsets: X: % 9.6f Y: % 9.6f Z: % 9.6f", (double)scale.x_offset, (double)scale.y_offset, (double)scale.z_offset); + warnx("scale: X: % 9.6f Y: % 9.6f Z: % 9.6f", (double)scale.x_scale, (double)scale.y_scale, (double)scale.z_scale); } else { warnx("gyro calibration and self test OK"); } @@ -199,7 +204,6 @@ static void do_mag(int argc, char *argv[]) { int fd; - int ret; fd = open(MAG_DEVICE_PATH, 0); @@ -209,6 +213,8 @@ do_mag(int argc, char *argv[]) } else { + int ret; + if (argc == 2 && !strcmp(argv[0], "sampling")) { /* set the mag internal sampling rate up to at least i Hz */ @@ -240,8 +246,13 @@ do_mag(int argc, char *argv[]) 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); + + if (ret) { + err(ret, "failed getting mag scale"); + } + + warnx("offsets: X: % 9.6f Y: % 9.6f Z: % 9.6f", (double)scale.x_offset, (double)scale.y_offset, (double)scale.z_offset); + warnx("scale: X: % 9.6f Y: % 9.6f Z: % 9.6f", (double)scale.x_scale, (double)scale.y_scale, (double)scale.z_scale); } else { warnx("mag calibration and self test OK"); } @@ -266,7 +277,6 @@ static void do_accel(int argc, char *argv[]) { int fd; - int ret; fd = open(ACCEL_DEVICE_PATH, 0); @@ -276,6 +286,8 @@ do_accel(int argc, char *argv[]) } else { + int ret; + if (argc == 2 && !strcmp(argv[0], "sampling")) { /* set the accel internal sampling rate up to at least i Hz */ @@ -307,8 +319,13 @@ do_accel(int argc, char *argv[]) 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); + + if (ret) { + err(ret, "failed getting accel scale"); + } + + warnx("offsets: X: % 9.6f Y: % 9.6f Z: % 9.6f", (double)scale.x_offset, (double)scale.y_offset, (double)scale.z_offset); + warnx("scale: X: % 9.6f Y: % 9.6f Z: % 9.6f", (double)scale.x_scale, (double)scale.y_scale, (double)scale.z_scale); } else { warnx("accel calibration and self test OK"); } diff --git a/src/systemcmds/hw_ver/hw_ver.c b/src/systemcmds/dumpfile/dumpfile.c index 4b84523cc..c18814342 100644 --- a/src/systemcmds/hw_ver/hw_ver.c +++ b/src/systemcmds/dumpfile/dumpfile.c @@ -32,42 +32,85 @@ ****************************************************************************/ /** - * @file hw_ver.c + * @file dumpfile.c * - * Show and test hardware version. + * Dump file utility. Prints file size and contents in binary mode (don't replace LF with CR LF) to stdout. + * + * @author Anton Babushkin <anton.babushkin@me.com> */ #include <nuttx/config.h> - +#include <unistd.h> #include <stdio.h> #include <string.h> -#include <errno.h> -#include <version/version.h> +#include <stdlib.h> +#include <fcntl.h> +#include <termios.h> + +#include <systemlib/err.h> -__EXPORT int hw_ver_main(int argc, char *argv[]); +__EXPORT int dumpfile_main(int argc, char *argv[]); int -hw_ver_main(int argc, char *argv[]) +dumpfile_main(int argc, char *argv[]) { - if (argc >= 2) { - if (!strcmp(argv[1], "show")) { - printf(HW_ARCH "\n"); - exit(0); - } + if (argc < 2) { + errx(1, "usage: dumpfile <filename>"); + } + + /* open input file */ + FILE *f; + f = fopen(argv[1], "r"); + + if (f == NULL) { + printf("ERROR\n"); + exit(1); + } + + /* get file size */ + fseek(f, 0L, SEEK_END); + int size = ftell(f); + fseek(f, 0L, SEEK_SET); + + printf("OK %d\n", size); - if (!strcmp(argv[1], "compare")) { - if (argc >= 3) { - int ret = strcmp(HW_ARCH, argv[2]) != 0; - if (ret == 0) { - printf("hw_ver match: %s\n", HW_ARCH); - } - exit(ret); - - } else { - errx(1, "not enough arguments, try 'compare PX4FMU_1'"); - } + /* configure stdout */ + int out = fileno(stdout); + + struct termios tc; + struct termios tc_old; + tcgetattr(out, &tc); + + /* save old terminal attributes to restore it later on exit */ + memcpy(&tc_old, &tc, sizeof(tc)); + + /* don't add CR on each LF*/ + tc.c_oflag &= ~ONLCR; + + if (tcsetattr(out, TCSANOW, &tc) < 0) { + warnx("ERROR setting stdout attributes"); + exit(1); + } + + char buf[512]; + int nread; + + /* dump file */ + while ((nread = fread(buf, 1, sizeof(buf), f)) > 0) { + if (write(out, buf, nread) <= 0) { + warnx("error dumping file"); + break; } } - errx(1, "expected a command, try 'show' or 'compare'"); + fsync(out); + fclose(f); + + /* restore old terminal attributes */ + if (tcsetattr(out, TCSANOW, &tc_old) < 0) { + warnx("ERROR restoring stdout attributes"); + exit(1); + } + + return OK; } diff --git a/src/systemcmds/hw_ver/module.mk b/src/systemcmds/dumpfile/module.mk index 3cc08b6a1..36461f477 100644 --- a/src/systemcmds/hw_ver/module.mk +++ b/src/systemcmds/dumpfile/module.mk @@ -32,12 +32,10 @@ ############################################################################ # -# Show and test hardware version +# Dump file utility # -MODULE_COMMAND = hw_ver -SRCS = hw_ver.c - -MODULE_STACKSIZE = 1024 +MODULE_COMMAND = dumpfile +SRCS = dumpfile.c MAXOPTIMIZATION = -Os diff --git a/src/systemcmds/esc_calib/esc_calib.c b/src/systemcmds/esc_calib/esc_calib.c index ad1996694..7d80af307 100644 --- a/src/systemcmds/esc_calib/esc_calib.c +++ b/src/systemcmds/esc_calib/esc_calib.c @@ -182,7 +182,7 @@ esc_calib_main(int argc, char *argv[]) if (orb_updated) { errx(1, "ABORTING! Attitude control still active. Please ensure to shut down all controllers:\n" - "\tmultirotor_att_control stop\n" + "\tmc_att_control stop\n" "\tfw_att_control stop\n"); } diff --git a/src/systemcmds/mixer/mixer.cpp b/src/systemcmds/mixer/mixer.cpp index 6da39d371..2f5ed3265 100644 --- a/src/systemcmds/mixer/mixer.cpp +++ b/src/systemcmds/mixer/mixer.cpp @@ -102,7 +102,8 @@ load(const char *devname, const char *fname) if (ioctl(dev, MIXERIOCRESET, 0)) err(1, "can't reset mixers on %s", devname); - load_mixer_file(fname, &buf[0], sizeof(buf)); + if (load_mixer_file(fname, &buf[0], sizeof(buf)) < 0) + err(1, "can't load mixer: %s", fname); /* XXX pass the buffer to the device */ int ret = ioctl(dev, MIXERIOCLOADBUF, (unsigned long)buf); diff --git a/src/systemcmds/mtd/24xxxx_mtd.c b/src/systemcmds/mtd/24xxxx_mtd.c index e34be44e3..72200f418 100644 --- a/src/systemcmds/mtd/24xxxx_mtd.c +++ b/src/systemcmds/mtd/24xxxx_mtd.c @@ -142,12 +142,9 @@ struct at24c_dev_s { uint16_t pagesize; /* 32, 63 */ uint16_t npages; /* 128, 256, 512, 1024 */ - perf_counter_t perf_reads; - perf_counter_t perf_writes; - perf_counter_t perf_resets; - perf_counter_t perf_read_retries; - perf_counter_t perf_read_errors; - perf_counter_t perf_write_errors; + perf_counter_t perf_transfers; + perf_counter_t perf_resets_retries; + perf_counter_t perf_errors; }; /************************************************************************************ @@ -240,8 +237,10 @@ void at24c_test(void) } else if (result != 1) { vdbg("unexpected %u\n", result); } - if ((count % 100) == 0) + + if ((count % 100) == 0) { vdbg("test %u errors %u\n", count, errors); + } } } @@ -298,9 +297,9 @@ static ssize_t at24c_bread(FAR struct mtd_dev_s *dev, off_t startblock, for (;;) { - perf_begin(priv->perf_reads); + perf_begin(priv->perf_transfers); ret = I2C_TRANSFER(priv->dev, &msgv[0], 2); - perf_end(priv->perf_reads); + perf_end(priv->perf_transfers); if (ret >= 0) break; @@ -314,10 +313,10 @@ static ssize_t at24c_bread(FAR struct mtd_dev_s *dev, off_t startblock, * XXX maybe do special first-read handling with optional * bus reset as well? */ - perf_count(priv->perf_read_retries); + perf_count(priv->perf_resets_retries); if (--tries == 0) { - perf_count(priv->perf_read_errors); + perf_count(priv->perf_errors); return ERROR; } } @@ -383,9 +382,9 @@ static ssize_t at24c_bwrite(FAR struct mtd_dev_s *dev, off_t startblock, size_t for (;;) { - perf_begin(priv->perf_writes); + perf_begin(priv->perf_transfers); ret = I2C_TRANSFER(priv->dev, &msgv[0], 1); - perf_end(priv->perf_writes); + perf_end(priv->perf_transfers); if (ret >= 0) break; @@ -397,7 +396,7 @@ static ssize_t at24c_bwrite(FAR struct mtd_dev_s *dev, off_t startblock, size_t * poll for write completion. */ if (--tries == 0) { - perf_count(priv->perf_write_errors); + perf_count(priv->perf_errors); return ERROR; } } @@ -521,12 +520,9 @@ FAR struct mtd_dev_s *at24c_initialize(FAR struct i2c_dev_s *dev) { priv->mtd.ioctl = at24c_ioctl; priv->dev = dev; - priv->perf_reads = perf_alloc(PC_ELAPSED, "EEPROM read"); - priv->perf_writes = perf_alloc(PC_ELAPSED, "EEPROM write"); - priv->perf_resets = perf_alloc(PC_COUNT, "EEPROM reset"); - priv->perf_read_retries = perf_alloc(PC_COUNT, "EEPROM read retries"); - priv->perf_read_errors = perf_alloc(PC_COUNT, "EEPROM read errors"); - priv->perf_write_errors = perf_alloc(PC_COUNT, "EEPROM write errors"); + priv->perf_transfers = perf_alloc(PC_ELAPSED, "eeprom_trans"); + priv->perf_resets_retries = perf_alloc(PC_COUNT, "eeprom_rst"); + priv->perf_errors = perf_alloc(PC_COUNT, "eeprom_errs"); } /* attempt to read to validate device is present */ @@ -548,9 +544,9 @@ FAR struct mtd_dev_s *at24c_initialize(FAR struct i2c_dev_s *dev) { } }; - perf_begin(priv->perf_reads); + perf_begin(priv->perf_transfers); int ret = I2C_TRANSFER(priv->dev, &msgv[0], 2); - perf_end(priv->perf_reads); + perf_end(priv->perf_transfers); if (ret < 0) { return NULL; diff --git a/src/systemcmds/mtd/mtd.c b/src/systemcmds/mtd/mtd.c index 0a88d40f3..a925cdd40 100644 --- a/src/systemcmds/mtd/mtd.c +++ b/src/systemcmds/mtd/mtd.c @@ -91,7 +91,7 @@ static void mtd_test(void); static void mtd_erase(char *partition_names[], unsigned n_partitions); static void mtd_readtest(char *partition_names[], unsigned n_partitions); static void mtd_rwtest(char *partition_names[], unsigned n_partitions); -static void mtd_print_info(); +static void mtd_print_info(void); static int mtd_get_geometry(unsigned long *blocksize, unsigned long *erasesize, unsigned long *neraseblocks, unsigned *blkpererase, unsigned *nblocks, unsigned *partsize, unsigned n_partitions); @@ -104,6 +104,16 @@ static unsigned n_partitions_current = 0; static char *partition_names_default[] = {"/fs/mtd_params", "/fs/mtd_waypoints"}; static const int n_partitions_default = sizeof(partition_names_default) / sizeof(partition_names_default[0]); +static void +mtd_status(void) +{ + if (!attached) + errx(1, "MTD driver not started"); + + mtd_print_info(); + exit(0); +} + int mtd_main(int argc, char *argv[]) { if (argc >= 2) { @@ -160,7 +170,11 @@ static void ramtron_attach(void) { /* find the right spi */ +#ifdef CONFIG_ARCH_BOARD_AEROCORE + struct spi_dev_s *spi = up_spiinitialize(4); +#else struct spi_dev_s *spi = up_spiinitialize(2); +#endif /* this resets the spi bus, set correct bus speed again */ SPI_SETFREQUENCY(spi, 10 * 1000 * 1000); SPI_SETBITS(spi, 8); @@ -189,8 +203,12 @@ ramtron_attach(void) errx(1, "failed to initialize mtd driver"); int ret = mtd_dev->ioctl(mtd_dev, MTDIOC_SETSPEED, (unsigned long)10*1000*1000); - if (ret != OK) - warnx(1, "failed to set bus speed"); + if (ret != OK) { + // FIXME: From the previous warnx call, it looked like this should have been an errx instead. Tried + // that but setting the bug speed does fail all the time. Which was then exiting and the board would + // not run correctly. So changed to warnx. + warnx("failed to set bus speed"); + } attached = true; } @@ -347,7 +365,7 @@ static ssize_t mtd_get_partition_size(void) return partsize; } -void mtd_print_info() +void mtd_print_info(void) { if (!attached) exit(1); @@ -378,16 +396,6 @@ mtd_test(void) } void -mtd_status(void) -{ - if (!attached) - errx(1, "MTD driver not started"); - - mtd_print_info(); - exit(0); -} - -void mtd_erase(char *partition_names[], unsigned n_partitions) { uint8_t v[64]; @@ -420,7 +428,7 @@ mtd_readtest(char *partition_names[], unsigned n_partitions) uint8_t v[128]; for (uint8_t i = 0; i < n_partitions; i++) { - uint32_t count = 0; + ssize_t count = 0; printf("reading %s expecting %u bytes\n", partition_names[i], expected_size); int fd = open(partition_names[i], O_RDONLY); if (fd == -1) { @@ -451,8 +459,8 @@ mtd_rwtest(char *partition_names[], unsigned n_partitions) uint8_t v[128], v2[128]; for (uint8_t i = 0; i < n_partitions; i++) { - uint32_t count = 0; - off_t offset = 0; + ssize_t count = 0; + off_t offset = 0; printf("rwtest %s testing %u bytes\n", partition_names[i], expected_size); int fd = open(partition_names[i], O_RDWR); if (fd == -1) { diff --git a/src/systemcmds/nshterm/module.mk b/src/systemcmds/nshterm/module.mk index a48588535..b22b446da 100644 --- a/src/systemcmds/nshterm/module.mk +++ b/src/systemcmds/nshterm/module.mk @@ -38,4 +38,4 @@ MODULE_COMMAND = nshterm SRCS = nshterm.c -MODULE_STACKSIZE = 3000 +MODULE_STACKSIZE = 1200 diff --git a/src/systemcmds/nshterm/nshterm.c b/src/systemcmds/nshterm/nshterm.c index 7d9484d3e..fca1798e6 100644 --- a/src/systemcmds/nshterm/nshterm.c +++ b/src/systemcmds/nshterm/nshterm.c @@ -60,7 +60,7 @@ nshterm_main(int argc, char *argv[]) printf("Usage: nshterm <device>\n"); exit(1); } - uint8_t retries = 0; + unsigned retries = 0; int fd = -1; /* try the first 30 seconds */ diff --git a/src/systemcmds/param/module.mk b/src/systemcmds/param/module.mk index 63f15ad28..f716eb71e 100644 --- a/src/systemcmds/param/module.mk +++ b/src/systemcmds/param/module.mk @@ -38,7 +38,8 @@ MODULE_COMMAND = param SRCS = param.c -MODULE_STACKSIZE = 4096 +# Note: measurements yielded a max of 900 bytes used. +MODULE_STACKSIZE = 1800 MAXOPTIMIZATION = -Os diff --git a/src/systemcmds/param/param.c b/src/systemcmds/param/param.c index 0cbba0a37..235ab7186 100644 --- a/src/systemcmds/param/param.c +++ b/src/systemcmds/param/param.c @@ -46,6 +46,7 @@ #include <stdbool.h> #include <unistd.h> #include <fcntl.h> +#include <math.h> #include <sys/stat.h> #include <arch/board/board.h> @@ -61,8 +62,10 @@ static void do_load(const char* param_file_name); static void do_import(const char* param_file_name); static void do_show(const char* search_string); static void do_show_print(void *arg, param_t param); -static void do_set(const char* name, const char* val); +static void do_set(const char* name, const char* val, bool fail_on_not_found); static void do_compare(const char* name, const char* vals[], unsigned comparisons); +static void do_reset(void); +static void do_reset_nostart(void); int param_main(int argc, char *argv[]) @@ -116,10 +119,17 @@ param_main(int argc, char *argv[]) } if (!strcmp(argv[1], "set")) { - if (argc >= 4) { - do_set(argv[2], argv[3]); + if (argc >= 5) { + + /* if the fail switch is provided, fails the command if not found */ + bool fail = !strcmp(argv[4], "fail"); + + do_set(argv[2], argv[3], fail); + + } else if (argc >= 4) { + do_set(argv[2], argv[3], false); } else { - errx(1, "not enough arguments.\nTry 'param set PARAM_NAME 3'"); + errx(1, "not enough arguments.\nTry 'param set PARAM_NAME 3 [fail]'"); } } @@ -130,6 +140,14 @@ param_main(int argc, char *argv[]) errx(1, "not enough arguments.\nTry 'param compare PARAM_NAME 3'"); } } + + if (!strcmp(argv[1], "reset")) { + do_reset(); + } + + if (!strcmp(argv[1], "reset_nostart")) { + do_reset_nostart(); + } } errx(1, "expected a command, try 'load', 'import', 'show', 'set', 'compare', 'select' or 'save'"); @@ -211,8 +229,8 @@ do_show_print(void *arg, param_t param) if (!(arg == NULL)) { /* start search */ - char *ss = search_string; - char *pp = p_name; + const char *ss = search_string; + const char *pp = p_name; bool mismatch = false; /* XXX this comparison is only ok for trailing wildcards */ @@ -277,7 +295,7 @@ do_show_print(void *arg, param_t param) } static void -do_set(const char* name, const char* val) +do_set(const char* name, const char* val, bool fail_on_not_found) { int32_t i; float f; @@ -285,8 +303,8 @@ do_set(const char* name, const char* val) /* set nothing if parameter cannot be found */ if (param == PARAM_INVALID) { - /* param not found */ - errx(1, "Error: Parameter %s not found.", name); + /* param not found - fail silenty in scripts as it prevents booting */ + errx(((fail_on_not_found) ? 1 : 0), "Error: Parameter %s not found.", name); } printf("%c %s: ", @@ -402,3 +420,39 @@ do_compare(const char* name, const char* vals[], unsigned comparisons) exit(ret); } + +static void +do_reset(void) +{ + param_reset_all(); + + if (param_save_default()) { + warnx("Param export failed."); + exit(1); + } else { + exit(0); + } +} + +static void +do_reset_nostart(void) +{ + + int32_t autostart; + int32_t autoconfig; + + (void)param_get(param_find("SYS_AUTOSTART"), &autostart); + (void)param_get(param_find("SYS_AUTOCONFIG"), &autoconfig); + + param_reset_all(); + + (void)param_set(param_find("SYS_AUTOSTART"), &autostart); + (void)param_set(param_find("SYS_AUTOCONFIG"), &autoconfig); + + if (param_save_default()) { + warnx("Param export failed."); + exit(1); + } else { + exit(0); + } +} diff --git a/src/systemcmds/perf/module.mk b/src/systemcmds/perf/module.mk index 77952842b..ec39a7a85 100644 --- a/src/systemcmds/perf/module.mk +++ b/src/systemcmds/perf/module.mk @@ -39,3 +39,5 @@ MODULE_COMMAND = perf SRCS = perf.c MAXOPTIMIZATION = -Os + +MODULE_STACKSIZE = 1800 diff --git a/src/systemcmds/perf/perf.c b/src/systemcmds/perf/perf.c index b69ea597b..b08a2e3b7 100644 --- a/src/systemcmds/perf/perf.c +++ b/src/systemcmds/perf/perf.c @@ -73,7 +73,7 @@ int perf_main(int argc, char *argv[]) return -1; } - perf_print_all(); + perf_print_all(0 /* stdout */); fflush(stdout); return 0; } diff --git a/src/systemcmds/preflight_check/module.mk b/src/systemcmds/preflight_check/module.mk index 7c3c88783..0cb2a4cd0 100644 --- a/src/systemcmds/preflight_check/module.mk +++ b/src/systemcmds/preflight_check/module.mk @@ -40,3 +40,5 @@ MODULE_COMMAND = preflight_check SRCS = preflight_check.c MAXOPTIMIZATION = -Os + +MODULE_STACKSIZE = 1800 diff --git a/src/systemcmds/preflight_check/preflight_check.c b/src/systemcmds/preflight_check/preflight_check.c index 982b03782..86e4ff545 100644 --- a/src/systemcmds/preflight_check/preflight_check.c +++ b/src/systemcmds/preflight_check/preflight_check.c @@ -44,6 +44,7 @@ #include <string.h> #include <fcntl.h> #include <errno.h> +#include <math.h> #include <systemlib/err.h> #include <systemlib/param/param.h> @@ -87,9 +88,7 @@ int preflight_check_main(int argc, char *argv[]) /* give the system some time to sample the sensors in the background */ usleep(150000); - /* ---- MAG ---- */ - close(fd); fd = open(MAG_DEVICE_PATH, 0); if (fd < 0) { warn("failed to open magnetometer - start with 'hmc5883 start' or 'lsm303d start'"); diff --git a/src/systemcmds/pwm/module.mk b/src/systemcmds/pwm/module.mk index 4a23bba90..13a24150f 100644 --- a/src/systemcmds/pwm/module.mk +++ b/src/systemcmds/pwm/module.mk @@ -38,4 +38,4 @@ MODULE_COMMAND = pwm SRCS = pwm.c -MODULE_STACKSIZE = 4096 +MODULE_STACKSIZE = 1800 diff --git a/src/systemcmds/pwm/pwm.c b/src/systemcmds/pwm/pwm.c index 7c23f38c2..e0e6ca537 100644 --- a/src/systemcmds/pwm/pwm.c +++ b/src/systemcmds/pwm/pwm.c @@ -1,6 +1,6 @@ /**************************************************************************** * - * Copyright (C) 2013 PX4 Development Team. All rights reserved. + * Copyright (c) 2013, 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 @@ -443,6 +443,111 @@ pwm_main(int argc, char *argv[]) exit(0); } } + usleep(2000); + } + exit(0); + + + } else if (!strcmp(argv[1], "steps")) { + + if (set_mask == 0) { + usage("no channels set"); + } + + /* get current servo values */ + struct pwm_output_values last_spos; + + for (unsigned i = 0; i < servo_count; i++) { + + ret = ioctl(fd, PWM_SERVO_GET(i), (unsigned long)&last_spos.values[i]); + if (ret != OK) + err(1, "PWM_SERVO_GET(%d)", i); + } + + /* perform PWM output */ + + /* Open console directly to grab CTRL-C signal */ + struct pollfd fds; + fds.fd = 0; /* stdin */ + fds.events = POLLIN; + + warnx("Running 5 steps. WARNING! Motors will be live in 5 seconds\nPress any key to abort now."); + sleep(5); + + unsigned off = 900; + unsigned idle = 1300; + unsigned full = 2000; + unsigned steps_timings_us[] = {2000, 5000, 20000, 50000}; + + unsigned phase = 0; + unsigned phase_counter = 0; + unsigned const phase_maxcount = 20; + + for ( unsigned steps_timing_index = 0; + steps_timing_index < sizeof(steps_timings_us) / sizeof(steps_timings_us[0]); + steps_timing_index++ ) { + + warnx("Sending step input with 0 to 100%% over a %u microseconds ramp", steps_timings_us[steps_timing_index]); + + while (1) { + for (unsigned i = 0; i < servo_count; i++) { + if (set_mask & 1<<i) { + + unsigned val; + + if (phase == 0) { + val = idle; + } else if (phase == 1) { + /* ramp - depending how steep it is this ramp will look instantaneous on the output */ + val = idle + (full - idle) * (phase_maxcount / (float)phase_counter); + } else { + val = off; + } + + ret = ioctl(fd, PWM_SERVO_SET(i), val); + if (ret != OK) + err(1, "PWM_SERVO_SET(%d)", i); + } + } + + /* abort on user request */ + char c; + ret = poll(&fds, 1, 0); + if (ret > 0) { + + ret = read(0, &c, 1); + + if (ret > 0) { + /* reset output to the last value */ + for (unsigned i = 0; i < servo_count; i++) { + if (set_mask & 1<<i) { + ret = ioctl(fd, PWM_SERVO_SET(i), last_spos.values[i]); + if (ret != OK) + err(1, "PWM_SERVO_SET(%d)", i); + } + } + warnx("Key pressed, user abort\n"); + exit(0); + } + } + if (phase == 1) { + usleep(steps_timings_us[steps_timing_index] / phase_maxcount); + + } else if (phase == 0) { + usleep(50000); + } else if (phase == 2) { + usleep(50000); + } else { + break; + } + + phase_counter++; + + if (phase_counter > phase_maxcount) { + phase++; + phase_counter = 0; + } + } } exit(0); diff --git a/src/systemcmds/reboot/module.mk b/src/systemcmds/reboot/module.mk index 19f64af54..edf9d8b37 100644 --- a/src/systemcmds/reboot/module.mk +++ b/src/systemcmds/reboot/module.mk @@ -39,3 +39,5 @@ MODULE_COMMAND = reboot SRCS = reboot.c MAXOPTIMIZATION = -Os + +MODULE_STACKSIZE = 800 diff --git a/src/systemcmds/tests/module.mk b/src/systemcmds/tests/module.mk index beb9ad13d..622a0faf3 100644 --- a/src/systemcmds/tests/module.mk +++ b/src/systemcmds/tests/module.mk @@ -24,7 +24,9 @@ SRCS = test_adc.c \ test_uart_loopback.c \ test_uart_send.c \ test_mixer.cpp \ + test_mathlib.cpp \ test_file.c \ + test_file2.c \ tests_main.c \ test_param.c \ test_ppm_loopback.c \ diff --git a/src/systemcmds/tests/test_adc.c b/src/systemcmds/tests/test_adc.c index 030ac6e23..03391b851 100644 --- a/src/systemcmds/tests/test_adc.c +++ b/src/systemcmds/tests/test_adc.c @@ -66,8 +66,8 @@ int test_adc(int argc, char *argv[]) } for (unsigned i = 0; i < 5; i++) { - /* make space for a maximum of eight channels */ - struct adc_msg_s data[8]; + /* make space for a maximum of twelve channels */ + struct adc_msg_s data[12]; /* read all channels available */ ssize_t count = read(fd, data, sizeof(data)); diff --git a/src/systemcmds/tests/test_conv.cpp b/src/systemcmds/tests/test_conv.cpp index 50dece816..fda949c61 100644 --- a/src/systemcmds/tests/test_conv.cpp +++ b/src/systemcmds/tests/test_conv.cpp @@ -65,7 +65,7 @@ int test_conv(int argc, char *argv[]) float f = i/10000.0f; float fres = REG_TO_FLOAT(FLOAT_TO_REG(f)); if (fabsf(f - fres) > 0.0001f) { - warnx("conversion fail: input: %8.4f, intermediate: %d, result: %8.4f", f, REG_TO_SIGNED(FLOAT_TO_REG(f)), fres); + warnx("conversion fail: input: %8.4f, intermediate: %d, result: %8.4f", (double)f, REG_TO_SIGNED(FLOAT_TO_REG(f)), (double)fres); return 1; } } diff --git a/src/systemcmds/tests/test_dataman.c b/src/systemcmds/tests/test_dataman.c new file mode 100644 index 000000000..1f844a97d --- /dev/null +++ b/src/systemcmds/tests/test_dataman.c @@ -0,0 +1,182 @@ +/**************************************************************************** + * px4/sensors/test_dataman.c + * + * 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 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 <nuttx/config.h> + +#include <sys/types.h> + +#include <stdio.h> +#include <stdlib.h> +#include <unistd.h> +#include <fcntl.h> +#include <errno.h> +#include <debug.h> + +#include <arch/board/board.h> + +#include <drivers/drv_led.h> +#include <systemlib/systemlib.h> +#include <drivers/drv_hrt.h> +#include <semaphore.h> + + +#include "tests.h" + +#include "dataman/dataman.h" + +static sem_t *sems; + +static int +task_main(int argc, char *argv[]) +{ + char buffer[DM_MAX_DATA_SIZE]; + hrt_abstime wstart, wend, rstart, rend; + + warnx("Starting dataman test task %s", argv[1]); + /* try to read an invalid item */ + int my_id = atoi(argv[1]); + /* try to read an invalid item */ + if (dm_read(DM_KEY_NUM_KEYS, 0, buffer, sizeof(buffer)) >= 0) { + warnx("%d read an invalid item failed", my_id); + goto fail; + } + /* try to read an invalid index */ + if (dm_read(DM_KEY_SAFE_POINTS, DM_KEY_SAFE_POINTS_MAX, buffer, sizeof(buffer)) >= 0) { + warnx("%d read an invalid index failed", my_id); + goto fail; + } + srand(hrt_absolute_time() ^ my_id); + unsigned hit = 0, miss = 0; + wstart = hrt_absolute_time(); + for (unsigned i = 0; i < NUM_MISSIONS_SUPPORTED; i++) { + memset(buffer, my_id, sizeof(buffer)); + buffer[1] = i; + unsigned hash = i ^ my_id; + unsigned len = (hash & 63) + 2; + + int ret = dm_write(DM_KEY_WAYPOINTS_OFFBOARD_1, hash, DM_PERSIST_IN_FLIGHT_RESET, buffer, len); + warnx("ret: %d", ret); + if (ret != len) { + warnx("%d write failed, index %d, length %d", my_id, hash, len); + goto fail; + } + usleep(rand() & ((64 * 1024) - 1)); + } + rstart = hrt_absolute_time(); + wend = rstart; + + for (unsigned i = 0; i < NUM_MISSIONS_SUPPORTED; i++) { + unsigned hash = i ^ my_id; + unsigned len2, len = (hash & 63) + 2; + if ((len2 = dm_read(DM_KEY_WAYPOINTS_OFFBOARD_1, hash, buffer, sizeof(buffer))) < 2) { + warnx("%d read failed length test, index %d", my_id, hash); + goto fail; + } + if (buffer[0] == my_id) { + hit++; + if (len2 != len) { + warnx("%d read failed length test, index %d, wanted %d, got %d", my_id, hash, len, len2); + goto fail; + } + if (buffer[1] != i) { + warnx("%d data verification failed, index %d, wanted %d, got %d", my_id, hash, my_id, buffer[1]); + goto fail; + } + } + else + miss++; + } + rend = hrt_absolute_time(); + warnx("Test %d pass, hit %d, miss %d, io time read %llums. write %llums.", + my_id, hit, miss, (rend - rstart) / NUM_MISSIONS_SUPPORTED / 1000, (wend - wstart) / NUM_MISSIONS_SUPPORTED / 1000); + sem_post(sems + my_id); + return 0; +fail: + warnx("Test %d fail, buffer %02x %02x %02x %02x %02x %02x", + my_id, buffer[0], buffer[1], buffer[2], buffer[3], buffer[4], buffer[5]); + sem_post(sems + my_id); + return -1; +} + +int test_dataman(int argc, char *argv[]) +{ + int i, num_tasks = 4; + char buffer[DM_MAX_DATA_SIZE]; + + if (argc > 1) + num_tasks = atoi(argv[1]); + + sems = (sem_t *)malloc(num_tasks * sizeof(sem_t)); + warnx("Running %d tasks", num_tasks); + for (i = 0; i < num_tasks; i++) { + int task; + char a[16]; + sprintf(a, "%d", i); + const char *av[2]; + av[0] = a; + av[1] = 0; + sem_init(sems + i, 1, 0); + /* start the task */ + if ((task = task_spawn_cmd("dataman", SCHED_DEFAULT, SCHED_PRIORITY_MAX - 5, 2048, task_main, av)) <= 0) { + warn("task start failed"); + } + } + for (i = 0; i < num_tasks; i++) { + sem_wait(sems + i); + sem_destroy(sems + i); + } + free(sems); + dm_restart(DM_INIT_REASON_IN_FLIGHT); + for (i = 0; i < NUM_MISSIONS_SUPPORTED; i++) { + if (dm_read(DM_KEY_WAYPOINTS_OFFBOARD_1, i, buffer, sizeof(buffer)) != 0) + break; + } + if (i >= NUM_MISSIONS_SUPPORTED) { + warnx("Restart in-flight failed"); + return -1; + + } + dm_restart(DM_INIT_REASON_POWER_ON); + for (i = 0; i < NUM_MISSIONS_SUPPORTED; i++) { + if (dm_read(DM_KEY_WAYPOINTS_OFFBOARD_1, i, buffer, sizeof(buffer)) != 0) { + warnx("Restart power-on failed"); + return -1; + } + } + return 0; +} diff --git a/src/systemcmds/tests/test_file.c b/src/systemcmds/tests/test_file.c index 96be1e8df..570583dee 100644 --- a/src/systemcmds/tests/test_file.c +++ b/src/systemcmds/tests/test_file.c @@ -102,7 +102,7 @@ test_file(int argc, char *argv[]) } /* perform tests for a range of chunk sizes */ - unsigned chunk_sizes[] = {1, 5, 8, 13, 16, 32, 33, 64, 70, 128, 133, 256, 300, 512, 555, 1024, 1500}; + int chunk_sizes[] = {1, 5, 8, 13, 16, 32, 33, 64, 70, 128, 133, 256, 300, 512, 555, 1024, 1500}; for (unsigned c = 0; c < (sizeof(chunk_sizes) / sizeof(chunk_sizes[0])); c++) { @@ -116,7 +116,7 @@ test_file(int argc, char *argv[]) uint8_t write_buf[chunk_sizes[c] + alignments] __attribute__((aligned(64))); /* fill write buffer with known values */ - for (int i = 0; i < sizeof(write_buf); i++) { + for (size_t i = 0; i < sizeof(write_buf); i++) { /* this will wrap, but we just need a known value with spacing */ write_buf[i] = i+11; } @@ -149,6 +149,8 @@ test_file(int argc, char *argv[]) } end = hrt_absolute_time(); + warnx("write took %llu us", (end - start)); + close(fd); fd = open("/fs/microsd/testfile", O_RDONLY); @@ -192,7 +194,6 @@ test_file(int argc, char *argv[]) warnx("testing aligned writes - please wait.. (CTRL^C to abort)"); - start = hrt_absolute_time(); for (unsigned i = 0; i < iterations; i++) { int wret = write(fd, write_buf, chunk_sizes[c]); @@ -224,9 +225,6 @@ test_file(int argc, char *argv[]) return 1; } - /* compare value */ - bool compare_ok = true; - for (int j = 0; j < chunk_sizes[c]; j++) { if (read_buf[j] != write_buf[j]) { warnx("COMPARISON ERROR: byte %d: %u != %u", j, (unsigned int)read_buf[j], (unsigned int)write_buf[j]); diff --git a/src/systemcmds/tests/test_file2.c b/src/systemcmds/tests/test_file2.c new file mode 100644 index 000000000..8db3ea5ae --- /dev/null +++ b/src/systemcmds/tests/test_file2.c @@ -0,0 +1,198 @@ +/**************************************************************************** + * + * 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. + * + ****************************************************************************/ + +/** + * @file test_file2.c + * + * File write test. + */ + +#include <sys/stat.h> +#include <dirent.h> +#include <stdio.h> +#include <stddef.h> +#include <unistd.h> +#include <fcntl.h> +#include <systemlib/err.h> +#include <systemlib/perf_counter.h> +#include <string.h> +#include <stdlib.h> +#include <getopt.h> + +#include "tests.h" + +#define FLAG_FSYNC 1 +#define FLAG_LSEEK 2 + +/* + return a predictable value for any file offset to allow detection of corruption + */ +static uint8_t get_value(uint32_t ofs) +{ + union { + uint32_t ofs; + uint8_t buf[4]; + } u; + u.ofs = ofs; + return u.buf[ofs % 4]; +} + +static void test_corruption(const char *filename, uint32_t write_chunk, uint32_t write_size, uint16_t flags) +{ + printf("Testing on %s with write_chunk=%u write_size=%u\n", + filename, (unsigned)write_chunk, (unsigned)write_size); + + uint32_t ofs = 0; + int fd = open(filename, O_CREAT | O_RDWR | O_TRUNC); + if (fd == -1) { + perror(filename); + exit(1); + } + + // create a file of size write_size, in write_chunk blocks + uint8_t counter = 0; + while (ofs < write_size) { + uint8_t buffer[write_chunk]; + for (uint16_t j=0; j<write_chunk; j++) { + buffer[j] = get_value(ofs); + ofs++; + } + if (write(fd, buffer, sizeof(buffer)) != (int)sizeof(buffer)) { + printf("write failed at offset %u\n", ofs); + exit(1); + } + if (flags & FLAG_FSYNC) { + fsync(fd); + } + if (counter % 100 == 0) { + printf("write ofs=%u\r", ofs); + } + counter++; + } + close(fd); + + printf("write ofs=%u\n", ofs); + + // read and check + fd = open(filename, O_RDONLY); + if (fd == -1) { + perror(filename); + exit(1); + } + + counter = 0; + ofs = 0; + while (ofs < write_size) { + uint8_t buffer[write_chunk]; + if (counter % 100 == 0) { + printf("read ofs=%u\r", ofs); + } + counter++; + if (read(fd, buffer, sizeof(buffer)) != (int)sizeof(buffer)) { + printf("read failed at offset %u\n", ofs); + exit(1); + } + for (uint16_t j=0; j<write_chunk; j++) { + if (buffer[j] != get_value(ofs)) { + printf("corruption at ofs=%u got %u\n", ofs, buffer[j]); + exit(1); + } + ofs++; + } + if (flags & FLAG_LSEEK) { + lseek(fd, 0, SEEK_CUR); + } + } + printf("read ofs=%u\n", ofs); + close(fd); + unlink(filename); + printf("All OK\n"); +} + +static void usage(void) +{ + printf("test file2 [options] [filename]\n"); + printf("\toptions:\n"); + printf("\t-s SIZE set file size\n"); + printf("\t-c CHUNK set IO chunk size\n"); + printf("\t-F fsync on every write\n"); + printf("\t-L lseek on every read\n"); +} + +int test_file2(int argc, char *argv[]) +{ + int opt; + uint16_t flags = 0; + const char *filename = "/fs/microsd/testfile2.dat"; + uint32_t write_chunk = 64; + uint32_t write_size = 5*1024; + + while ((opt = getopt(argc, argv, "c:s:FLh")) != EOF) { + switch (opt) { + case 'F': + flags |= FLAG_FSYNC; + break; + case 'L': + flags |= FLAG_LSEEK; + break; + case 's': + write_size = strtoul(optarg, NULL, 0); + break; + case 'c': + write_chunk = strtoul(optarg, NULL, 0); + break; + case 'h': + default: + usage(); + exit(1); + } + } + + argc -= optind; + argv += optind; + + if (argc > 0) { + filename = argv[0]; + } + + /* check if microSD card is mounted */ + struct stat buffer; + if (stat("/fs/microsd/", &buffer)) { + warnx("no microSD card mounted, aborting file test"); + return 1; + } + + test_corruption(filename, write_chunk, write_size, flags); + return 0; +} + diff --git a/src/systemcmds/tests/test_float.c b/src/systemcmds/tests/test_float.c index 4921c9bbb..bb8b6c7f5 100644 --- a/src/systemcmds/tests/test_float.c +++ b/src/systemcmds/tests/test_float.c @@ -68,7 +68,7 @@ int test_float(int argc, char *argv[]) float sinf_one = sinf(1.0f); float sqrt_two = sqrt(2.0f); - if (sinf_zero == 0.0f) { + if (fabsf(sinf_zero) < FLT_EPSILON) { printf("\t success: sinf(0.0f) == 0.0f\n"); } else { @@ -94,7 +94,7 @@ int test_float(int argc, char *argv[]) printf("\t success: asinf(1.0f) == 1.57079f\n"); } else { - printf("\t FAIL: asinf(1.0f) != 1.57079f, result: %f\n", asinf_one); + printf("\t FAIL: asinf(1.0f) != 1.57079f, result: %f\n", (double)asinf_one); ret = -1; } @@ -128,7 +128,7 @@ int test_float(int argc, char *argv[]) float sinf_zero_one = sinf(0.1f); - if (fabs(sinf_zero_one - 0.0998334166f) < FLT_EPSILON) { + if (fabsf(sinf_zero_one - 0.0998334166f) < FLT_EPSILON) { printf("\t success: sinf(0.1f) == 0.09983f\n"); } else { @@ -136,7 +136,7 @@ int test_float(int argc, char *argv[]) ret = -2; } - if (sqrt_two == 1.41421356f) { + if (fabsf(sqrt_two - 1.41421356f) < FLT_EPSILON) { printf("\t success: sqrt(2.0f) == 1.41421f\n"); } else { @@ -155,7 +155,7 @@ int test_float(int argc, char *argv[]) } char sbuf[30]; - sprintf(sbuf, "%8.4f", 0.553415f); + sprintf(sbuf, "%8.4f", (double)0.553415f); if (sbuf[0] == ' ' && sbuf[1] == ' ' && sbuf[2] == '0' && sbuf[3] == '.' && sbuf[4] == '5' && sbuf[5] == '5' @@ -166,7 +166,7 @@ int test_float(int argc, char *argv[]) ret = -5; } - sprintf(sbuf, "%8.4f", -0.553415f); + sprintf(sbuf, "%8.4f", (double)-0.553415f); if (sbuf[0] == ' ' && sbuf[1] == '-' && sbuf[2] == '0' && sbuf[3] == '.' && sbuf[4] == '5' && sbuf[5] == '5' @@ -188,7 +188,7 @@ int test_float(int argc, char *argv[]) double d1d2 = d1 * d2; - if (d1d2 == 2.022200000000000219557705349871) { + if (fabs(d1d2 - 2.022200000000000219557705349871) < DBL_EPSILON) { printf("\t success: 1.0111 * 2.0 == 2.0222\n"); } else { @@ -201,11 +201,11 @@ int test_float(int argc, char *argv[]) // Assign value of f1 to d1 d1 = f1; - if (f1 == (float)d1) { + if (fabsf(f1 - (float)d1) < FLT_EPSILON) { printf("\t success: (float) 1.55f == 1.55 (double)\n"); } else { - printf("\t FAIL: (float) 1.55f != 1.55 (double), result: %8.4f\n", f1); + printf("\t FAIL: (float) 1.55f != 1.55 (double), result: %8.4f\n", (double)f1); ret = -8; } @@ -216,7 +216,7 @@ int test_float(int argc, char *argv[]) double sin_one = sin(1.0); double atan2_ones = atan2(1.0, 1.0); - if (sin_zero == 0.0) { + if (fabs(sin_zero - 0.0) < DBL_EPSILON) { printf("\t success: sin(0.0) == 0.0\n"); } else { @@ -224,7 +224,7 @@ int test_float(int argc, char *argv[]) ret = -9; } - if (sin_one == 0.841470984807896504875657228695) { + if (fabs(sin_one - 0.841470984807896504875657228695) < DBL_EPSILON) { printf("\t success: sin(1.0) == 0.84147098480\n"); } else { @@ -232,7 +232,7 @@ int test_float(int argc, char *argv[]) ret = -10; } - if (atan2_ones != 0.785398) { + if (fabs(atan2_ones - 0.785398) < DBL_EPSILON) { printf("\t success: atan2(1.0, 1.0) == 0.785398\n"); } else { diff --git a/src/systemcmds/tests/test_mathlib.cpp b/src/systemcmds/tests/test_mathlib.cpp new file mode 100644 index 000000000..00c649c75 --- /dev/null +++ b/src/systemcmds/tests/test_mathlib.cpp @@ -0,0 +1,155 @@ +/**************************************************************************** + * + * 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 test_mathlib.cpp + * + * Mathlib test + */ + +#include <stdio.h> +#include <stdlib.h> +#include <unistd.h> +#include <string.h> +#include <time.h> +#include <mathlib/mathlib.h> +#include <systemlib/err.h> +#include <drivers/drv_hrt.h> + +#include "tests.h" + +#define TEST_OP(_title, _op) { unsigned int n = 60000; hrt_abstime t0, t1; t0 = hrt_absolute_time(); for (unsigned int j = 0; j < n; j++) { _op; }; t1 = hrt_absolute_time(); warnx(_title ": %.6fus", (double)(t1 - t0) / n); } + +using namespace math; + +int test_mathlib(int argc, char *argv[]) +{ + warnx("testing mathlib"); + + { + Vector<2> v; + Vector<2> v1(1.0f, 2.0f); + Vector<2> v2(1.0f, -1.0f); + float data[2] = {1.0f, 2.0f}; + TEST_OP("Constructor Vector<2>()", Vector<2> v3); + TEST_OP("Constructor Vector<2>(Vector<2>)", Vector<2> v3(v1)); + TEST_OP("Constructor Vector<2>(float[])", Vector<2> v3(data)); + TEST_OP("Constructor Vector<2>(float, float)", Vector<2> v3(1.0f, 2.0f)); + TEST_OP("Vector<2> = Vector<2>", v = v1); + TEST_OP("Vector<2> + Vector<2>", v + v1); + TEST_OP("Vector<2> - Vector<2>", v - v1); + TEST_OP("Vector<2> += Vector<2>", v += v1); + TEST_OP("Vector<2> -= Vector<2>", v -= v1); + TEST_OP("Vector<2> * Vector<2>", v * v1); + TEST_OP("Vector<2> %% Vector<2>", v1 % v2); + } + + { + Vector<3> v; + Vector<3> v1(1.0f, 2.0f, 0.0f); + Vector<3> v2(1.0f, -1.0f, 2.0f); + float data[3] = {1.0f, 2.0f, 3.0f}; + TEST_OP("Constructor Vector<3>()", Vector<3> v3); + TEST_OP("Constructor Vector<3>(Vector<3>)", Vector<3> v3(v1)); + TEST_OP("Constructor Vector<3>(float[])", Vector<3> v3(data)); + TEST_OP("Constructor Vector<3>(float, float, float)", Vector<3> v3(1.0f, 2.0f, 3.0f)); + TEST_OP("Vector<3> = Vector<3>", v = v1); + TEST_OP("Vector<3> + Vector<3>", v + v1); + TEST_OP("Vector<3> - Vector<3>", v - v1); + TEST_OP("Vector<3> += Vector<3>", v += v1); + TEST_OP("Vector<3> -= Vector<3>", v -= v1); + TEST_OP("Vector<3> * float", v1 * 2.0f); + TEST_OP("Vector<3> / float", v1 / 2.0f); + TEST_OP("Vector<3> *= float", v1 *= 2.0f); + TEST_OP("Vector<3> /= float", v1 /= 2.0f); + TEST_OP("Vector<3> * Vector<3>", v * v1); + TEST_OP("Vector<3> %% Vector<3>", v1 % v2); + TEST_OP("Vector<3> length", v1.length()); + TEST_OP("Vector<3> length squared", v1.length_squared()); + TEST_OP("Vector<3> element read", volatile float a = v1(0)); + TEST_OP("Vector<3> element read direct", volatile float a = v1.data[0]); + TEST_OP("Vector<3> element write", v1(0) = 1.0f); + TEST_OP("Vector<3> element write direct", v1.data[0] = 1.0f); + } + + { + Vector<4> v; + Vector<4> v1(1.0f, 2.0f, 0.0f, -1.0f); + Vector<4> v2(1.0f, -1.0f, 2.0f, 0.0f); + float data[4] = {1.0f, 2.0f, 3.0f, 4.0f}; + TEST_OP("Constructor Vector<4>()", Vector<4> v3); + TEST_OP("Constructor Vector<4>(Vector<4>)", Vector<4> v3(v1)); + TEST_OP("Constructor Vector<4>(float[])", Vector<4> v3(data)); + TEST_OP("Constructor Vector<4>(float, float, float, float)", Vector<4> v3(1.0f, 2.0f, 3.0f, 4.0f)); + TEST_OP("Vector<4> = Vector<4>", v = v1); + TEST_OP("Vector<4> + Vector<4>", v + v1); + TEST_OP("Vector<4> - Vector<4>", v - v1); + TEST_OP("Vector<4> += Vector<4>", v += v1); + TEST_OP("Vector<4> -= Vector<4>", v -= v1); + TEST_OP("Vector<4> * Vector<4>", v * v1); + } + + { + Vector<10> v1; + v1.zero(); + float data[10]; + TEST_OP("Constructor Vector<10>()", Vector<10> v3); + TEST_OP("Constructor Vector<10>(Vector<10>)", Vector<10> v3(v1)); + TEST_OP("Constructor Vector<10>(float[])", Vector<10> v3(data)); + } + + { + Matrix<3, 3> m1; + m1.identity(); + Matrix<3, 3> m2; + m2.identity(); + Vector<3> v1(1.0f, 2.0f, 0.0f); + TEST_OP("Matrix<3, 3> * Vector<3>", m1 * v1); + TEST_OP("Matrix<3, 3> + Matrix<3, 3>", m1 + m2); + TEST_OP("Matrix<3, 3> * Matrix<3, 3>", m1 * m2); + } + + { + Matrix<10, 10> m1; + m1.identity(); + Matrix<10, 10> m2; + m2.identity(); + Vector<10> v1; + v1.zero(); + TEST_OP("Matrix<10, 10> * Vector<10>", m1 * v1); + TEST_OP("Matrix<10, 10> + Matrix<10, 10>", m1 + m2); + TEST_OP("Matrix<10, 10> * Matrix<10, 10>", m1 * m2); + } + + return 0; +} diff --git a/src/systemcmds/tests/test_mixer.cpp b/src/systemcmds/tests/test_mixer.cpp index df382e2c6..8ab8fa2d6 100644 --- a/src/systemcmds/tests/test_mixer.cpp +++ b/src/systemcmds/tests/test_mixer.cpp @@ -81,7 +81,7 @@ int test_mixer(int argc, char *argv[]) warnx("testing mixer"); - char *filename = "/etc/mixers/IO_pass.mix"; + const char *filename = "/etc/mixers/IO_pass.mix"; if (argc > 1) filename = argv[1]; @@ -100,8 +100,6 @@ int test_mixer(int argc, char *argv[]) * e.g. on PX4IO. */ - unsigned nused = 0; - const unsigned chunk_size = 64; MixerGroup mixer_group(mixer_callback, 0); @@ -124,7 +122,6 @@ int test_mixer(int argc, char *argv[]) return 1; /* FIRST mark the mixer as invalid */ - bool mixer_ok = false; /* THEN actually delete it */ mixer_group.reset(); char mixer_text[256]; /* large enough for one mixer */ @@ -140,7 +137,6 @@ int test_mixer(int argc, char *argv[]) /* check for overflow - this would be really fatal */ if ((mixer_text_length + text_length + 1) > sizeof(mixer_text)) { - bool mixer_ok = false; return 1; } @@ -156,15 +152,6 @@ int test_mixer(int argc, char *argv[]) /* if anything was parsed */ if (resid != mixer_text_length) { - - /* only set mixer ok if no residual is left over */ - if (resid == 0) { - mixer_ok = true; - } else { - /* not yet reached the end of the mixer, set as not ok */ - mixer_ok = false; - } - warnx("used %u", mixer_text_length - resid); /* copy any leftover text to the base of the buffer for re-use */ @@ -192,7 +179,7 @@ int test_mixer(int argc, char *argv[]) should_arm = true; /* run through arming phase */ - for (int i = 0; i < output_max; i++) { + for (unsigned i = 0; i < output_max; i++) { actuator_controls[i] = 0.1f; r_page_servo_disarmed[i] = PWM_LOWEST_MIN; r_page_servo_control_min[i] = PWM_DEFAULT_MIN; @@ -213,7 +200,7 @@ int test_mixer(int argc, char *argv[]) pwm_limit_calc(should_arm, mixed, r_page_servo_disarmed, r_page_servo_control_min, r_page_servo_control_max, outputs, r_page_servos, &pwm_limit); //warnx("mixed %d outputs (max %d), values:", mixed, output_max); - for (int i = 0; i < mixed; i++) + for (unsigned i = 0; i < mixed; i++) { /* check mixed outputs to be zero during init phase */ if (hrt_elapsed_time(&starttime) < INIT_TIME_US && @@ -228,7 +215,7 @@ int test_mixer(int argc, char *argv[]) return 1; } - //printf("\t %d: %8.4f limited: %8.4f, servo: %d\n", i, outputs_unlimited[i], outputs[i], (int)r_page_servos[i]); + //printf("\t %d: %8.4f limited: %8.4f, servo: %d\n", i, (double)outputs_unlimited[i], (double)outputs[i], (int)r_page_servos[i]); } usleep(sleep_quantum_us); sleepcount++; @@ -244,7 +231,7 @@ int test_mixer(int argc, char *argv[]) for (int j = -jmax; j <= jmax; j++) { - for (int i = 0; i < output_max; i++) { + for (unsigned i = 0; i < output_max; i++) { actuator_controls[i] = j/10.0f + 0.1f * i; r_page_servo_disarmed[i] = PWM_LOWEST_MIN; r_page_servo_control_min[i] = PWM_DEFAULT_MIN; @@ -257,11 +244,11 @@ int test_mixer(int argc, char *argv[]) pwm_limit_calc(should_arm, mixed, r_page_servo_disarmed, r_page_servo_control_min, r_page_servo_control_max, outputs, r_page_servos, &pwm_limit); warnx("mixed %d outputs (max %d)", mixed, output_max); - for (int i = 0; i < mixed; i++) + for (unsigned i = 0; i < mixed; i++) { servo_predicted[i] = 1500 + outputs[i] * (r_page_servo_control_max[i] - r_page_servo_control_min[i]) / 2.0f; if (fabsf(servo_predicted[i] - r_page_servos[i]) > 2) { - printf("\t %d: %8.4f predicted: %d, servo: %d\n", i, outputs[i], servo_predicted[i], (int)r_page_servos[i]); + printf("\t %d: %8.4f predicted: %d, servo: %d\n", i, (double)outputs[i], servo_predicted[i], (int)r_page_servos[i]); warnx("mixer violated predicted value"); return 1; } @@ -282,7 +269,7 @@ int test_mixer(int argc, char *argv[]) pwm_limit_calc(should_arm, mixed, r_page_servo_disarmed, r_page_servo_control_min, r_page_servo_control_max, outputs, r_page_servos, &pwm_limit); //warnx("mixed %d outputs (max %d), values:", mixed, output_max); - for (int i = 0; i < mixed; i++) + for (unsigned i = 0; i < mixed; i++) { /* check mixed outputs to be zero during init phase */ if (r_page_servos[i] != r_page_servo_disarmed[i]) { @@ -316,7 +303,7 @@ int test_mixer(int argc, char *argv[]) pwm_limit_calc(should_arm, mixed, r_page_servo_disarmed, r_page_servo_control_min, r_page_servo_control_max, outputs, r_page_servos, &pwm_limit); //warnx("mixed %d outputs (max %d), values:", mixed, output_max); - for (int i = 0; i < mixed; i++) + for (unsigned i = 0; i < mixed; i++) { /* predict value */ servo_predicted[i] = 1500 + outputs[i] * (r_page_servo_control_max[i] - r_page_servo_control_min[i]) / 2.0f; @@ -333,7 +320,7 @@ int test_mixer(int argc, char *argv[]) /* check post ramp phase */ if (hrt_elapsed_time(&starttime) > RAMP_TIME_US && fabsf(servo_predicted[i] - r_page_servos[i]) > 2) { - printf("\t %d: %8.4f predicted: %d, servo: %d\n", i, outputs[i], servo_predicted[i], (int)r_page_servos[i]); + printf("\t %d: %8.4f predicted: %d, servo: %d\n", i, (double)outputs[i], servo_predicted[i], (int)r_page_servos[i]); warnx("mixer violated predicted value"); return 1; } @@ -372,6 +359,7 @@ int test_mixer(int argc, char *argv[]) } warnx("SUCCESS: No errors in mixer test"); + return 0; } static int diff --git a/src/systemcmds/tests/test_mount.c b/src/systemcmds/tests/test_mount.c index 44e34d9ef..4b6303cfb 100644 --- a/src/systemcmds/tests/test_mount.c +++ b/src/systemcmds/tests/test_mount.c @@ -141,8 +141,8 @@ test_mount(int argc, char *argv[]) /* announce mode switch */ if (it_left_fsync_prev != it_left_fsync && it_left_fsync == 0) { warnx("\n SUCCESSFULLY PASSED FSYNC'ED WRITES, CONTINUTING WITHOUT FSYNC"); - fsync(stdout); - fsync(stderr); + fsync(fileno(stdout)); + fsync(fileno(stderr)); usleep(20000); } @@ -162,7 +162,7 @@ test_mount(int argc, char *argv[]) } char buf[64]; - int wret = sprintf(buf, "TEST: %d %d ", it_left_fsync, it_left_abort); + (void)sprintf(buf, "TEST: %d %d ", it_left_fsync, it_left_abort); lseek(cmd_fd, 0, SEEK_SET); write(cmd_fd, buf, strlen(buf) + 1); fsync(cmd_fd); @@ -174,8 +174,8 @@ test_mount(int argc, char *argv[]) printf("\n\n====== FILE TEST: %u bytes chunks (%s) ======\n", chunk_sizes[c], (it_left_fsync > 0) ? "FSYNC" : "NO FSYNC"); printf("unpower the system immediately (within 0.5s) when the hash (#) sign appears\n"); - fsync(stdout); - fsync(stderr); + fsync(fileno(stdout)); + fsync(fileno(stderr)); usleep(50000); for (unsigned a = 0; a < alignments; a++) { @@ -185,22 +185,20 @@ test_mount(int argc, char *argv[]) uint8_t write_buf[chunk_sizes[c] + alignments] __attribute__((aligned(64))); /* fill write buffer with known values */ - for (int i = 0; i < sizeof(write_buf); i++) { + for (unsigned i = 0; i < sizeof(write_buf); i++) { /* this will wrap, but we just need a known value with spacing */ write_buf[i] = i+11; } uint8_t read_buf[chunk_sizes[c] + alignments] __attribute__((aligned(64))); - hrt_abstime start, end; int fd = open("/fs/microsd/testfile", O_TRUNC | O_WRONLY | O_CREAT); - start = hrt_absolute_time(); for (unsigned i = 0; i < iterations; i++) { int wret = write(fd, write_buf + a, chunk_sizes[c]); - if (wret != chunk_sizes[c]) { + if (wret != (int)chunk_sizes[c]) { warn("WRITE ERROR!"); if ((0x3 & (uintptr_t)(write_buf + a))) @@ -214,8 +212,8 @@ test_mount(int argc, char *argv[]) fsync(fd); } else { printf("#"); - fsync(stdout); - fsync(stderr); + fsync(fileno(stdout)); + fsync(fileno(stderr)); } } @@ -224,12 +222,10 @@ test_mount(int argc, char *argv[]) } printf("."); - fsync(stdout); - fsync(stderr); + fsync(fileno(stdout)); + fsync(fileno(stderr)); usleep(200000); - end = hrt_absolute_time(); - close(fd); fd = open("/fs/microsd/testfile", O_RDONLY); @@ -237,7 +233,7 @@ test_mount(int argc, char *argv[]) for (unsigned i = 0; i < iterations; i++) { int rret = read(fd, read_buf, chunk_sizes[c]); - if (rret != chunk_sizes[c]) { + if (rret != (int)chunk_sizes[c]) { warnx("READ ERROR!"); return 1; } @@ -245,7 +241,7 @@ test_mount(int argc, char *argv[]) /* compare value */ bool compare_ok = true; - for (int j = 0; j < chunk_sizes[c]; j++) { + for (unsigned j = 0; j < chunk_sizes[c]; j++) { if (read_buf[j] != write_buf[j + a]) { warnx("COMPARISON ERROR: byte %d, align shift: %d", j, a); compare_ok = false; @@ -271,16 +267,16 @@ test_mount(int argc, char *argv[]) } } - fsync(stdout); - fsync(stderr); + fsync(fileno(stdout)); + fsync(fileno(stderr)); usleep(20000); /* we always reboot for the next test if we get here */ warnx("Iteration done, rebooting.."); - fsync(stdout); - fsync(stderr); + fsync(fileno(stdout)); + fsync(fileno(stderr)); usleep(50000); systemreset(false); diff --git a/src/systemcmds/tests/test_mtd.c b/src/systemcmds/tests/test_mtd.c index bac9efbdb..43231ccad 100644 --- a/src/systemcmds/tests/test_mtd.c +++ b/src/systemcmds/tests/test_mtd.c @@ -57,6 +57,8 @@ #define PARAM_FILE_NAME "/fs/mtd_params" static int check_user_abort(int fd); +static void print_fail(void); +static void print_success(void); int check_user_abort(int fd) { /* check if user wants to abort */ @@ -126,7 +128,7 @@ test_mtd(int argc, char *argv[]) uint8_t write_buf[chunk_sizes[c]] __attribute__((aligned(64))); /* fill write buffer with known values */ - for (int i = 0; i < sizeof(write_buf); i++) { + for (unsigned i = 0; i < sizeof(write_buf); i++) { /* this will wrap, but we just need a known value with spacing */ write_buf[i] = i+11; } @@ -137,11 +139,14 @@ test_mtd(int argc, char *argv[]) int fd = open(PARAM_FILE_NAME, O_RDONLY); int rret = read(fd, read_buf, chunk_sizes[c]); close(fd); + if (rret <= 0) { + err(1, "read error"); + } fd = open(PARAM_FILE_NAME, O_WRONLY); printf("printing 2 percent of the first chunk:\n"); - for (int i = 0; i < sizeof(read_buf) / 50; i++) { + for (unsigned i = 0; i < sizeof(read_buf) / 50; i++) { printf("%02X", read_buf[i]); } printf("\n"); @@ -166,14 +171,16 @@ test_mtd(int argc, char *argv[]) } end = hrt_absolute_time(); + warnx("write took %llu us", (end - start)); + close(fd); fd = open(PARAM_FILE_NAME, O_RDONLY); /* read back data for validation */ for (unsigned i = 0; i < iterations; i++) { - int rret = read(fd, read_buf, chunk_sizes[c]); + int rret2 = read(fd, read_buf, chunk_sizes[c]); - if (rret != chunk_sizes[c]) { + if (rret2 != (int)chunk_sizes[c]) { warnx("READ ERROR!"); print_fail(); return 1; @@ -182,7 +189,7 @@ test_mtd(int argc, char *argv[]) /* compare value */ bool compare_ok = true; - for (int j = 0; j < chunk_sizes[c]; j++) { + for (unsigned j = 0; j < chunk_sizes[c]; j++) { if (read_buf[j] != write_buf[j]) { warnx("COMPARISON ERROR: byte %d", j); print_fail(); @@ -211,7 +218,7 @@ test_mtd(int argc, char *argv[]) char ffbuf[64]; memset(ffbuf, 0xFF, sizeof(ffbuf)); int fd = open(PARAM_FILE_NAME, O_WRONLY); - for (int i = 0; i < file_size / sizeof(ffbuf); i++) { + for (unsigned i = 0; i < file_size / sizeof(ffbuf); i++) { int ret = write(fd, ffbuf, sizeof(ffbuf)); if (ret != sizeof(ffbuf)) { diff --git a/src/systemcmds/tests/test_ppm_loopback.c b/src/systemcmds/tests/test_ppm_loopback.c index b9041b013..addd57bea 100644 --- a/src/systemcmds/tests/test_ppm_loopback.c +++ b/src/systemcmds/tests/test_ppm_loopback.c @@ -65,7 +65,6 @@ int test_ppm_loopback(int argc, char *argv[]) int _rc_sub = orb_subscribe(ORB_ID(input_rc)); int servo_fd, result; - servo_position_t data[PWM_OUTPUT_MAX_CHANNELS]; servo_position_t pos; servo_fd = open(PWM_OUTPUT_DEVICE_PATH, O_RDWR); diff --git a/src/systemcmds/tests/test_rc.c b/src/systemcmds/tests/test_rc.c index 57c0e7f4c..c9f9ef439 100644 --- a/src/systemcmds/tests/test_rc.c +++ b/src/systemcmds/tests/test_rc.c @@ -52,6 +52,7 @@ #include <arch/board/board.h> #include <drivers/drv_pwm_output.h> #include <drivers/drv_rc_input.h> +#include <drivers/drv_hrt.h> #include <systemlib/err.h> #include "tests.h" diff --git a/src/systemcmds/tests/test_servo.c b/src/systemcmds/tests/test_servo.c index ef8512bf5..9c6951ca2 100644 --- a/src/systemcmds/tests/test_servo.c +++ b/src/systemcmds/tests/test_servo.c @@ -51,6 +51,7 @@ #include <arch/board/board.h> #include <drivers/drv_pwm_output.h> +#include <systemlib/err.h> #include <nuttx/spi.h> diff --git a/src/systemcmds/tests/tests.h b/src/systemcmds/tests/tests.h index 82de05dff..ad55e1410 100644 --- a/src/systemcmds/tests/tests.h +++ b/src/systemcmds/tests/tests.h @@ -107,11 +107,13 @@ extern int test_jig_voltages(int argc, char *argv[]); extern int test_param(int argc, char *argv[]); extern int test_bson(int argc, char *argv[]); extern int test_file(int argc, char *argv[]); +extern int test_file2(int argc, char *argv[]); extern int test_mixer(int argc, char *argv[]); extern int test_rc(int argc, char *argv[]); extern int test_conv(int argc, char *argv[]); extern int test_mount(int argc, char *argv[]); extern int test_mtd(int argc, char *argv[]); +extern int test_mathlib(int argc, char *argv[]); __END_DECLS diff --git a/src/systemcmds/tests/tests_main.c b/src/systemcmds/tests/tests_main.c index 77a4df618..e3f26924f 100644 --- a/src/systemcmds/tests/tests_main.c +++ b/src/systemcmds/tests/tests_main.c @@ -104,11 +104,13 @@ const struct { {"param", test_param, 0}, {"bson", test_bson, 0}, {"file", test_file, 0}, + {"file2", test_file2, OPT_NOJIGTEST | OPT_NOALLTEST}, {"mixer", test_mixer, OPT_NOJIGTEST | OPT_NOALLTEST}, {"rc", test_rc, OPT_NOJIGTEST | OPT_NOALLTEST}, {"conv", test_conv, OPT_NOJIGTEST | OPT_NOALLTEST}, {"mount", test_mount, OPT_NOJIGTEST | OPT_NOALLTEST}, {"mtd", test_mtd, 0}, + {"mathlib", test_mathlib, 0}, {"help", test_help, OPT_NOALLTEST | OPT_NOHELP | OPT_NOJIGTEST}, {NULL, NULL, 0} }; @@ -233,7 +235,7 @@ test_perf(int argc, char *argv[]) printf("perf: expect count of 1\n"); perf_print_counter(ec); printf("perf: expect at least two counters\n"); - perf_print_all(); + perf_print_all(0); perf_free(cc); perf_free(ec); diff --git a/src/systemcmds/top/module.mk b/src/systemcmds/top/module.mk index 9239aafc3..548a09f85 100644 --- a/src/systemcmds/top/module.mk +++ b/src/systemcmds/top/module.mk @@ -38,7 +38,7 @@ MODULE_COMMAND = top SRCS = top.c -MODULE_STACKSIZE = 3000 +MODULE_STACKSIZE = 1700 MAXOPTIMIZATION = -Os diff --git a/src/systemcmds/top/top.c b/src/systemcmds/top/top.c index 1ca3fc928..37e913040 100644 --- a/src/systemcmds/top/top.c +++ b/src/systemcmds/top/top.c @@ -233,8 +233,8 @@ top_main(void) system_load.tasks[i].tcb->pid, CONFIG_TASK_NAME_SIZE, system_load.tasks[i].tcb->name, (system_load.tasks[i].total_runtime / 1000), - (int)(curr_loads[i] * 100), - (int)(curr_loads[i] * 100000.0f - (int)(curr_loads[i] * 1000.0f) * 100), + (int)(curr_loads[i] * 100.0f), + (int)((curr_loads[i] * 100.0f - (int)(curr_loads[i] * 100.0f)) * 1000), stack_size - stack_free, stack_size, system_load.tasks[i].tcb->sched_priority, diff --git a/src/systemcmds/ver/module.mk b/src/systemcmds/ver/module.mk new file mode 100644 index 000000000..2eeb80b61 --- /dev/null +++ b/src/systemcmds/ver/module.mk @@ -0,0 +1,44 @@ +############################################################################ +# +# 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. +# +############################################################################ + +# +# "version" nsh-command displays version infromation for hw,sw, gcc,build etc +# can be also included and used in own code via "ver.h" +# + +MODULE_COMMAND = ver +SRCS = ver.c + +MODULE_STACKSIZE = 1024 + +MAXOPTIMIZATION = -Os diff --git a/src/systemcmds/ver/ver.c b/src/systemcmds/ver/ver.c new file mode 100644 index 000000000..9ae080ee2 --- /dev/null +++ b/src/systemcmds/ver/ver.c @@ -0,0 +1,123 @@ +/**************************************************************************** +* +* 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. +* +****************************************************************************/ + +/** +* @file ver.c +* +* Version command, unifies way of showing versions of HW, SW, Build, GCC +* In case you want to add new version just extend version_main function +* +* @author Vladimir Kulla <ufon@kullaonline.net> +*/ + +#include <stdio.h> +#include <string.h> +#include <version/version.h> +#include <systemlib/err.h> + +// string constants for version commands +static const char sz_ver_hw_str[] = "hw"; +static const char sz_ver_hwcmp_str[] = "hwcmp"; +static const char sz_ver_git_str[] = "git"; +static const char sz_ver_bdate_str[] = "bdate"; +static const char sz_ver_gcc_str[] = "gcc"; +static const char sz_ver_all_str[] = "all"; + +static void usage(const char *reason) +{ + if (reason != NULL) { + printf("%s\n", reason); + } + + printf("usage: ver {hw|hwcmp|git|bdate|gcc|all}\n\n"); +} + +__EXPORT int ver_main(int argc, char *argv[]); + +int ver_main(int argc, char *argv[]) +{ + int ret = 1; //defaults to an error + + // first check if there are at least 2 params + if (argc >= 2) { + if (argv[1] != NULL) { + if (!strncmp(argv[1], sz_ver_hw_str, sizeof(sz_ver_hw_str))) { + printf("%s\n", HW_ARCH); + ret = 0; + + } else if (!strncmp(argv[1], sz_ver_hwcmp_str, sizeof(sz_ver_hwcmp_str))) { + if (argc >= 3 && argv[2] != NULL) { + // compare 3rd parameter with HW_ARCH string, in case of match, return 0 + ret = strncmp(HW_ARCH, argv[2], strlen(HW_ARCH)); + + if (ret == 0) { + printf("ver hwcmp match: %s\n", HW_ARCH); + } + + } else { + errx(1, "Not enough arguments, try 'ver hwcmp PX4FMU_V2'"); + } + + } else if (!strncmp(argv[1], sz_ver_git_str, sizeof(sz_ver_git_str))) { + printf("%s\n", FW_GIT); + ret = 0; + + } else if (!strncmp(argv[1], sz_ver_bdate_str, sizeof(sz_ver_bdate_str))) { + printf("%s %s\n", __DATE__, __TIME__); + ret = 0; + + } else if (!strncmp(argv[1], sz_ver_gcc_str, sizeof(sz_ver_gcc_str))) { + printf("%s\n", __VERSION__); + ret = 0; + + } else if (!strncmp(argv[1], sz_ver_all_str, sizeof(sz_ver_all_str))) { + printf("HW arch: %s\n", HW_ARCH); + printf("Build datetime: %s %s\n", __DATE__, __TIME__); + printf("FW git-hash: %s\n", FW_GIT); + printf("GCC toolchain: %s\n", __VERSION__); + ret = 0; + + } else { + errx(1, "unknown command.\n"); + } + + } else { + usage("Error, input parameter NULL.\n"); + } + + } else { + usage("Error, not enough parameters."); + } + + return ret; +} |