aboutsummaryrefslogtreecommitdiff
path: root/src/modules/mavlink/mavlink.c
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2013-07-15 15:02:45 +0200
committerLorenz Meier <lm@inf.ethz.ch>2013-07-15 15:02:45 +0200
commitbf2ff98856b7e6b107a7ec5bbde3b00e38713804 (patch)
treead11c218b7524826e45c58257cdaac12e8a1ac53 /src/modules/mavlink/mavlink.c
parent88389ea2554c6f56a4fdd86cdd86a1e7b6affc21 (diff)
parent17338ca61aa8a58c92ae621de94240ddd22f28a2 (diff)
downloadpx4-firmware-bf2ff98856b7e6b107a7ec5bbde3b00e38713804.tar.gz
px4-firmware-bf2ff98856b7e6b107a7ec5bbde3b00e38713804.tar.bz2
px4-firmware-bf2ff98856b7e6b107a7ec5bbde3b00e38713804.zip
Merged master
Diffstat (limited to 'src/modules/mavlink/mavlink.c')
-rw-r--r--src/modules/mavlink/mavlink.c7
1 files changed, 3 insertions, 4 deletions
diff --git a/src/modules/mavlink/mavlink.c b/src/modules/mavlink/mavlink.c
index f6c371c7c..a2758a45c 100644
--- a/src/modules/mavlink/mavlink.c
+++ b/src/modules/mavlink/mavlink.c
@@ -49,7 +49,6 @@
#include <mqueue.h>
#include <string.h>
#include "mavlink_bridge_header.h"
-#include <v1.0/common/mavlink.h>
#include <drivers/drv_hrt.h>
#include <time.h>
#include <float.h>
@@ -464,7 +463,7 @@ int mavlink_open_uart(int baud, const char *uart_name, struct termios *uart_conf
}
void
-mavlink_send_uart_bytes(mavlink_channel_t channel, uint8_t *ch, int length)
+mavlink_send_uart_bytes(mavlink_channel_t channel, const uint8_t *ch, int length)
{
write(uart, ch, (size_t)(sizeof(uint8_t) * length));
}
@@ -472,7 +471,7 @@ mavlink_send_uart_bytes(mavlink_channel_t channel, uint8_t *ch, int length)
/*
* Internal function to give access to the channel status for each channel
*/
-mavlink_status_t *mavlink_get_channel_status(uint8_t channel)
+extern mavlink_status_t *mavlink_get_channel_status(uint8_t channel)
{
static mavlink_status_t m_mavlink_status[MAVLINK_COMM_NUM_BUFFERS];
return &m_mavlink_status[channel];
@@ -481,7 +480,7 @@ mavlink_status_t *mavlink_get_channel_status(uint8_t channel)
/*
* Internal function to give access to the channel buffer for each channel
*/
-mavlink_message_t *mavlink_get_channel_buffer(uint8_t channel)
+extern mavlink_message_t *mavlink_get_channel_buffer(uint8_t channel)
{
static mavlink_message_t m_mavlink_buffer[MAVLINK_COMM_NUM_BUFFERS];
return &m_mavlink_buffer[channel];