diff options
author | Lorenz Meier <lm@inf.ethz.ch> | 2013-07-18 13:18:42 +0200 |
---|---|---|
committer | Lorenz Meier <lm@inf.ethz.ch> | 2013-07-18 13:18:42 +0200 |
commit | a4d0594bd73d6ec24c320380674d94c59a141595 (patch) | |
tree | 1f3a082db48270a4a307654b447e3db3db8b56d7 /src/modules | |
parent | 47dd3fdae1d626a28c273946d45ea8c79fb4b76f (diff) | |
parent | 8d1abf4aa441e1c6c886e8af6ecaab2c3ca6e255 (diff) | |
download | px4-firmware-a4d0594bd73d6ec24c320380674d94c59a141595.tar.gz px4-firmware-a4d0594bd73d6ec24c320380674d94c59a141595.tar.bz2 px4-firmware-a4d0594bd73d6ec24c320380674d94c59a141595.zip |
Merge branch 'master' into autostart
Diffstat (limited to 'src/modules')
-rw-r--r-- | src/modules/commander/commander.c | 2 | ||||
-rw-r--r-- | src/modules/mavlink/mavlink.c | 47 | ||||
-rw-r--r-- | src/modules/systemlib/airspeed.c | 4 |
3 files changed, 25 insertions, 28 deletions
diff --git a/src/modules/commander/commander.c b/src/modules/commander/commander.c index 928d9b85e..8e5e36712 100644 --- a/src/modules/commander/commander.c +++ b/src/modules/commander/commander.c @@ -282,7 +282,7 @@ void tune_error(void) void do_rc_calibration(int status_pub, struct vehicle_status_s *status) { - if (current_status.offboard_control_signal_lost) { + if (current_status.rc_signal_lost) { mavlink_log_critical(mavlink_fd, "TRIM CAL: ABORT. No RC signal."); return; } 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; diff --git a/src/modules/systemlib/airspeed.c b/src/modules/systemlib/airspeed.c index 15bb833a9..e01cc4dda 100644 --- a/src/modules/systemlib/airspeed.c +++ b/src/modules/systemlib/airspeed.c @@ -62,7 +62,7 @@ float calc_indicated_airspeed(float differential_pressure) if (differential_pressure > 0) { return sqrtf((2.0f*differential_pressure) / CONSTANTS_AIR_DENSITY_SEA_LEVEL_15C); } else { - return -sqrtf((2.0f*fabs(differential_pressure)) / CONSTANTS_AIR_DENSITY_SEA_LEVEL_15C); + return -sqrtf((2.0f*fabsf(differential_pressure)) / CONSTANTS_AIR_DENSITY_SEA_LEVEL_15C); } } @@ -106,6 +106,6 @@ float calc_true_airspeed(float total_pressure, float static_pressure, float temp return sqrtf((2.0f*(pressure_difference)) / density); } else { - return -sqrtf((2.0f*fabs(pressure_difference)) / density); + return -sqrtf((2.0f*fabsf(pressure_difference)) / density); } } |