mavlink协议移植问题
mavlink源代码是一个代码库,使用的时候只需要将mavlink.h头文件包含到工程项目中即可。
mavlink通信协议是无状态的连接,一般采用心跳消息跟踪系统是否存在。请确保每60、30、10或1秒发送心跳(建议使用1HZ),一旦心跳到达则视为系统已经连接。
快速整合方法: 发送数据例程(这个例子需要的代码比较多)
/* The default UART header for your MCU */
#include "uart.h"
#include <mavlink/v1./common/mavlink.h> mavlink_system_t mavlink_system; mavlink_system.sysid = ; ///< ID 20 for this airplane
mavlink_system.compid = MAV_COMP_ID_IMU; ///< The component sending the message is the IMU, it could be also a Linux process // Define the system type, in this case an airplane
uint8_t system_type = MAV_TYPE_FIXED_WING;
uint8_t autopilot_type = MAV_AUTOPILOT_GENERIC; uint8_t system_mode = MAV_MODE_PREFLIGHT; ///< Booting up
uint32_t custom_mode = 0; ///< Custom mode, can be defined by user/adopter
uint8_t system_state = MAV_STATE_STANDBY; ///< System ready for flight // Initialize the required buffers
mavlink_message_t msg;
uint8_t buf[MAVLINK_MAX_PACKET_LEN]; // Pack the message
mavlink_msg_heartbeat_pack(mavlink_system.sysid, mavlink_system.compid, &msg, system_type, autopilot_type, system_mode, custom_mode, system_state); // Copy the message to the send buffer
uint16_t len = mavlink_msg_to_send_buffer(buf, &msg); // Send the message with the standard UART send function
// uart0_send might be named differently depending on
// the individual microcontroller / library in use.
uart0_send(buf, len);
接收数据例程:此段代码运行效率比较低,所以建议在主循环中运行该函数,并且尽快清空USART缓冲区。
#include <mavlink/v1./common/mavlink.h> // Example variable, by declaring them static they're persistent
// and will thus track the system state
static int packet_drops = ;
static int mode = MAV_MODE_UNINIT; /* Defined in mavlink_types.h, which is included by mavlink.h */ /**
* @brief Receive communication packets and handle them
*
* This function decodes packets on the protocol level and also handles
* their value by calling the appropriate functions.
*/
static void communication_receive(void)
{
mavlink_message_t msg;
mavlink_status_t status; // COMMUNICATION THROUGH EXTERNAL UART PORT (XBee serial) while(uart0_char_available())
{
uint8_t c = uart0_get_char();
// Try to get a new message
if(mavlink_parse_char(MAVLINK_COMM_0, c, &msg, &status)) {
// Handle message switch(msg.msgid)
{
case MAVLINK_MSG_ID_HEARTBEAT:
{
// E.g. read GCS heartbeat and go into
// comm lost mode if timer times out
}
break;
case MAVLINK_MSG_ID_COMMAND_LONG:
// EXECUTE ACTION
break;
default:
//Do nothing
break;
}
} // And get the next one
} // Update global packet drops counter
packet_drops += status.packet_rx_drop_count;
} 利用适配器函数减少代码 #include "your_mavlink_bridge_header.h"
/* You have to #define MAVLINK_USE_CONVENIENCE_FUNCTIONS in your_mavlink_bridge_header,
and you have to declare: mavlink_system_t mavlink_system;
these two variables will be used internally by the mavlink_msg_xx_send() functions.
Please see the section below for an example of such a bridge header. */
#include <mavlink.h> // Define the system type, in this case an airplane
int system_type = MAV_FIXED_WING;
// Send a heartbeat over UART0 including the system type
mavlink_msg_heartbeat_send(MAVLINK_COMM_0, system_type, MAV_AUTOPILOT_GENERIC, MAV_MODE_MANUAL_DISARMED, MAV_STATE_STANDBY); your_mavlink_bridge_header.h
/* MAVLink adapter header */
#ifndef YOUR_MAVLINK_BRIDGE_HEADER_H
#define YOUR_MAVLINK_BRIDGE_HEADER_H #define MAVLINK_USE_CONVENIENCE_FUNCTIONS #include <mavlink/v1./mavlink_types.h> /* Struct that stores the communication settings of this system.
you can also define / alter these settings elsewhere, as long
as they're included BEFORE mavlink.h.
So you can set the mavlink_system.sysid = 100; // System ID, 1-255
mavlink_system.compid = 50; // Component/Subsystem ID, 1-255 Lines also in your main.c, e.g. by reading these parameter from EEPROM.
*/
mavlink_system_t mavlink_system;
mavlink_system.sysid = ; // System ID, 1-255
mavlink_system.compid = ; // Component/Subsystem ID, 1-255 /**
* @brief Send one char (uint8_t) over a comm channel
*
* @param chan MAVLink channel to use, usually MAVLINK_COMM_0 = UART0
* @param ch Character to send
*/
static inline void comm_send_ch(mavlink_channel_t chan, uint8_t ch)
{
if (chan == MAVLINK_COMM_0)
{
uart0_transmit(ch);
}
if (chan == MAVLINK_COMM_1)
{
uart1_transmit(ch);
}
} #endif /* YOUR_MAVLINK_BRIDGE_HEADER_H */