Merge branch 'getopt-cleanup-v2'

This commit is contained in:
Lorenz Meier 2015-07-02 00:26:57 +02:00
commit f411b7ed21
7 changed files with 92 additions and 64 deletions

View File

@ -23,6 +23,8 @@ MODULES += systemcmds/tests
#MODULES += systemcmds/reboot #MODULES += systemcmds/reboot
MODULES += systemcmds/topic_listener MODULES += systemcmds/topic_listener
MODULES += systemcmds/ver MODULES += systemcmds/ver
MODULES += systemcmds/esc_calib
MODULES += systemcmds/reboot
# #
# General system control # General system control

View File

@ -56,9 +56,11 @@ $(PRODUCT_SHARED_PRELINK): $(OBJS) $(MODULE_OBJS) $(LIBRARY_LIBS) $(GLOBAL_DEPS)
$(PRODUCT_SHARED_LIB): $(PRODUCT_SHARED_PRELINK) $(PRODUCT_SHARED_LIB): $(PRODUCT_SHARED_PRELINK)
$(call LINK_A,$@,$(PRODUCT_SHARED_PRELINK)) $(call LINK_A,$@,$(PRODUCT_SHARED_PRELINK))
$(WORK_DIR)apps.h: $(WORK_DIR)builtin_commands
$(PX4_BASE)/Tools/posix_apps.py > $(WORK_DIR)apps.h
MAIN = $(PX4_BASE)/src/platforms/posix/main.cpp MAIN = $(PX4_BASE)/src/platforms/posix/main.cpp
$(WORK_DIR)mainapp: $(PRODUCT_SHARED_LIB) $(WORK_DIR)mainapp: $(PRODUCT_SHARED_LIB) $(WORK_DIR)apps.h
$(PX4_BASE)/Tools/posix_apps.py > apps.h
$(call LINK,$@, -I. $(MAIN) $(PRODUCT_SHARED_LIB)) $(call LINK,$@, -I. $(MAIN) $(PRODUCT_SHARED_LIB))
# #

View File

@ -120,7 +120,7 @@ ifeq ($(CONFIG_BOARD),)
$(error Board config does not define CONFIG_BOARD) $(error Board config does not define CONFIG_BOARD)
endif endif
ARCHDEFINES += -DCONFIG_ARCH_BOARD_$(CONFIG_BOARD) \ ARCHDEFINES += -DCONFIG_ARCH_BOARD_$(CONFIG_BOARD) \
-Dnoreturn_function= \ -Dnoreturn_function=__attribute__\(\(noreturn\)\) \
-I$(PX4_BASE)/src/modules/systemlib \ -I$(PX4_BASE)/src/modules/systemlib \
-I$(PX4_BASE)/src/lib/eigen \ -I$(PX4_BASE)/src/lib/eigen \
-I$(PX4_BASE)/src/platforms/posix/include \ -I$(PX4_BASE)/src/platforms/posix/include \

View File

