From 13dd993e016e3642790802c21c9378710f0c00c6 Mon Sep 17 00:00:00 2001 From: Mark Charlebois Date: Tue, 9 Jun 2015 16:32:22 -0700 Subject: [PATCH] Nuttx: mavlink fixes Needed to ifdef SITL functionality not supoprted in NuttX build. Signed-off-by: Mark Charlebois --- src/modules/mavlink/mavlink_main.cpp | 4 ++++ src/modules/mavlink/mavlink_main.h | 4 ++-- 2 files changed, 6 insertions(+), 2 deletions(-) diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index ef51f556ee..619922eec8 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -690,8 +690,10 @@ int Mavlink::mavlink_open_uart(int baud, const char *uart_name, struct termios * _is_usb_uart = true; } +#ifdef __PX4_LINUX /* Put in raw mode */ cfmakeraw(&uart_config); +#endif if ((termios_state = tcsetattr(_uart_fd, TCSANOW, &uart_config)) < 0) { warnx("ERR SET CONF %s\n", uart_name); @@ -942,6 +944,7 @@ Mavlink::resend_message(mavlink_message_t *msg) void Mavlink::init_udp() { +#ifdef __PX4_LINUX PX4_INFO("Setting up UDP w/port %d\n",_network_port); memset((char *)&_myaddr, 0, sizeof(_myaddr)); @@ -964,6 +967,7 @@ Mavlink::init_udp() // wait for client to connect to socket recvfrom(_socket_fd,inbuf,sizeof(inbuf),0,(struct sockaddr *)&_src_addr,&addrlen); +#endif } void diff --git a/src/modules/mavlink/mavlink_main.h b/src/modules/mavlink/mavlink_main.h index 72688af8f8..326182bbef 100644 --- a/src/modules/mavlink/mavlink_main.h +++ b/src/modules/mavlink/mavlink_main.h @@ -398,13 +398,13 @@ private: float _rate_rx; #ifdef __PX4_POSIX - int _socket_fd; struct sockaddr_in _myaddr; struct sockaddr_in _src_addr; +#endif + int _socket_fd; Protocol _protocol; unsigned short _network_port; -#endif struct telemetry_status_s _rstatus; ///< receive status