diff options
Diffstat (limited to 'src/systemcmds')
-rw-r--r-- | src/systemcmds/motor_test/module.mk | 2 | ||||
-rw-r--r-- | src/systemcmds/motor_test/motor_test.c | 33 | ||||
-rw-r--r-- | src/systemcmds/nshterm/nshterm.c | 27 | ||||
-rw-r--r-- | src/systemcmds/pwm/pwm.c | 68 | ||||
-rw-r--r-- | src/systemcmds/ver/ver.c | 76 |
5 files changed, 134 insertions, 72 deletions
diff --git a/src/systemcmds/motor_test/module.mk b/src/systemcmds/motor_test/module.mk index eb36d2ded..261428ef9 100644 --- a/src/systemcmds/motor_test/module.mk +++ b/src/systemcmds/motor_test/module.mk @@ -39,3 +39,5 @@ MODULE_COMMAND = motor_test SRCS = motor_test.c MODULE_STACKSIZE = 4096 + +MAXOPTIMIZATION = -Os diff --git a/src/systemcmds/motor_test/motor_test.c b/src/systemcmds/motor_test/motor_test.c index 079f99674..1b7ff75f7 100644 --- a/src/systemcmds/motor_test/motor_test.c +++ b/src/systemcmds/motor_test/motor_test.c @@ -54,7 +54,8 @@ #include "systemlib/err.h" -__EXPORT int motor_test_main(int argc, char *argv[]); +__EXPORT int motor_test_main(int argc, char *argv[]); + static void motor_test(unsigned channel, float value); static void usage(const char *reason); @@ -67,19 +68,20 @@ void motor_test(unsigned channel, float value) _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); - } + if (_test_motor_pub > 0) { + /* publish test 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) + if (reason != NULL) { warnx("%s", reason); + } errx(1, "usage:\n" @@ -90,8 +92,9 @@ static void usage(const char *reason) int motor_test_main(int argc, char *argv[]) { - unsigned long channel, lval; - float value; + unsigned long channel = 0; + unsigned long lval; + float value = 0.0f; int ch; if (argc != 5) { @@ -102,18 +105,18 @@ int motor_test_main(int argc, char *argv[]) switch (ch) { case 'm': - /* Read in channels supplied as one int and convert to mask: 1234 -> 0xF */ + /* Read in motor number */ channel = strtoul(optarg, NULL, 0); break; case 'p': - /* Read in custom low value */ + /* Read in power value */ lval = strtoul(optarg, NULL, 0); if (lval > 100) usage("value invalid"); - value = (float)lval/100.f; + value = ((float)lval)/100.f; break; default: usage(NULL); @@ -122,7 +125,7 @@ int motor_test_main(int argc, char *argv[]) motor_test(channel, value); - printf("motor %d set to %.2f\n", channel, value); + printf("motor %d set to %.2f\n", channel, (double)value); exit(0); } diff --git a/src/systemcmds/nshterm/nshterm.c b/src/systemcmds/nshterm/nshterm.c index f06c49552..edeb5c624 100644 --- a/src/systemcmds/nshterm/nshterm.c +++ b/src/systemcmds/nshterm/nshterm.c @@ -51,6 +51,8 @@ #include <fcntl.h> #include <systemlib/err.h> +#include <uORB/topics/actuator_armed.h> + __EXPORT int nshterm_main(int argc, char *argv[]); int @@ -62,9 +64,30 @@ nshterm_main(int argc, char *argv[]) } unsigned retries = 0; int fd = -1; + int armed_fd = orb_subscribe(ORB_ID(actuator_armed)); + struct actuator_armed_s armed; + /* we assume the system does not provide arming status feedback */ + bool armed_updated = false; + + /* try the first 30 seconds or if arming system is ready */ + while ((retries < 300) || armed_updated) { + + /* abort if an arming topic is published and system is armed */ + bool updated = false; + if (orb_check(armed_fd, &updated)) { + /* the system is now providing arming status feedback. + * instead of timing out, we resort to abort bringing + * up the terminal. + */ + armed_updated = true; + orb_copy(ORB_ID(actuator_armed), armed_fd, &armed); + + if (armed.armed) { + /* this is not an error, but we are done */ + exit(0); + } + } - /* try the first 30 seconds */ - while (retries < 300) { /* the retries are to cope with the behaviour of /dev/ttyACM0 */ /* which may not be ready immediately. */ fd = open(argv[1], O_RDWR); diff --git a/src/systemcmds/pwm/pwm.c b/src/systemcmds/pwm/pwm.c index 360a80a90..4bc1a727b 100644 --- a/src/systemcmds/pwm/pwm.c +++ b/src/systemcmds/pwm/pwm.c @@ -70,34 +70,34 @@ usage(const char *reason) "usage:\n" "pwm arm|disarm|rate|failsafe|disarmed|min|max|test|info ...\n" "\n" - " arm Arm output\n" - " disarm Disarm output\n" + "arm\t\t\t\tArm output\n" + "disarm\t\t\t\tDisarm output\n" "\n" - " rate ... Configure PWM rates\n" - " [-g <channel group>] Channel group that should update at the alternate rate\n" - " [-m <chanmask> ] Directly supply channel mask\n" - " [-a] Configure all outputs\n" - " -r <alt_rate> PWM rate (50 to 400 Hz)\n" + "rate ...\t\t\tConfigure PWM rates\n" + "\t[-g <channel group>]\t(e.g. 0,1,2)\n" + "\t[-m <channel mask> ]\t(e.g. 0xF)\n" + "\t[-a]\t\t\tConfigure all outputs\n" + "\t-r <alt_rate>\t\tPWM rate (50 to 400 Hz)\n" "\n" - " failsafe ... Configure failsafe PWM values\n" - " disarmed ... Configure disarmed PWM values\n" - " min ... Configure minimum PWM values\n" - " max ... Configure maximum PWM values\n" - " [-c <channels>] Supply channels (e.g. 1234)\n" - " [-m <chanmask> ] Directly supply channel mask (e.g. 0xF)\n" - " [-a] Configure all outputs\n" - " -p <pwm value> PWM value\n" + "failsafe ...\t\t\tFailsafe PWM\n" + "disarmed ...\t\t\tDisarmed PWM\n" + "min ...\t\t\t\tMinimum PWM\n" + "max ...\t\t\t\tMaximum PWM\n" + "\t[-c <channels>]\t\t(e.g. 1234)\n" + "\t[-m <channel mask> ]\t(e.g. 0xF)\n" + "\t[-a]\t\t\tConfigure all outputs\n" + "\t-p <pwm value>\t\tPWM value\n" "\n" - " test ... Directly set PWM values\n" - " [-c <channels>] Supply channels (e.g. 1234)\n" - " [-m <chanmask> ] Directly supply channel mask (e.g. 0xF)\n" - " [-a] Configure all outputs\n" - " -p <pwm value> PWM value\n" + "test ...\t\t\tDirectly set PWM\n" + "\t[-c <channels>]\t\t(e.g. 1234)\n" + "\t[-m <channel mask> ]\t(e.g. 0xF)\n" + "\t[-a]\t\t\tConfigure all outputs\n" + "\t-p <pwm value>\t\tPWM value\n" "\n" - " info Print information about the PWM device\n" + "info\t\t\t\tPrint information\n" "\n" - " -v Print verbose information\n" - " -d <device> PWM output device (defaults to " PWM_OUTPUT_DEVICE_PATH ")\n" + "\t-v\t\t\tVerbose\n" + "\t-d <dev>\t\t(default " PWM_OUTPUT_DEVICE_PATH ")\n" ); } @@ -119,7 +119,7 @@ pwm_main(int argc, char *argv[]) unsigned single_ch = 0; unsigned pwm_value = 0; - if (argc < 1) + if (argc < 2) usage(NULL); while ((ch = getopt(argc-1, &argv[1], "d:vc:g:m:ap:r:")) != EOF) { @@ -161,7 +161,7 @@ pwm_main(int argc, char *argv[]) /* Read in mask directly */ set_mask = strtoul(optarg, &ep, 0); if (*ep != '\0') - usage("bad set_mask value"); + usage("BAD set_mask VAL"); break; case 'a': @@ -172,12 +172,12 @@ pwm_main(int argc, char *argv[]) case 'p': pwm_value = strtoul(optarg, &ep, 0); if (*ep != '\0') - usage("bad PWM value provided"); + usage("BAD PWM VAL"); break; case 'r': alt_rate = strtoul(optarg, &ep, 0); if (*ep != '\0') - usage("bad alternative rate provided"); + usage("BAD rate VAL"); break; default: break; @@ -185,7 +185,7 @@ pwm_main(int argc, char *argv[]) } if (print_verbose && set_mask > 0) { - warnx("Chose channels: "); + warnx("Channels: "); printf(" "); for (unsigned i = 0; i<PWM_OUTPUT_MAX_CHANNELS; i++) { if (set_mask & 1<<i) @@ -360,7 +360,7 @@ pwm_main(int argc, char *argv[]) usage("no channels set"); } if (pwm_value == 0) - usage("no PWM value provided"); + usage("no PWM provided"); struct pwm_output_values pwm_values = {.values = {0}, .channel_count = 0}; @@ -379,7 +379,7 @@ pwm_main(int argc, char *argv[]) ret = ioctl(fd, PWM_SERVO_SET_FAILSAFE_PWM, (long unsigned int)&pwm_values); if (ret != OK) - errx(ret, "failed setting failsafe values"); + errx(ret, "BAD input VAL"); } exit(0); @@ -389,7 +389,7 @@ pwm_main(int argc, char *argv[]) usage("no channels set"); } if (pwm_value == 0) - usage("no PWM value provided"); + usage("no PWM provided"); /* get current servo values */ struct pwm_output_values last_spos; @@ -483,7 +483,7 @@ pwm_main(int argc, char *argv[]) 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]); + warnx("Step input (0 to 100%%) over %u us ramp", steps_timings_us[steps_timing_index]); while (1) { for (unsigned i = 0; i < servo_count; i++) { @@ -522,7 +522,7 @@ pwm_main(int argc, char *argv[]) err(1, "PWM_SERVO_SET(%d)", i); } } - warnx("Key pressed, user abort\n"); + warnx("User abort\n"); exit(0); } } @@ -671,7 +671,7 @@ pwm_main(int argc, char *argv[]) exit(0); } - usage("specify arm|disarm|rate|failsafe\n\t\tdisarmed|min|max|test|info|forcefail|terminatefail"); + usage(NULL); return 0; } diff --git a/src/systemcmds/ver/ver.c b/src/systemcmds/ver/ver.c index 9ae080ee2..2ead3e632 100644 --- a/src/systemcmds/ver/ver.c +++ b/src/systemcmds/ver/ver.c @@ -44,14 +44,16 @@ #include <string.h> #include <version/version.h> #include <systemlib/err.h> +#include <systemlib/mcu_version.h> -// string constants for version commands +/* 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 const char mcu_ver_str[] = "mcu"; static void usage(const char *reason) { @@ -59,55 +61,87 @@ static void usage(const char *reason) printf("%s\n", reason); } - printf("usage: ver {hw|hwcmp|git|bdate|gcc|all}\n\n"); + printf("usage: ver {hw|hwcmp|git|bdate|gcc|all|mcu}\n\n"); } __EXPORT int ver_main(int argc, char *argv[]); int ver_main(int argc, char *argv[]) { - int ret = 1; //defaults to an error + /* defaults to an error */ + int ret = 1; - // first check if there are at least 2 params + /* 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 (!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 + /* 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); } + return ret; } 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; + /* check if we want to show all */ + bool show_all = !strncmp(argv[1], sz_ver_all_str, sizeof(sz_ver_all_str)); - } else if (!strncmp(argv[1], sz_ver_bdate_str, sizeof(sz_ver_bdate_str))) { - printf("%s %s\n", __DATE__, __TIME__); + if (show_all || !strncmp(argv[1], sz_ver_hw_str, sizeof(sz_ver_hw_str))) { + printf("HW arch: %s\n", HW_ARCH); ret = 0; - } else if (!strncmp(argv[1], sz_ver_gcc_str, sizeof(sz_ver_gcc_str))) { - printf("%s\n", __VERSION__); + } + + if (show_all || !strncmp(argv[1], sz_ver_git_str, sizeof(sz_ver_git_str))) { + printf("FW git-hash: %s\n", FW_GIT); ret = 0; - } else if (!strncmp(argv[1], sz_ver_all_str, sizeof(sz_ver_all_str))) { - printf("HW arch: %s\n", HW_ARCH); + } + + if (show_all || !strncmp(argv[1], sz_ver_bdate_str, sizeof(sz_ver_bdate_str))) { 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 { + } + + if (show_all || !strncmp(argv[1], sz_ver_gcc_str, sizeof(sz_ver_gcc_str))) { + printf("Toolchain: %s\n", __VERSION__); + ret = 0; + + } + + if (show_all || !strncmp(argv[1], mcu_ver_str, sizeof(mcu_ver_str))) { + + char rev; + char* revstr; + + int chip_version = mcu_version(&rev, &revstr); + + if (chip_version < 0) { + printf("UNKNOWN MCU\n"); + + } else { + printf("MCU: %s, rev. %c\n", revstr, rev); + + if (chip_version < MCU_REV_STM32F4_REV_3) { + printf("\nWARNING WARNING WARNING!\n" + "Revision %c has a silicon errata\n" + "This device can only utilize a maximum of 1MB flash safely!\n" + "http://px4.io/help/errata\n\n", rev); + } + } + + ret = 0; + } + + if (ret == 1) { errx(1, "unknown command.\n"); } |