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.
|
2016-02-17 21:25:55 -04:00
|
|
|
#pragma once
|
2010-11-25 02:38:18 -04:00
|
|
|
|
2015-08-11 03:28:46 -03:00
|
|
|
#include <AP_HAL/AP_HAL.h>
|
|
|
|
#include <AP_Param/AP_Param.h>
|
|
|
|
#include <AP_Math/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)
|
|
|
|
|
2016-04-19 00:49:12 -03:00
|
|
|
// allow five telemetry ports
|
|
|
|
#define MAVLINK_COMM_NUM_BUFFERS 5
|
2013-01-08 00:58:40 -04:00
|
|
|
|
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
|
|
|
#define MAVLINK_MAX_PAYLOAD_LEN 255
|
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-05-15 02:40:23 -03:00
|
|
|
extern AP_HAL::UARTDriver *mavlink_comm_port[MAVLINK_COMM_NUM_BUFFERS];
|
2015-05-02 09:38:07 -03:00
|
|
|
|
2010-11-25 02:38:18 -04:00
|
|
|
/// MAVLink system definition
|
|
|
|
extern mavlink_system_t mavlink_system;
|
|
|
|
|
2016-03-28 11:33:59 -03:00
|
|
|
/// Sanity check MAVLink channel
|
|
|
|
///
|
|
|
|
/// @param chan Channel to send to
|
|
|
|
static inline bool valid_channel(mavlink_channel_t chan)
|
|
|
|
{
|
|
|
|
#pragma clang diagnostic push
|
|
|
|
#pragma clang diagnostic ignored "-Wtautological-constant-out-of-range-compare"
|
2016-03-29 23:45:09 -03:00
|
|
|
return chan < MAVLINK_COMM_NUM_BUFFERS;
|
2016-03-28 11:33:59 -03:00
|
|
|
#pragma clang diagnostic pop
|
|
|
|
}
|
|
|
|
|
2010-11-25 02:38:18 -04:00
|
|
|
/// 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)
|
|
|
|
{
|
2016-03-28 11:33:59 -03:00
|
|
|
if (!valid_channel(chan)) {
|
2015-05-15 02:40:23 -03:00
|
|
|
return;
|
|
|
|
}
|
|
|
|
mavlink_comm_port[chan]->write(ch);
|
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-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);
|
|
|
|
|
2014-07-25 02:46:20 -03:00
|
|
|
#pragma GCC diagnostic pop
|