Browse Source

mavlink_onboard: major optimization, cleanup and minor fixes, WIP

sbg
Anton Babushkin 12 years ago
parent
commit
5e3bdd7789
  1. 2
      src/modules/mavlink/mavlink_receiver.cpp
  2. 2
      src/modules/mavlink/orb_listener.c
  3. 20
      src/modules/mavlink_onboard/mavlink.c
  4. 27
      src/modules/mavlink_onboard/mavlink_receiver.c

2
src/modules/mavlink/mavlink_receiver.cpp

@ -733,7 +733,7 @@ receive_thread(void *arg) @@ -733,7 +733,7 @@ receive_thread(void *arg)
mavlink_message_t msg;
prctl(PR_SET_NAME, "mavlink uart rcv", getpid());
prctl(PR_SET_NAME, "mavlink_uart_rcv", getpid());
while (!thread_should_exit) {

2
src/modules/mavlink/orb_listener.c

@ -695,7 +695,7 @@ static void * @@ -695,7 +695,7 @@ static void *
uorb_receive_thread(void *arg)
{
/* Set thread name */
prctl(PR_SET_NAME, "mavlink orb rcv", getpid());
prctl(PR_SET_NAME, "mavlink_orb_rcv", getpid());
/*
* set up poll to block for new data,

20
src/modules/mavlink_onboard/mavlink.c

@ -167,12 +167,12 @@ int mavlink_open_uart(int baud, const char *uart_name, struct termios *uart_conf @@ -167,12 +167,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", baud);
return -EINVAL;
}
/* open uart */
printf("[mavlink] UART is %s, baudrate is %d\n", uart_name, baud);
warnx("UART is %s, baudrate is %d", uart_name, baud);
uart = open(uart_name, O_RDWR | O_NOCTTY);
/* Try to set baud rate */
@ -183,7 +183,7 @@ int mavlink_open_uart(int baud, const char *uart_name, struct termios *uart_conf @@ -183,7 +183,7 @@ int mavlink_open_uart(int baud, const char *uart_name, struct termios *uart_conf
if (strcmp(uart_name, "/dev/ttyACM0") != 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);
warnx("ERROR getting baudrate / termios config for %s: %d", uart_name, termios_state);
close(uart);
return -1;
}
@ -196,14 +196,14 @@ int mavlink_open_uart(int baud, const char *uart_name, struct termios *uart_conf @@ -196,14 +196,14 @@ int mavlink_open_uart(int baud, const char *uart_name, struct termios *uart_conf
/* 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)", 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);
warnx("ERROR setting baudrate / termios config for %s (tcsetattr)", uart_name);
close(uart);
return -1;
}
@ -481,9 +481,9 @@ int mavlink_thread_main(int argc, char *argv[]) @@ -481,9 +481,9 @@ int mavlink_thread_main(int argc, char *argv[])
static void
usage()
{
fprintf(stderr, "usage: mavlink start [-d <devicename>] [-b <baud rate>]\n"
" mavlink stop\n"
" mavlink status\n");
fprintf(stderr, "usage: mavlink_onboard start [-d <devicename>] [-b <baud rate>]\n"
" mavlink_onboard stop\n"
" mavlink_onboard status\n");
exit(1);
}
@ -499,7 +499,7 @@ int mavlink_onboard_main(int argc, char *argv[]) @@ -499,7 +499,7 @@ int mavlink_onboard_main(int argc, char *argv[])
/* this is not an error */
if (thread_running)
errx(0, "mavlink already running\n");
errx(0, "already running");
thread_should_exit = false;
mavlink_task = task_spawn_cmd("mavlink_onboard",
@ -516,7 +516,7 @@ int mavlink_onboard_main(int argc, char *argv[]) @@ -516,7 +516,7 @@ int mavlink_onboard_main(int argc, char *argv[])
while (thread_running) {
usleep(200000);
}
warnx("terminated.");
warnx("terminated");
exit(0);
}

27
src/modules/mavlink_onboard/mavlink_receiver.c

@ -104,7 +104,7 @@ handle_message(mavlink_message_t *msg) @@ -104,7 +104,7 @@ handle_message(mavlink_message_t *msg)
//check for MAVLINK terminate command
if (cmd_mavlink.command == MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN && ((int)cmd_mavlink.param1) == 3) {
/* This is the link shutdown command, terminate mavlink */
printf("[mavlink] Terminating .. \n");
warnx("terminating...");
fflush(stdout);
usleep(50000);
@ -284,28 +284,33 @@ receive_thread(void *arg) @@ -284,28 +284,33 @@ receive_thread(void *arg)
int uart_fd = *((int*)arg);
const int timeout = 1000;
uint8_t ch;
uint8_t buf[32];
mavlink_message_t msg;
prctl(PR_SET_NAME, "mavlink offb rcv", getpid());
while (!thread_should_exit) {
prctl(PR_SET_NAME, "mavlink_onboard_rcv", getpid());
struct pollfd fds[] = { { .fd = uart_fd, .events = POLLIN } };
ssize_t nread = 0;
while (!thread_should_exit) {
if (poll(fds, 1, timeout) > 0) {
/* non-blocking read until buffer is empty */
int nread = 0;
if (nread < sizeof(buf)) {
/* to avoid reading very small chunks wait for data before reading */
usleep(1000);
}
do {
nread = read(uart_fd, &ch, 1);
/* non-blocking read. read may return negative values */
ssize_t nread = read(uart_fd, buf, sizeof(buf));
if (mavlink_parse_char(chan, ch, &msg, &status)) { //parse the char
/* if read failed, this loop won't execute */
for (ssize_t i = 0; i < nread; i++) {
if (mavlink_parse_char(chan, buf[i], &msg, &status)) {
/* handle generic messages and commands */
handle_message(&msg);
}
} while (nread > 0);
}
}
}

Loading…
Cancel
Save