2013-05-29 20:50:57 -03:00
|
|
|
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
2010-11-25 02:38:18 -04:00
|
|
|
|
|
|
|
/// @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
|
|
|
|
2012-09-18 15:08:57 -03:00
|
|
|
#include <AP_HAL.h>
|
2013-09-19 03:27:14 -03:00
|
|
|
#include <AP_Param.h>
|
2013-07-14 03:56:58 -03:00
|
|
|
#include <AP_Math.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
|
2012-08-30 23:09:52 -03:00
|
|
|
#define MAVLINK_SEPARATE_HELPERS
|
2011-09-17 22:03:27 -03:00
|
|
|
|
2013-01-08 00:58:40 -04:00
|
|
|
#define MAVLINK_SEND_UART_BYTES(chan, buf, len) comm_send_buffer(chan, buf, len)
|
|
|
|
|
2013-01-10 06:28:07 -04:00
|
|
|
// define our own MAVLINK_MESSAGE_CRC() macro to allow it to be put
|
|
|
|
// into progmem
|
|
|
|
#define MAVLINK_MESSAGE_CRC(msgid) mavlink_get_message_crc(msgid)
|
|
|
|
|
2013-01-08 00:58:40 -04:00
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1 || CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
|
|
|
#include <util/crc16.h>
|
|
|
|
#define HAVE_CRC_ACCUMULATE
|
2013-11-22 04:17:34 -04:00
|
|
|
// only two telemetry ports on APM1/APM2
|
|
|
|
#define MAVLINK_COMM_NUM_BUFFERS 2
|
|
|
|
#else
|
|
|
|
// allow three telemetry ports on other boards
|
|
|
|
#define MAVLINK_COMM_NUM_BUFFERS 3
|
2013-01-08 00:58:40 -04:00
|
|
|
#endif
|
|
|
|
|
2014-07-25 02:46:20 -03:00
|
|
|
/*
|
|
|
|
The MAVLink protocol code generator does its own alignment, so
|
|
|
|
alignment cast warnings can be ignored
|
|
|
|
*/
|
|
|
|
#pragma GCC diagnostic push
|
|
|
|
#pragma GCC diagnostic ignored "-Wcast-align"
|
|
|
|
|
2012-07-04 21:55:58 -03:00
|
|
|
#include "include/mavlink/v1.0/ardupilotmega/version.h"
|
2011-09-04 05:51:51 -03:00
|
|
|
|
2014-03-10 23:48:25 -03:00
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1 || CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
2012-12-03 08:28:23 -04:00
|
|
|
// this allows us to make mavlink_message_t much smaller. It means we
|
|
|
|
// can't support the largest messages in common.xml, but we don't need
|
2014-03-10 23:48:25 -03:00
|
|
|
// those for APM1/APM2
|
2013-11-22 00:08:18 -04:00
|
|
|
#define MAVLINK_MAX_PAYLOAD_LEN 104
|
2014-03-10 23:48:25 -03:00
|
|
|
#else
|
|
|
|
#define MAVLINK_MAX_PAYLOAD_LEN 255
|
|
|
|
#endif
|
2011-09-04 05:51:51 -03:00
|
|
|
|
2012-07-04 21:55:58 -03:00
|
|
|
#include "include/mavlink/v1.0/mavlink_types.h"
|
2010-11-25 02:38:18 -04:00
|
|
|
|
2013-11-22 04:17:34 -04:00
|
|
|
/// MAVLink stream used for uartA
|
2015-01-25 21:35:29 -04:00
|
|
|
extern AP_HAL::UARTDriver *mavlink_comm_0_port;
|
2010-11-25 02:38:18 -04:00
|
|
|
|
2013-11-22 04:17:34 -04:00
|
|
|
/// MAVLink stream used for uartC
|
2015-01-25 21:35:29 -04:00
|
|
|
extern AP_HAL::UARTDriver *mavlink_comm_1_port;
|
2010-11-25 02:38:18 -04:00
|
|
|
|
2013-11-22 04:17:34 -04:00
|
|
|
#if MAVLINK_COMM_NUM_BUFFERS > 2
|
|
|
|
/// MAVLink stream used for uartD
|
2015-01-25 21:35:29 -04:00
|
|
|
extern AP_HAL::UARTDriver *mavlink_comm_2_port;
|
2013-11-22 04:17:34 -04:00
|
|
|
#endif
|
|
|
|
|
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;
|
2013-11-22 04:17:34 -04:00
|
|
|
#if MAVLINK_COMM_NUM_BUFFERS > 2
|
|
|
|
case MAVLINK_COMM_2:
|
|
|
|
mavlink_comm_2_port->write(ch);
|
|
|
|
break;
|
|
|
|
#endif
|
2011-05-04 16:12:27 -03:00
|
|
|
default:
|
|
|
|
break;
|
2010-11-25 02:38:18 -04:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2013-01-08 00:31:01 -04:00
|
|
|
void comm_send_buffer(mavlink_channel_t chan, const uint8_t *buf, uint8_t len);
|
|
|
|
|
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
|
|
|
|
///
|
2014-04-03 23:19:15 -03:00
|
|
|
uint8_t comm_receive_ch(mavlink_channel_t chan);
|
2010-11-25 02:38:18 -04:00
|
|
|
|
|
|
|
/// Check for available data on the nominated MAVLink channel
|
|
|
|
///
|
|
|
|
/// @param chan Channel to check
|
|
|
|
/// @returns Number of bytes available
|
2014-04-03 23:19:15 -03:00
|
|
|
uint16_t comm_get_available(mavlink_channel_t chan);
|
2010-11-25 02:38:18 -04:00
|
|
|
|
2011-09-04 18:23:24 -03:00
|
|
|
|
|
|
|
/// Check for available transmit space on the nominated MAVLink channel
|
|
|
|
///
|
|
|
|
/// @param chan Channel to check
|
2012-09-24 18:20:43 -03:00
|
|
|
/// @returns Number of bytes available
|
2014-04-03 23:19:15 -03:00
|
|
|
uint16_t comm_get_txspace(mavlink_channel_t chan);
|
2011-09-04 18:23:24 -03:00
|
|
|
|
2013-01-08 00:58:40 -04:00
|
|
|
#ifdef HAVE_CRC_ACCUMULATE
|
|
|
|
// use the AVR C library implementation. This is a bit over twice as
|
|
|
|
// fast as the C version
|
|
|
|
static inline void crc_accumulate(uint8_t data, uint16_t *crcAccum)
|
|
|
|
{
|
|
|
|
*crcAccum = _crc_ccitt_update(*crcAccum, data);
|
|
|
|
}
|
|
|
|
#endif
|
|
|
|
|
2013-03-21 07:55:12 -03:00
|
|
|
/*
|
|
|
|
return true if the MAVLink parser is idle, so there is no partly parsed
|
|
|
|
MAVLink message being processed
|
|
|
|
*/
|
|
|
|
bool comm_is_idle(mavlink_channel_t chan);
|
|
|
|
|
2010-11-25 02:38:18 -04:00
|
|
|
#define MAVLINK_USE_CONVENIENCE_FUNCTIONS
|
2012-07-04 21:55:58 -03:00
|
|
|
#include "include/mavlink/v1.0/ardupilotmega/mavlink.h"
|
2010-11-25 02:38:18 -04:00
|
|
|
|
2012-08-08 23:22:46 -03:00
|
|
|
// return a MAVLink variable type given a AP_Param type
|
|
|
|
uint8_t mav_var_type(enum ap_var_type t);
|
|
|
|
|
2013-01-10 06:28:07 -04:00
|
|
|
// return CRC byte for a mavlink message ID
|
|
|
|
uint8_t mavlink_get_message_crc(uint8_t msgid);
|
|
|
|
|
2013-05-08 20:27:58 -03:00
|
|
|
// severity levels used in STATUSTEXT messages
|
|
|
|
enum gcs_severity {
|
|
|
|
SEVERITY_LOW=1,
|
|
|
|
SEVERITY_MEDIUM,
|
|
|
|
SEVERITY_HIGH,
|
|
|
|
SEVERITY_CRITICAL,
|
|
|
|
SEVERITY_USER_RESPONSE
|
|
|
|
};
|
|
|
|
|
2014-07-25 02:46:20 -03:00
|
|
|
#pragma GCC diagnostic pop
|
|
|
|
|
2010-11-25 02:38:18 -04:00
|
|
|
#endif // GCS_MAVLink_h
|