2010-11-25 02:38:18 -04:00
|
|
|
// -*- 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
|
2010-12-05 05:48:58 -04:00
|
|
|
#define GCS_MAVLink_h
|
2010-11-25 02:38:18 -04:00
|
|
|
|
2011-09-04 19:52:22 -03:00
|
|
|
#include <BetterStream.h>
|
2011-08-31 02:23:18 -03:00
|
|
|
|
2012-04-24 09:17:20 -03:00
|
|
|
// we have separate helpers disabled to make it possible
|
|
|
|
// to select MAVLink 1.0 in the arduino GUI build
|
|
|
|
//#define MAVLINK_SEPARATE_HELPERS
|
2011-09-17 22:03:27 -03:00
|
|
|
|
2011-10-16 04:00:12 -03:00
|
|
|
#ifdef MAVLINK10
|
2012-04-19 16:46:29 -03:00
|
|
|
# include "include/mavlink/v1.0/ardupilotmega/version.h"
|
2011-10-16 04:00:12 -03:00
|
|
|
#else
|
2012-04-19 16:46:29 -03:00
|
|
|
# include "include/mavlink/v0.9/ardupilotmega/version.h"
|
2011-10-16 04:00:12 -03:00
|
|
|
#endif
|
2011-09-04 05:51:51 -03:00
|
|
|
|
|
|
|
// this allows us to make mavlink_message_t much smaller
|
|
|
|
#define MAVLINK_MAX_PAYLOAD_LEN MAVLINK_MAX_DIALECT_PAYLOAD_SIZE
|
|
|
|
|
2011-08-31 02:23:18 -03:00
|
|
|
#define MAVLINK_COMM_NUM_BUFFERS 2
|
2011-10-16 04:00:12 -03:00
|
|
|
#ifdef MAVLINK10
|
2012-04-19 16:46:29 -03:00
|
|
|
# include "include/mavlink/v1.0/mavlink_types.h"
|
2011-10-16 04:00:12 -03:00
|
|
|
#else
|
2012-04-19 16:46:29 -03:00
|
|
|
# include "include/mavlink/v0.9/mavlink_types.h"
|
2011-10-16 04:00:12 -03:00
|
|
|
#endif
|
2010-11-25 02:38:18 -04:00
|
|
|
|
|
|
|
/// MAVLink stream used for HIL interaction
|
2011-09-04 19:52:22 -03:00
|
|
|
extern BetterStream *mavlink_comm_0_port;
|
2010-11-25 02:38:18 -04:00
|
|
|
|
|
|
|
/// MAVLink stream used for ground control communication
|
2011-09-04 19:52:22 -03:00
|
|
|
extern BetterStream *mavlink_comm_1_port;
|
2010-11-25 02:38:18 -04:00
|
|
|
|
|
|
|
/// 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;
|
2011-05-04 16:12:27 -03:00
|
|
|
default:
|
|
|
|
break;
|
2010-11-25 02:38:18 -04:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
/// 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;
|
2011-05-04 16:12:27 -03:00
|
|
|
default:
|
|
|
|
break;
|
2010-11-25 02:38:18 -04:00
|
|
|
}
|
|
|
|
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;
|
2011-05-04 16:12:27 -03:00
|
|
|
default:
|
|
|
|
break;
|
2010-11-25 02:38:18 -04:00
|
|
|
}
|
|
|
|
return bytes;
|
|
|
|
}
|
|
|
|
|
2011-09-04 18:23:24 -03:00
|
|
|
|
|
|
|
/// Check for available transmit space on the nominated MAVLink channel
|
|
|
|
///
|
|
|
|
/// @param chan Channel to check
|
|
|
|
/// @returns Number of bytes available, -1 for error
|
|
|
|
static inline int comm_get_txspace(mavlink_channel_t chan)
|
|
|
|
{
|
|
|
|
switch(chan) {
|
|
|
|
case MAVLINK_COMM_0:
|
|
|
|
return mavlink_comm_0_port->txspace();
|
|
|
|
break;
|
|
|
|
case MAVLINK_COMM_1:
|
|
|
|
return mavlink_comm_1_port->txspace();
|
|
|
|
break;
|
|
|
|
default:
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
return -1;
|
|
|
|
}
|
|
|
|
|
2010-11-25 02:38:18 -04:00
|
|
|
#define MAVLINK_USE_CONVENIENCE_FUNCTIONS
|
2011-10-16 04:00:12 -03:00
|
|
|
#ifdef MAVLINK10
|
2012-04-19 16:46:29 -03:00
|
|
|
# include "include/mavlink/v1.0/ardupilotmega/mavlink.h"
|
2011-10-16 04:00:12 -03:00
|
|
|
#else
|
2012-04-19 16:46:29 -03:00
|
|
|
# include "include/mavlink/v0.9/ardupilotmega/mavlink.h"
|
2011-10-16 04:00:12 -03:00
|
|
|
#endif
|
2010-11-25 02:38:18 -04:00
|
|
|
|
2011-09-24 09:40:07 -03:00
|
|
|
uint8_t mavlink_check_target(uint8_t sysid, uint8_t compid);
|
|
|
|
|
2010-11-25 02:38:18 -04:00
|
|
|
#endif // GCS_MAVLink_h
|