aboutsummaryrefslogtreecommitdiff
path: root/src
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2013-07-18 13:16:34 +0200
committerLorenz Meier <lm@inf.ethz.ch>2013-07-18 13:16:34 +0200
commit8d1abf4aa441e1c6c886e8af6ecaab2c3ca6e255 (patch)
tree724a92a0f6dcc29ac05a45dc77f4998bc8b7f9c7 /src
parent0cd8f2d35b30b5081083ae830409a9090a02c6bc (diff)
downloadpx4-firmware-8d1abf4aa441e1c6c886e8af6ecaab2c3ca6e255.tar.gz
px4-firmware-8d1abf4aa441e1c6c886e8af6ecaab2c3ca6e255.tar.bz2
px4-firmware-8d1abf4aa441e1c6c886e8af6ecaab2c3ca6e255.zip
Lunchtime HOTFIX: Bring back USB console to operational, allow single-USB connection operation via QGC
Diffstat (limited to 'src')
-rw-r--r--src/drivers/boards/px4fmu/px4fmu_init.c2
-rw-r--r--src/drivers/hmc5883/hmc5883.cpp3
-rw-r--r--src/drivers/mpu6000/mpu6000.cpp3
-rw-r--r--src/drivers/ms5611/ms5611.cpp3
-rw-r--r--src/modules/mavlink/mavlink.c47
5 files changed, 29 insertions, 29 deletions
diff --git a/src/drivers/boards/px4fmu/px4fmu_init.c b/src/drivers/boards/px4fmu/px4fmu_init.c
index 212a92cfa..36af2298c 100644
--- a/src/drivers/boards/px4fmu/px4fmu_init.c
+++ b/src/drivers/boards/px4fmu/px4fmu_init.c
@@ -194,7 +194,7 @@ __EXPORT int nsh_archinitialize(void)
/* initial LED state */
drv_led_start();
led_off(LED_AMBER);
- led_on(LED_BLUE);
+ led_off(LED_BLUE);
/* Configure SPI-based devices */
diff --git a/src/drivers/hmc5883/hmc5883.cpp b/src/drivers/hmc5883/hmc5883.cpp
index 59e90d86c..ac3bdc132 100644
--- a/src/drivers/hmc5883/hmc5883.cpp
+++ b/src/drivers/hmc5883/hmc5883.cpp
@@ -1221,7 +1221,8 @@ start()
int fd;
if (g_dev != nullptr)
- errx(1, "already started");
+ /* if already started, the still command succeeded */
+ errx(0, "already started");
/* create the driver, attempt expansion bus first */
g_dev = new HMC5883(PX4_I2C_BUS_EXPANSION);
diff --git a/src/drivers/mpu6000/mpu6000.cpp b/src/drivers/mpu6000/mpu6000.cpp
index 220842536..8d9054a38 100644
--- a/src/drivers/mpu6000/mpu6000.cpp
+++ b/src/drivers/mpu6000/mpu6000.cpp
@@ -1063,7 +1063,8 @@ start()
int fd;
if (g_dev != nullptr)
- errx(1, "already started");
+ /* if already started, the still command succeeded */
+ errx(0, "already started");
/* create the driver */
g_dev = new MPU6000(1 /* XXX magic number */, (spi_dev_e)PX4_SPIDEV_MPU);
diff --git a/src/drivers/ms5611/ms5611.cpp b/src/drivers/ms5611/ms5611.cpp
index 59ab5936e..c13b65d5a 100644
--- a/src/drivers/ms5611/ms5611.cpp
+++ b/src/drivers/ms5611/ms5611.cpp
@@ -969,7 +969,8 @@ start()
int fd;
if (g_dev != nullptr)
- errx(1, "already started");
+ /* if already started, the still command succeeded */
+ errx(0, "already started");
/* create the driver */
g_dev = new MS5611(MS5611_BUS);
diff --git a/src/modules/mavlink/mavlink.c b/src/modules/mavlink/mavlink.c
index 7c1c4b175..919d01561 100644
--- a/src/modules/mavlink/mavlink.c
+++ b/src/modules/mavlink/mavlink.c
@@ -420,12 +420,12 @@ int mavlink_open_uart(int baud, const char *uart_name, struct termios *uart_conf
case 921600: speed = B921600; break;
default:
- fprintf(stderr, "[mavlink] ERROR: Unsupported baudrate: %d\n\tsupported examples:\n\n\t9600\n19200\n38400\n57600\n115200\n230400\n460800\n921600\n\n", baud);
+ warnx("ERROR: Unsupported baudrate: %d\n\tsupported examples:\n\n\t9600\n19200\n38400\n57600\n115200\n230400\n460800\n921600\n\n", baud);
return -EINVAL;
}
/* open uart */
- printf("[mavlink] UART is %s, baudrate is %d\n", uart_name, baud);
+ warnx("UART is %s, baudrate is %d\n", uart_name, baud);
uart = open(uart_name, O_RDWR | O_NOCTTY);
/* Try to set baud rate */
@@ -433,37 +433,35 @@ int mavlink_open_uart(int baud, const char *uart_name, struct termios *uart_conf
int termios_state;
*is_usb = false;
- /* make some wild guesses including that USB serial is indicated by either /dev/ttyACM0 or /dev/console */
- if (strcmp(uart_name, "/dev/ttyACM0") != OK && strcmp(uart_name, "/dev/console") != OK) {
- /* Back up the original uart configuration to restore it after exit */
- if ((termios_state = tcgetattr(uart, uart_config_original)) < 0) {
- fprintf(stderr, "[mavlink] ERROR getting baudrate / termios config for %s: %d\n", uart_name, termios_state);
- close(uart);
- return -1;
- }
+ /* Back up the original uart configuration to restore it after exit */
+ if ((termios_state = tcgetattr(uart, uart_config_original)) < 0) {
+ warnx("ERROR get termios config %s: %d\n", uart_name, termios_state);
+ close(uart);
+ return -1;
+ }
+
+ /* Fill the struct for the new configuration */
+ tcgetattr(uart, &uart_config);
- /* Fill the struct for the new configuration */
- tcgetattr(uart, &uart_config);
+ /* Clear ONLCR flag (which appends a CR for every LF) */
+ uart_config.c_oflag &= ~ONLCR;
- /* Clear ONLCR flag (which appends a CR for every LF) */
- uart_config.c_oflag &= ~ONLCR;
+ /* USB serial is indicated by /dev/ttyACM0*/
+ if (strcmp(uart_name, "/dev/ttyACM0") != OK && strcmp(uart_name, "/dev/ttyACM1") != OK) {
/* Set baud rate */
if (cfsetispeed(&uart_config, speed) < 0 || cfsetospeed(&uart_config, speed) < 0) {
- fprintf(stderr, "[mavlink] ERROR setting baudrate / termios config for %s: %d (cfsetispeed, cfsetospeed)\n", uart_name, termios_state);
+ warnx("ERROR setting baudrate / termios config for %s: %d (cfsetispeed, cfsetospeed)\n", uart_name, termios_state);
close(uart);
return -1;
}
+ }
- if ((termios_state = tcsetattr(uart, TCSANOW, &uart_config)) < 0) {
- fprintf(stderr, "[mavlink] ERROR setting baudrate / termios config for %s (tcsetattr)\n", uart_name);
- close(uart);
- return -1;
- }
-
- } else {
- *is_usb = true;
+ if ((termios_state = tcsetattr(uart, TCSANOW, &uart_config)) < 0) {
+ warnx("ERROR setting baudrate / termios config for %s (tcsetattr)\n", uart_name);
+ close(uart);
+ return -1;
}
return uart;
@@ -751,8 +749,7 @@ int mavlink_thread_main(int argc, char *argv[])
pthread_join(uorb_receive_thread, NULL);
/* Reset the UART flags to original state */
- if (!usb_uart)
- tcsetattr(uart, TCSANOW, &uart_config_original);
+ tcsetattr(uart, TCSANOW, &uart_config_original);
thread_running = false;