@ -44,6 +44,7 @@
#include <px4_config.h> #include <px4_config.h>
#include <px4_defines.h> #include <px4_defines.h>
#include <px4_getopt.h>
#include <sys/types.h> #include <sys/types.h>
#include <sys/stat.h> #include <sys/stat.h>
#include <sys/prctl.h> #include <sys/prctl.h>
@ -895,10 +896,12 @@ int sdlog2_thread_main(int argc, char *argv[])
* set error flag instead */ * set error flag instead */
bool err_flag = false; bool err_flag = false;
while ((ch = getopt(argc, argv, "r:b:eatx")) != EOF) { int myoptind = 1;
const char *myoptarg = NULL;
while ((ch = px4_getopt(argc, argv, "r:b:eatx", &myoptind, &myoptarg)) != EOF) {
switch (ch) { switch (ch) {
case 'r': { case 'r': {
unsigned long r = strtoul(optarg, NULL, 10); unsigned long r = strtoul(myoptarg, NULL, 10);
if (r == 0) { if (r == 0) {
r = 1; r = 1;
@ -909,7 +912,7 @@ int sdlog2_thread_main(int argc, char *argv[])
break; break;
case 'b': { case 'b': {
unsigned long s = strtoul(optarg, NULL, 10); unsigned long s = strtoul(myoptarg, NULL, 10);
if (s < 1) { if (s < 1) {
s = 1; s = 1;

View File

@ -98,6 +98,7 @@ void
px4_systemreset(bool to_bootloader) px4_systemreset(bool to_bootloader)
{ {
PX4_WARN("Called px4_system_reset"); PX4_WARN("Called px4_system_reset");
exit(0);
} }
px4_task_t px4_task_spawn_cmd(const char *name, int scheduler, int priority, int stack_size, px4_main_t entry, char * const argv[]) px4_task_t px4_task_spawn_cmd(const char *name, int scheduler, int priority, int stack_size, px4_main_t entry, char * const argv[])

View File

@ -39,7 +39,9 @@
*/ */
#include <px4_config.h> #include <px4_config.h>
#include <platforms/px4_defines.h> #include <px4_getopt.h>
#include <px4_defines.h>
#include <px4_log.h>
#include <stdio.h> #include <stdio.h>
#include <stdlib.h> #include <stdlib.h>
@ -52,15 +54,9 @@
#include <sys/ioctl.h> #include <sys/ioctl.h>
#include <sys/stat.h> #include <sys/stat.h>
#include <nuttx/i2c.h>
#include <nuttx/mtd.h>
#include <nuttx/fs/nxffs.h>
#include <nuttx/fs/ioctl.h>
#include <arch/board/board.h> #include <arch/board/board.h>
#include "systemlib/systemlib.h" #include "systemlib/systemlib.h"
#include "systemlib/err.h"
#include "drivers/drv_pwm_output.h" #include "drivers/drv_pwm_output.h"
#include <uORB/topics/actuator_controls.h> #include <uORB/topics/actuator_controls.h>
@ -76,9 +72,9 @@ static void
usage(const char *reason) usage(const char *reason)
{ {
if (reason != NULL) if (reason != NULL)
warnx("%s", reason); PX4_ERR("%s", reason);
errx(1, PX4_ERR(
"usage:\n" "usage:\n"
"esc_calib\n" "esc_calib\n"
" [-d <device> PWM output device (defaults to " PWM_OUTPUT0_DEVICE_PATH ")\n" " [-d <device> PWM output device (defaults to " PWM_OUTPUT0_DEVICE_PATH ")\n"
@ -93,7 +89,7 @@ usage(const char *reason)
int int
esc_calib_main(int argc, char *argv[]) esc_calib_main(int argc, char *argv[])
{ {
char *dev = PWM_OUTPUT0_DEVICE_PATH; const char *dev = PWM_OUTPUT0_DEVICE_PATH;
char *ep; char *ep;
int ch; int ch;
int ret; int ret;
@ -114,21 +110,24 @@ esc_calib_main(int argc, char *argv[])
if (argc < 2) { if (argc < 2) {
usage("no channels provided"); usage("no channels provided");
return 1;
} }
int arg_consumed = 0; int arg_consumed = 0;
while ((ch = getopt(argc, argv, "d:c:m:al:h:")) != EOF) { int myoptind = 1;
const char *myoptarg = NULL;
while ((ch = px4_getopt(argc, argv, "d:c:m:al:h:", &myoptind, &myoptarg)) != EOF) {
switch (ch) { switch (ch) {
case 'd': case 'd':
dev = optarg; dev = myoptarg;
arg_consumed += 2; arg_consumed += 2;
break; break;
case 'c': case 'c':
/* Read in channels supplied as one int and convert to mask: 1234 -> 0xF */ /* Read in channels supplied as one int and convert to mask: 1234 -> 0xF */
channels = strtoul(optarg, &ep, 0); channels = strtoul(myoptarg, &ep, 0);
while ((single_ch = channels % 10)) { while ((single_ch = channels % 10)) {
@ -139,9 +138,11 @@ esc_calib_main(int argc, char *argv[])
case 'm': case 'm':
/* Read in mask directly */ /* Read in mask directly */
set_mask = strtoul(optarg, &ep, 0); set_mask = strtoul(myoptarg, &ep, 0);
if (*ep != '\0') if (*ep != '\0') {
usage("bad set_mask value"); usage("bad set_mask value");
return 1;
}
break; break;
case 'a': case 'a':
@ -153,27 +154,34 @@ esc_calib_main(int argc, char *argv[])
case 'l': case 'l':
/* Read in custom low value */ /* Read in custom low value */
pwm_low = strtoul(optarg, &ep, 0); pwm_low = strtoul(myoptarg, &ep, 0);
if (*ep != '\0' || pwm_low < PWM_LOWEST_MIN || pwm_low > PWM_HIGHEST_MIN) if (*ep != '\0' || pwm_low < PWM_LOWEST_MIN || pwm_low > PWM_HIGHEST_MIN) {
usage("low PWM invalid"); usage("low PWM invalid");
return 1;
}
break; break;
case 'h': case 'h':
/* Read in custom high value */ /* Read in custom high value */
pwm_high = strtoul(optarg, &ep, 0); pwm_high = strtoul(myoptarg, &ep, 0);
if (*ep != '\0' || pwm_high > PWM_HIGHEST_MAX || pwm_high < PWM_LOWEST_MAX) if (*ep != '\0' || pwm_high > PWM_HIGHEST_MAX || pwm_high < PWM_LOWEST_MAX) {
usage("high PWM invalid"); usage("high PWM invalid");
return 1;
}
break; break;
default: default:
usage(NULL); usage(NULL);
return 1;
} }
} }
if (set_mask == 0) { if (set_mask == 0) {
usage("no channels chosen"); usage("no channels chosen");
return 1;
} }
if (pwm_low > pwm_high) { if (pwm_low > pwm_high) {
usage("low pwm is higher than high pwm"); usage("low pwm is higher than high pwm");
return 1;
} }
/* make sure no other source is publishing control values now */ /* make sure no other source is publishing control values now */
@ -191,9 +199,10 @@ esc_calib_main(int argc, char *argv[])
orb_check(act_sub, &orb_updated); orb_check(act_sub, &orb_updated);
if (orb_updated) { if (orb_updated) {
errx(1, "ABORTING! Attitude control still active. Please ensure to shut down all controllers:\n" PX4_ERR("ABORTING! Attitude control still active. Please ensure to shut down all controllers:\n"
"\tmc_att_control stop\n" "\tmc_att_control stop\n"
"\tfw_att_control stop\n"); "\tfw_att_control stop\n");
return 1;
} }
printf("\nATTENTION, please remove or fix propellers before starting calibration!\n" printf("\nATTENTION, please remove or fix propellers before starting calibration!\n"
@ -211,24 +220,22 @@ esc_calib_main(int argc, char *argv[])
ret = poll(&fds, 1, 0); ret = poll(&fds, 1, 0);
if (ret > 0) { if (ret > 0) {
read(0, &c, 1); read(0, &c, 1);
if (c == 'y' || c == 'Y') { if (c == 'y' || c == 'Y') {
break; break;
} else if (c == 0x03 || c == 0x63 || c == 'q') { } else if (c == 0x03 || c == 0x63 || c == 'q') {
printf("ESC calibration exited\n"); printf("ESC calibration exited\n");
exit(0); return 0;
} else if (c == 'n' || c == 'N') { } else if (c == 'n' || c == 'N') {
printf("ESC calibration aborted\n"); printf("ESC calibration aborted\n");
exit(0); return 0;
} else { } else {
printf("Unknown input, ESC calibration aborted\n"); printf("Unknown input, ESC calibration aborted\n");
exit(0); return 0;
} }
} }
@ -239,24 +246,32 @@ esc_calib_main(int argc, char *argv[])
/* open for ioctl only */ /* open for ioctl only */
int fd = open(dev, 0); int fd = open(dev, 0);
if (fd < 0) if (fd < 0) {
err(1, "can't open %s", dev); PX4_ERR("can't open %s", dev);
return 1;
}
/* get number of channels available on the device */ /* get number of channels available on the device */
ret = ioctl(fd, PWM_SERVO_GET_COUNT, (unsigned long)&max_channels); ret = ioctl(fd, PWM_SERVO_GET_COUNT, (unsigned long)&max_channels);
if (ret != OK) if (ret != OK) {
err(1, "PWM_SERVO_GET_COUNT"); PX4_ERR("PWM_SERVO_GET_COUNT");
return 1;
}
/* tell IO/FMU that its ok to disable its safety with the switch */ /* tell IO/FMU that its ok to disable its safety with the switch */
ret = ioctl(fd, PWM_SERVO_SET_ARM_OK, 0); ret = ioctl(fd, PWM_SERVO_SET_ARM_OK, 0);
if (ret != OK) if (ret != OK) {
err(1, "PWM_SERVO_SET_ARM_OK"); PX4_ERR("PWM_SERVO_SET_ARM_OK");
return 1;
}
/* tell IO/FMU that the system is armed (it will output values if safety is off) */ /* tell IO/FMU that the system is armed (it will output values if safety is off) */
ret = ioctl(fd, PWM_SERVO_ARM, 0); ret = ioctl(fd, PWM_SERVO_ARM, 0);
if (ret != OK) if (ret != OK) {
err(1, "PWM_SERVO_ARM"); PX4_ERR("PWM_SERVO_ARM");
return 1;
}
warnx("Outputs armed"); printf("Outputs armed");
/* wait for user confirmation */ /* wait for user confirmation */
@ -273,24 +288,24 @@ esc_calib_main(int argc, char *argv[])
if (set_mask & 1<<i) { if (set_mask & 1<<i) {
ret = ioctl(fd, PWM_SERVO_SET(i), pwm_high); ret = ioctl(fd, PWM_SERVO_SET(i), pwm_high);
if (ret != OK) if (ret != OK) {
err(1, "PWM_SERVO_SET(%d), value: %d", i, pwm_high); PX4_ERR( "PWM_SERVO_SET(%d), value: %d", i, pwm_high);
goto cleanup;
}
} }
} }
ret = poll(&fds, 1, 0); ret = poll(&fds, 1, 0);
if (ret > 0) { if (ret > 0) {
read(0, &c, 1); read(0, &c, 1);
if (c == 13) { if (c == 13) {
break; break;
} else if (c == 0x03 || c == 0x63 || c == 'q') { } else if (c == 0x03 || c == 0x63 || c == 'q') {
warnx("ESC calibration exited"); printf("ESC calibration exited");
exit(0); goto done;
} }
} }
@ -310,24 +325,24 @@ esc_calib_main(int argc, char *argv[])
if (set_mask & 1<<i) { if (set_mask & 1<<i) {
ret = ioctl(fd, PWM_SERVO_SET(i), pwm_low); ret = ioctl(fd, PWM_SERVO_SET(i), pwm_low);
if (ret != OK) if (ret != OK) {
err(1, "PWM_SERVO_SET(%d), value: %d", i, pwm_low); PX4_ERR("PWM_SERVO_SET(%d), value: %d", i, pwm_low);
goto cleanup;
}
} }
} }
ret = poll(&fds, 1, 0); ret = poll(&fds, 1, 0);
if (ret > 0) { if (ret > 0) {
read(0, &c, 1); read(0, &c, 1);
if (c == 13) { if (c == 13) {
break; break;
} else if (c == 0x03 || c == 0x63 || c == 'q') { } else if (c == 0x03 || c == 0x63 || c == 'q') {
printf("ESC calibration exited\n"); printf("ESC calibration exited\n");
exit(0); goto done;
} }
} }
@ -337,12 +352,19 @@ esc_calib_main(int argc, char *argv[])
/* disarm */ /* disarm */
ret = ioctl(fd, PWM_SERVO_DISARM, 0); ret = ioctl(fd, PWM_SERVO_DISARM, 0);
if (ret != OK) if (ret != OK) {
err(1, "PWM_SERVO_DISARM"); PX4_ERR("PWM_SERVO_DISARM");
goto cleanup;
}
warnx("Outputs disarmed"); printf("Outputs disarmed");
printf("ESC calibration finished\n"); printf("ESC calibration finished\n");
exit(0); done:
close(fd);
return 0;
cleanup:
close(fd);
return 1;
} }

View File

@ -38,12 +38,10 @@
*/ */
#include <px4_config.h> #include <px4_config.h>
#include <unistd.h> #include <px4_getopt.h>
#include <stdio.h> #include <px4_tasks.h>
#include <getopt.h> #include <px4_log.h>
#include <systemlib/systemlib.h> #include <systemlib/systemlib.h>
#include <systemlib/err.h>
__EXPORT int reboot_main(int argc, char *argv[]); __EXPORT int reboot_main(int argc, char *argv[]);
@ -52,14 +50,16 @@ int reboot_main(int argc, char *argv[])
int ch; int ch;
bool to_bootloader = false; bool to_bootloader = false;
while ((ch = getopt(argc, argv, "b")) != -1) { int myoptind = 1;
const char *myoptarg = NULL;
while ((ch = px4_getopt(argc, argv, "b", &myoptind, &myoptarg)) != -1) {
switch (ch) { switch (ch) {
case 'b': case 'b':
to_bootloader = true; to_bootloader = true;
break; break;
default: default:
errx(1, "usage: reboot [-b]\n" PX4_ERR("usage: reboot [-b]\n"
" -b reboot into the bootloader"); " -b reboot into the bootloader");
} }
@ -67,5 +67,3 @@ int reboot_main(int argc, char *argv[])
px4_systemreset(to_bootloader); px4_systemreset(to_bootloader);
} }