ardupilot/libraries/GCS_MAVLink/GCS_MAVLink.h
tridge60@gmail.com ca8141cfb6 imported new MAVLink implementation
this new implementation reduces code size, and also reduces stack
usage, while avoiding the gcc union stack bug

Note that we will gain even more when we move to the new protocol
version, especially in terms of code size

git-svn-id: https://arducopter.googlecode.com/svn/trunk@3200 f9c3cf11-9bcb-44bc-f272-b75c42450872
2011-08-31 05:23:18 +00:00

88 lines
1.8 KiB
C

// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*-
/// @file GCS_MAVLink.h
/// @brief One size fits all header for MAVLink integration.
#ifndef GCS_MAVLink_h
#define GCS_MAVLink_h
#include <Stream.h>
#define MAVLINK_COMM_NUM_BUFFERS 2
#include "include/mavlink_types.h"
/// MAVLink stream used for HIL interaction
extern Stream *mavlink_comm_0_port;
/// MAVLink stream used for ground control communication
extern Stream *mavlink_comm_1_port;
/// MAVLink system definition
extern mavlink_system_t mavlink_system;
/// Send a byte to the nominated MAVLink channel
///
/// @param chan Channel to send to
/// @param ch Byte to send
///
static inline void comm_send_ch(mavlink_channel_t chan, uint8_t ch)
{
switch(chan) {
case MAVLINK_COMM_0:
mavlink_comm_0_port->write(ch);
break;
case MAVLINK_COMM_1:
mavlink_comm_1_port->write(ch);
break;
default:
break;
}
}
/// Read a byte from the nominated MAVLink channel
///
/// @param chan Channel to receive on
/// @returns Byte read
///
static inline uint8_t comm_receive_ch(mavlink_channel_t chan)
{
uint8_t data = 0;
switch(chan) {
case MAVLINK_COMM_0:
data = mavlink_comm_0_port->read();
break;
case MAVLINK_COMM_1:
data = mavlink_comm_1_port->read();
break;
default:
break;
}
return data;
}
/// Check for available data on the nominated MAVLink channel
///
/// @param chan Channel to check
/// @returns Number of bytes available
static inline uint16_t comm_get_available(mavlink_channel_t chan)
{
uint16_t bytes = 0;
switch(chan) {
case MAVLINK_COMM_0:
bytes = mavlink_comm_0_port->available();
break;
case MAVLINK_COMM_1:
bytes = mavlink_comm_1_port->available();
break;
default:
break;
}
return bytes;
}
#define MAVLINK_USE_CONVENIENCE_FUNCTIONS
#include "include/ardupilotmega/mavlink.h"
#endif // GCS_MAVLink_h