Commit 95950113 authored by LM's avatar LM

Updated packed MAVLink sources

parent d67528e0
/** @file
* @brief MAVLink comm protocol.
* @see http://qgroundcontrol.org/mavlink/
* Generated on Tuesday, August 9 2011, 16:16 UTC
* Generated on Tuesday, August 9 2011, 16:49 UTC
*/
#ifndef COMMON_H
#define COMMON_H
......@@ -236,8 +236,7 @@ enum MAV_CMD
#include "./mavlink_msg_change_operator_control.h"
#include "./mavlink_msg_change_operator_control_ack.h"
#include "./mavlink_msg_auth_key.h"
#include "./mavlink_msg_action_ack.h"
#include "./mavlink_msg_action.h"
#include "./mavlink_msg_cmd_ack.h"
#include "./mavlink_msg_set_mode.h"
#include "./mavlink_msg_set_nav_mode.h"
#include "./mavlink_msg_param_request_read.h"
......@@ -300,7 +299,7 @@ enum MAV_CMD
// MESSAGE CRC KEYS
#undef MAVLINK_MESSAGE_KEYS
#define MAVLINK_MESSAGE_KEYS { 71, 249, 232, 226, 76, 126, 117, 186, 0, 165, 44, 249, 133, 0, 0, 0, 0, 0, 0, 0, 112, 34, 81, 152, 0, 223, 28, 99, 28, 21, 243, 240, 204, 21, 111, 43, 192, 234, 22, 197, 192, 192, 166, 34, 233, 34, 166, 158, 142, 60, 10, 75, 249, 247, 234, 157, 125, 0, 0, 0, 85, 211, 62, 75, 185, 18, 42, 38, 0, 127, 200, 0, 0, 53, 251, 20, 22, 0, 0, 0, 0, 0, 0, 0, 0, 127, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 8, 238, 165, 0, 0, 0, 0, 0, 0, 0, 218, 218, 235, 0, 0, 0, 0, 0, 0, 225, 114, 0, 0, 0, 0, 0, 0, 0, 0, 221, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 171, 122, 0, 0, 0, 0, 0, 0, 0, 92, 114, 4, 169, 10, 0, 0, 0, 0, 0, 72, 62, 83, 0, 0, 0, 0, 0, 0, 0, 202, 144, 106, 254, 0, 0, 255, 185, 0, 14, 136, 53, 0, 212, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 43, 141, 211, 166 }
#define MAVLINK_MESSAGE_KEYS { 71, 249, 232, 226, 76, 126, 117, 186, 0, 144, 0, 249, 133, 0, 0, 0, 0, 0, 0, 0, 33, 34, 163, 45, 0, 223, 28, 99, 28, 21, 243, 240, 204, 21, 111, 43, 192, 234, 22, 197, 192, 192, 166, 34, 233, 34, 166, 158, 142, 60, 10, 75, 249, 247, 234, 157, 125, 0, 0, 0, 85, 211, 62, 75, 185, 18, 42, 38, 0, 127, 200, 0, 0, 53, 251, 20, 22, 0, 0, 0, 0, 0, 0, 0, 0, 127, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 8, 238, 165, 0, 0, 0, 0, 0, 0, 0, 218, 218, 235, 0, 0, 0, 0, 0, 0, 225, 114, 0, 0, 0, 0, 0, 0, 0, 0, 221, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 171, 122, 0, 0, 0, 0, 0, 0, 0, 92, 99, 4, 169, 10, 0, 0, 0, 0, 0, 52, 163, 16, 0, 0, 0, 0, 0, 0, 0, 200, 135, 217, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 43, 141, 211, 144 }
#ifdef __cplusplus
}
......
/** @file
* @brief MAVLink comm protocol.
* @see http://pixhawk.ethz.ch/software/mavlink
* Generated on Tuesday, August 9 2011, 16:16 UTC
* Generated on Tuesday, August 9 2011, 16:49 UTC
*/
#ifndef MAVLINK_H
#define MAVLINK_H
......
// MESSAGE CMD_ACK PACKING
#define MAVLINK_MSG_ID_CMD_ACK 9
#define MAVLINK_MSG_ID_CMD_ACK_LEN 2
#define MAVLINK_MSG_9_LEN 2
typedef struct __mavlink_cmd_ack_t
{
uint8_t cmd; ///< The MAV_CMD ID
uint8_t result; ///< 0: Action DENIED, 1: Action executed
} mavlink_cmd_ack_t;
/**
* @brief Pack a cmd_ack message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param cmd The MAV_CMD ID
* @param result 0: Action DENIED, 1: Action executed
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_cmd_ack_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t cmd, uint8_t result)
{
mavlink_cmd_ack_t *p = (mavlink_cmd_ack_t *)&msg->payload[0];
msg->msgid = MAVLINK_MSG_ID_CMD_ACK;
p->cmd = cmd; // uint8_t:The MAV_CMD ID
p->result = result; // uint8_t:0: Action DENIED, 1: Action executed
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CMD_ACK_LEN);
}
/**
* @brief Pack a cmd_ack message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param cmd The MAV_CMD ID
* @param result 0: Action DENIED, 1: Action executed
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_cmd_ack_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t cmd, uint8_t result)
{
mavlink_cmd_ack_t *p = (mavlink_cmd_ack_t *)&msg->payload[0];
msg->msgid = MAVLINK_MSG_ID_CMD_ACK;
p->cmd = cmd; // uint8_t:The MAV_CMD ID
p->result = result; // uint8_t:0: Action DENIED, 1: Action executed
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CMD_ACK_LEN);
}
/**
* @brief Encode a cmd_ack struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param cmd_ack C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_cmd_ack_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_cmd_ack_t* cmd_ack)
{
return mavlink_msg_cmd_ack_pack(system_id, component_id, msg, cmd_ack->cmd, cmd_ack->result);
}
/**
* @brief Send a cmd_ack message
* @param chan MAVLink channel to send the message
*
* @param cmd The MAV_CMD ID
* @param result 0: Action DENIED, 1: Action executed
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_cmd_ack_send(mavlink_channel_t chan, uint8_t cmd, uint8_t result)
{
mavlink_header_t hdr;
mavlink_cmd_ack_t payload;
uint16_t checksum;
mavlink_cmd_ack_t *p = &payload;
p->cmd = cmd; // uint8_t:The MAV_CMD ID
p->result = result; // uint8_t:0: Action DENIED, 1: Action executed
hdr.STX = MAVLINK_STX;
hdr.len = MAVLINK_MSG_ID_CMD_ACK_LEN;
hdr.msgid = MAVLINK_MSG_ID_CMD_ACK;
hdr.sysid = mavlink_system.sysid;
hdr.compid = mavlink_system.compid;
hdr.seq = mavlink_get_channel_status(chan)->current_tx_seq;
mavlink_get_channel_status(chan)->current_tx_seq = hdr.seq + 1;
mavlink_send_mem(chan, (uint8_t *)&hdr.STX, MAVLINK_NUM_HEADER_BYTES );
crc_init(&checksum);
checksum = crc_calculate_mem((uint8_t *)&hdr.len, &checksum, MAVLINK_CORE_HEADER_LEN);
checksum = crc_calculate_mem((uint8_t *)&payload, &checksum, hdr.len );
hdr.ck_a = (uint8_t)(checksum & 0xFF); ///< Low byte
hdr.ck_b = (uint8_t)(checksum >> 8); ///< High byte
mavlink_send_mem(chan, (uint8_t *)&payload, hdr.len);
mavlink_send_mem(chan, (uint8_t *)&hdr.ck_a, MAVLINK_NUM_CHECKSUM_BYTES);
}
#endif
// MESSAGE CMD_ACK UNPACKING
/**
* @brief Get field cmd from cmd_ack message
*
* @return The MAV_CMD ID
*/
static inline uint8_t mavlink_msg_cmd_ack_get_cmd(const mavlink_message_t* msg)
{
mavlink_cmd_ack_t *p = (mavlink_cmd_ack_t *)&msg->payload[0];
return (uint8_t)(p->cmd);
}
/**
* @brief Get field result from cmd_ack message
*
* @return 0: Action DENIED, 1: Action executed
*/
static inline uint8_t mavlink_msg_cmd_ack_get_result(const mavlink_message_t* msg)
{
mavlink_cmd_ack_t *p = (mavlink_cmd_ack_t *)&msg->payload[0];
return (uint8_t)(p->result);
}
/**
* @brief Decode a cmd_ack message into a struct
*
* @param msg The message to decode
* @param cmd_ack C-struct to decode the message contents into
*/
static inline void mavlink_msg_cmd_ack_decode(const mavlink_message_t* msg, mavlink_cmd_ack_t* cmd_ack)
{
memcpy( cmd_ack, msg->payload, sizeof(mavlink_cmd_ack_t));
}
......@@ -9,7 +9,7 @@ typedef struct __mavlink_param_request_read_t
int16_t param_index; ///< Parameter index. Send -1 to use the param ID field as identifier
uint8_t target_system; ///< System ID
uint8_t target_component; ///< Component ID
uint8_t param_id[16]; ///< Onboard parameter id
char param_id[16]; ///< Onboard parameter id
} mavlink_param_request_read_t;
#define MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN 16
......@@ -26,14 +26,14 @@ typedef struct __mavlink_param_request_read_t
* @param param_index Parameter index. Send -1 to use the param ID field as identifier
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_param_request_read_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, const uint8_t* param_id, int16_t param_index)
static inline uint16_t mavlink_msg_param_request_read_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, const char* param_id, int16_t param_index)
{
mavlink_param_request_read_t *p = (mavlink_param_request_read_t *)&msg->payload[0];
msg->msgid = MAVLINK_MSG_ID_PARAM_REQUEST_READ;
p->target_system = target_system; // uint8_t:System ID
p->target_component = target_component; // uint8_t:Component ID
memcpy(p->param_id, param_id, sizeof(p->param_id)); // uint8_t[16]:Onboard parameter id
memcpy(p->param_id, param_id, sizeof(p->param_id)); // char[16]:Onboard parameter id
p->param_index = param_index; // int16_t:Parameter index. Send -1 to use the param ID field as identifier
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN);
......@@ -51,14 +51,14 @@ static inline uint16_t mavlink_msg_param_request_read_pack(uint8_t system_id, ui
* @param param_index Parameter index. Send -1 to use the param ID field as identifier
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_param_request_read_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, const uint8_t* param_id, int16_t param_index)
static inline uint16_t mavlink_msg_param_request_read_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, const char* param_id, int16_t param_index)
{
mavlink_param_request_read_t *p = (mavlink_param_request_read_t *)&msg->payload[0];
msg->msgid = MAVLINK_MSG_ID_PARAM_REQUEST_READ;
p->target_system = target_system; // uint8_t:System ID
p->target_component = target_component; // uint8_t:Component ID
memcpy(p->param_id, param_id, sizeof(p->param_id)); // uint8_t[16]:Onboard parameter id
memcpy(p->param_id, param_id, sizeof(p->param_id)); // char[16]:Onboard parameter id
p->param_index = param_index; // int16_t:Parameter index. Send -1 to use the param ID field as identifier
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN);
......@@ -89,7 +89,7 @@ static inline uint16_t mavlink_msg_param_request_read_encode(uint8_t system_id,
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_param_request_read_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const uint8_t* param_id, int16_t param_index)
static inline void mavlink_msg_param_request_read_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const char* param_id, int16_t param_index)
{
mavlink_header_t hdr;
mavlink_param_request_read_t payload;
......@@ -98,7 +98,7 @@ static inline void mavlink_msg_param_request_read_send(mavlink_channel_t chan, u
p->target_system = target_system; // uint8_t:System ID
p->target_component = target_component; // uint8_t:Component ID
memcpy(p->param_id, param_id, sizeof(p->param_id)); // uint8_t[16]:Onboard parameter id
memcpy(p->param_id, param_id, sizeof(p->param_id)); // char[16]:Onboard parameter id
p->param_index = param_index; // int16_t:Parameter index. Send -1 to use the param ID field as identifier
hdr.STX = MAVLINK_STX;
......@@ -150,7 +150,7 @@ static inline uint8_t mavlink_msg_param_request_read_get_target_component(const
*
* @return Onboard parameter id
*/
static inline uint16_t mavlink_msg_param_request_read_get_param_id(const mavlink_message_t* msg, uint8_t* param_id)
static inline uint16_t mavlink_msg_param_request_read_get_param_id(const mavlink_message_t* msg, char* param_id)
{
mavlink_param_request_read_t *p = (mavlink_param_request_read_t *)&msg->payload[0];
......
......@@ -9,7 +9,7 @@ typedef struct __mavlink_param_set_t
float param_value; ///< Onboard parameter value
uint8_t target_system; ///< System ID
uint8_t target_component; ///< Component ID
uint8_t param_id[16]; ///< Onboard parameter id
char param_id[16]; ///< Onboard parameter id
} mavlink_param_set_t;
#define MAVLINK_MSG_PARAM_SET_FIELD_PARAM_ID_LEN 16
......@@ -26,14 +26,14 @@ typedef struct __mavlink_param_set_t
* @param param_value Onboard parameter value
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_param_set_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, const uint8_t* param_id, float param_value)
static inline uint16_t mavlink_msg_param_set_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, const char* param_id, float param_value)
{
mavlink_param_set_t *p = (mavlink_param_set_t *)&msg->payload[0];
msg->msgid = MAVLINK_MSG_ID_PARAM_SET;
p->target_system = target_system; // uint8_t:System ID
p->target_component = target_component; // uint8_t:Component ID
memcpy(p->param_id, param_id, sizeof(p->param_id)); // uint8_t[16]:Onboard parameter id
memcpy(p->param_id, param_id, sizeof(p->param_id)); // char[16]:Onboard parameter id
p->param_value = param_value; // float:Onboard parameter value
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PARAM_SET_LEN);
......@@ -51,14 +51,14 @@ static inline uint16_t mavlink_msg_param_set_pack(uint8_t system_id, uint8_t com
* @param param_value Onboard parameter value
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_param_set_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, const uint8_t* param_id, float param_value)
static inline uint16_t mavlink_msg_param_set_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, const char* param_id, float param_value)
{
mavlink_param_set_t *p = (mavlink_param_set_t *)&msg->payload[0];
msg->msgid = MAVLINK_MSG_ID_PARAM_SET;
p->target_system = target_system; // uint8_t:System ID
p->target_component = target_component; // uint8_t:Component ID
memcpy(p->param_id, param_id, sizeof(p->param_id)); // uint8_t[16]:Onboard parameter id
memcpy(p->param_id, param_id, sizeof(p->param_id)); // char[16]:Onboard parameter id
p->param_value = param_value; // float:Onboard parameter value
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PARAM_SET_LEN);
......@@ -89,7 +89,7 @@ static inline uint16_t mavlink_msg_param_set_encode(uint8_t system_id, uint8_t c
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_param_set_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const uint8_t* param_id, float param_value)
static inline void mavlink_msg_param_set_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const char* param_id, float param_value)
{
mavlink_header_t hdr;
mavlink_param_set_t payload;
......@@ -98,7 +98,7 @@ static inline void mavlink_msg_param_set_send(mavlink_channel_t chan, uint8_t ta
p->target_system = target_system; // uint8_t:System ID
p->target_component = target_component; // uint8_t:Component ID
memcpy(p->param_id, param_id, sizeof(p->param_id)); // uint8_t[16]:Onboard parameter id
memcpy(p->param_id, param_id, sizeof(p->param_id)); // char[16]:Onboard parameter id
p->param_value = param_value; // float:Onboard parameter value
hdr.STX = MAVLINK_STX;
......@@ -150,7 +150,7 @@ static inline uint8_t mavlink_msg_param_set_get_target_component(const mavlink_m
*
* @return Onboard parameter id
*/
static inline uint16_t mavlink_msg_param_set_get_param_id(const mavlink_message_t* msg, uint8_t* param_id)
static inline uint16_t mavlink_msg_param_set_get_param_id(const mavlink_message_t* msg, char* param_id)
{
mavlink_param_set_t *p = (mavlink_param_set_t *)&msg->payload[0];
......
......@@ -9,7 +9,7 @@ typedef struct __mavlink_param_value_t
float param_value; ///< Onboard parameter value
uint16_t param_count; ///< Total number of onboard parameters
uint16_t param_index; ///< Index of this onboard parameter
uint8_t param_id[16]; ///< Onboard parameter id
char param_id[16]; ///< Onboard parameter id
} mavlink_param_value_t;
#define MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN 16
......@@ -26,12 +26,12 @@ typedef struct __mavlink_param_value_t
* @param param_index Index of this onboard parameter
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_param_value_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const uint8_t* param_id, float param_value, uint16_t param_count, uint16_t param_index)
static inline uint16_t mavlink_msg_param_value_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const char* param_id, float param_value, uint16_t param_count, uint16_t param_index)
{
mavlink_param_value_t *p = (mavlink_param_value_t *)&msg->payload[0];
msg->msgid = MAVLINK_MSG_ID_PARAM_VALUE;
memcpy(p->param_id, param_id, sizeof(p->param_id)); // uint8_t[16]:Onboard parameter id
memcpy(p->param_id, param_id, sizeof(p->param_id)); // char[16]:Onboard parameter id
p->param_value = param_value; // float:Onboard parameter value
p->param_count = param_count; // uint16_t:Total number of onboard parameters
p->param_index = param_index; // uint16_t:Index of this onboard parameter
......@@ -51,12 +51,12 @@ static inline uint16_t mavlink_msg_param_value_pack(uint8_t system_id, uint8_t c
* @param param_index Index of this onboard parameter
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_param_value_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const uint8_t* param_id, float param_value, uint16_t param_count, uint16_t param_index)
static inline uint16_t mavlink_msg_param_value_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const char* param_id, float param_value, uint16_t param_count, uint16_t param_index)
{
mavlink_param_value_t *p = (mavlink_param_value_t *)&msg->payload[0];
msg->msgid = MAVLINK_MSG_ID_PARAM_VALUE;
memcpy(p->param_id, param_id, sizeof(p->param_id)); // uint8_t[16]:Onboard parameter id
memcpy(p->param_id, param_id, sizeof(p->param_id)); // char[16]:Onboard parameter id
p->param_value = param_value; // float:Onboard parameter value
p->param_count = param_count; // uint16_t:Total number of onboard parameters
p->param_index = param_index; // uint16_t:Index of this onboard parameter
......@@ -89,14 +89,14 @@ static inline uint16_t mavlink_msg_param_value_encode(uint8_t system_id, uint8_t
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_param_value_send(mavlink_channel_t chan, const uint8_t* param_id, float param_value, uint16_t param_count, uint16_t param_index)
static inline void mavlink_msg_param_value_send(mavlink_channel_t chan, const char* param_id, float param_value, uint16_t param_count, uint16_t param_index)
{
mavlink_header_t hdr;
mavlink_param_value_t payload;
uint16_t checksum;
mavlink_param_value_t *p = &payload;
memcpy(p->param_id, param_id, sizeof(p->param_id)); // uint8_t[16]:Onboard parameter id
memcpy(p->param_id, param_id, sizeof(p->param_id)); // char[16]:Onboard parameter id
p->param_value = param_value; // float:Onboard parameter value
p->param_count = param_count; // uint16_t:Total number of onboard parameters
p->param_index = param_index; // uint16_t:Index of this onboard parameter
......@@ -128,7 +128,7 @@ static inline void mavlink_msg_param_value_send(mavlink_channel_t chan, const ui
*
* @return Onboard parameter id
*/
static inline uint16_t mavlink_msg_param_value_get_param_id(const mavlink_message_t* msg, uint8_t* param_id)
static inline uint16_t mavlink_msg_param_value_get_param_id(const mavlink_message_t* msg, char* param_id)
{
mavlink_param_value_t *p = (mavlink_param_value_t *)&msg->payload[0];
......
......@@ -7,7 +7,7 @@
typedef struct __mavlink_statustext_t
{
uint8_t severity; ///< Severity of status, 0 = info message, 255 = critical fault
int8_t text[50]; ///< Status text message, without null termination character
char text[50]; ///< Status text message, without null termination character
} mavlink_statustext_t;
#define MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN 50
......@@ -22,13 +22,13 @@ typedef struct __mavlink_statustext_t
* @param text Status text message, without null termination character
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_statustext_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t severity, const int8_t* text)
static inline uint16_t mavlink_msg_statustext_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t severity, const char* text)
{
mavlink_statustext_t *p = (mavlink_statustext_t *)&msg->payload[0];
msg->msgid = MAVLINK_MSG_ID_STATUSTEXT;
p->severity = severity; // uint8_t:Severity of status, 0 = info message, 255 = critical fault
memcpy(p->text, text, sizeof(p->text)); // int8_t[50]:Status text message, without null termination character
memcpy(p->text, text, sizeof(p->text)); // char[50]:Status text message, without null termination character
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_STATUSTEXT_LEN);
}
......@@ -43,13 +43,13 @@ static inline uint16_t mavlink_msg_statustext_pack(uint8_t system_id, uint8_t co
* @param text Status text message, without null termination character
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_statustext_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t severity, const int8_t* text)
static inline uint16_t mavlink_msg_statustext_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t severity, const char* text)
{
mavlink_statustext_t *p = (mavlink_statustext_t *)&msg->payload[0];
msg->msgid = MAVLINK_MSG_ID_STATUSTEXT;
p->severity = severity; // uint8_t:Severity of status, 0 = info message, 255 = critical fault
memcpy(p->text, text, sizeof(p->text)); // int8_t[50]:Status text message, without null termination character
memcpy(p->text, text, sizeof(p->text)); // char[50]:Status text message, without null termination character
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_STATUSTEXT_LEN);
}
......@@ -77,7 +77,7 @@ static inline uint16_t mavlink_msg_statustext_encode(uint8_t system_id, uint8_t
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_statustext_send(mavlink_channel_t chan, uint8_t severity, const int8_t* text)
static inline void mavlink_msg_statustext_send(mavlink_channel_t chan, uint8_t severity, const char* text)
{
mavlink_header_t hdr;
mavlink_statustext_t payload;
......@@ -85,7 +85,7 @@ static inline void mavlink_msg_statustext_send(mavlink_channel_t chan, uint8_t s
mavlink_statustext_t *p = &payload;
p->severity = severity; // uint8_t:Severity of status, 0 = info message, 255 = critical fault
memcpy(p->text, text, sizeof(p->text)); // int8_t[50]:Status text message, without null termination character
memcpy(p->text, text, sizeof(p->text)); // char[50]:Status text message, without null termination character
hdr.STX = MAVLINK_STX;
hdr.len = MAVLINK_MSG_ID_STATUSTEXT_LEN;
......@@ -125,7 +125,7 @@ static inline uint8_t mavlink_msg_statustext_get_severity(const mavlink_message_
*
* @return Status text message, without null termination character
*/
static inline uint16_t mavlink_msg_statustext_get_text(const mavlink_message_t* msg, int8_t* text)
static inline uint16_t mavlink_msg_statustext_get_text(const mavlink_message_t* msg, char* text)
{
mavlink_statustext_t *p = (mavlink_statustext_t *)&msg->payload[0];
......
......@@ -19,7 +19,7 @@ extern "C" {
* table. Comment out the define to leave out the table and code to check it.
*
*/
#define MAVLINK_CHECK_LENGTH
//#define MAVLINK_CHECK_LENGTH
/**
*
......@@ -30,7 +30,7 @@ extern "C" {
* enable if you make the changes required. Default DISABLED.
*
*/
//#define MAVLINK_STAIC_BUFFER
//#define MAVLINK_STATIC_BUFFER
/**
*
......
......@@ -9,148 +9,6 @@
#include "inttypes.h"
enum MAV_CLASS
{
MAV_CLASS_GENERIC = 0, ///< Generic autopilot, full support for everything
MAV_CLASS_PIXHAWK = 1, ///< PIXHAWK autopilot, http://pixhawk.ethz.ch
MAV_CLASS_SLUGS = 2, ///< SLUGS autopilot, http://slugsuav.soe.ucsc.edu
MAV_CLASS_ARDUPILOTMEGA = 3, ///< ArduPilotMega / ArduCopter, http://diydrones.com
MAV_CLASS_OPENPILOT = 4, ///< OpenPilot, http://openpilot.org
MAV_CLASS_GENERIC_MISSION_WAYPOINTS_ONLY = 5, ///< Generic autopilot only supporting simple waypoints
MAV_CLASS_GENERIC_MISSION_NAVIGATION_ONLY = 6, ///< Generic autopilot supporting waypoints and other simple navigation commands
MAV_CLASS_GENERIC_MISSION_FULL = 7, ///< Generic autopilot supporting the full mission command set
MAV_CLASS_NB ///< Number of autopilot classes
};
enum MAV_ACTION
{
MAV_ACTION_HOLD = 0,
MAV_ACTION_MOTORS_START = 1,
MAV_ACTION_LAUNCH = 2,
MAV_ACTION_RETURN = 3,
MAV_ACTION_EMCY_LAND = 4,
MAV_ACTION_EMCY_KILL = 5,
MAV_ACTION_CONFIRM_KILL = 6,
MAV_ACTION_CONTINUE = 7,
MAV_ACTION_MOTORS_STOP = 8,
MAV_ACTION_HALT = 9,
MAV_ACTION_SHUTDOWN = 10,
MAV_ACTION_REBOOT = 11,
MAV_ACTION_SET_MANUAL = 12,
MAV_ACTION_SET_AUTO = 13,
MAV_ACTION_STORAGE_READ = 14,
MAV_ACTION_STORAGE_WRITE = 15,
MAV_ACTION_CALIBRATE_RC = 16,
MAV_ACTION_CALIBRATE_GYRO = 17,
MAV_ACTION_CALIBRATE_MAG = 18,
MAV_ACTION_CALIBRATE_ACC = 19,
MAV_ACTION_CALIBRATE_PRESSURE = 20,
MAV_ACTION_REC_START = 21,
MAV_ACTION_REC_PAUSE = 22,
MAV_ACTION_REC_STOP = 23,
MAV_ACTION_TAKEOFF = 24,
MAV_ACTION_NAVIGATE = 25,
MAV_ACTION_LAND = 26,
MAV_ACTION_LOITER = 27,
MAV_ACTION_SET_ORIGIN = 28,
MAV_ACTION_RELAY_ON = 29,
MAV_ACTION_RELAY_OFF = 30,
MAV_ACTION_GET_IMAGE = 31,
MAV_ACTION_VIDEO_START = 32,
MAV_ACTION_VIDEO_STOP = 33,
MAV_ACTION_RESET_MAP = 34,
MAV_ACTION_RESET_PLAN = 35,
MAV_ACTION_DELAY_BEFORE_COMMAND = 36,
MAV_ACTION_ASCEND_AT_RATE = 37,
MAV_ACTION_CHANGE_MODE = 38,
MAV_ACTION_LOITER_MAX_TURNS = 39,
MAV_ACTION_LOITER_MAX_TIME = 40,
MAV_ACTION_START_HILSIM = 41,
MAV_ACTION_STOP_HILSIM = 42,
MAV_ACTION_NB ///< Number of MAV actions
};
enum MAV_MODE
{
MAV_MODE_UNINIT = 0, ///< System is in undefined state
MAV_MODE_LOCKED = 1, ///< Motors are blocked, system is safe
MAV_MODE_MANUAL = 2, ///< System is allowed to be active, under manual (RC) control
MAV_MODE_GUIDED = 3, ///< System is allowed to be active, under autonomous control, manual setpoint
MAV_MODE_AUTO = 4, ///< System is allowed to be active, under autonomous control and navigation
MAV_MODE_TEST1 = 5, ///< Generic test mode, for custom use
MAV_MODE_TEST2 = 6, ///< Generic test mode, for custom use
MAV_MODE_TEST3 = 7, ///< Generic test mode, for custom use
MAV_MODE_READY = 8, ///< System is ready, motors are unblocked, but controllers are inactive
MAV_MODE_RC_TRAINING = 9 ///< System is blocked, only RC valued are read and reported back
};
enum MAV_STATE
{
MAV_STATE_UNINIT = 0,
MAV_STATE_BOOT,
MAV_STATE_CALIBRATING,
MAV_STATE_STANDBY,
MAV_STATE_ACTIVE,
MAV_STATE_CRITICAL,
MAV_STATE_EMERGENCY,
MAV_STATE_POWEROFF
};
enum MAV_NAV
{
MAV_NAV_GROUNDED = 0,
MAV_NAV_LIFTOFF,
MAV_NAV_HOLD,
MAV_NAV_WAYPOINT,
MAV_NAV_VECTOR,
MAV_NAV_RETURNING,
MAV_NAV_LANDING,
MAV_NAV_LOST,
MAV_NAV_LOITER
};
enum MAV_TYPE
{
MAV_GENERIC = 0,
MAV_FIXED_WING = 1,
MAV_QUADROTOR = 2,
MAV_COAXIAL = 3,
MAV_HELICOPTER = 4,
MAV_GROUND = 5,
OCU = 6
};
enum MAV_AUTOPILOT_TYPE
{
MAV_AUTOPILOT_GENERIC = 0,
MAV_AUTOPILOT_PIXHAWK = 1,
MAV_AUTOPILOT_SLUGS = 2,
MAV_AUTOPILOT_ARDUPILOTMEGA = 3
};
enum MAV_COMPONENT
{
MAV_COMP_ID_GPS,
MAV_COMP_ID_WAYPOINTPLANNER,
MAV_COMP_ID_BLOBTRACKER,
MAV_COMP_ID_PATHPLANNER,
MAV_COMP_ID_AIRSLAM,
MAV_COMP_ID_MAPPER,
MAV_COMP_ID_CAMERA,
MAV_COMP_ID_IMU = 200,
MAV_COMP_ID_UDP_BRIDGE = 240,
MAV_COMP_ID_UART_BRIDGE = 241,
MAV_COMP_ID_SYSTEM_CONTROL = 250
};
enum MAV_FRAME
{
MAV_FRAME_GLOBAL = 0,
MAV_FRAME_LOCAL = 1,
MAV_FRAME_MISSION = 2,
MAV_FRAME_GLOBAL_RELATIVE_ALT = 3
};
#define MAVLINK_STX 0xD5 ///< Packet start sign
#define MAVLINK_STX_LEN 1 ///< Length of start sign
#define MAVLINK_MAX_PAYLOAD_LEN 255 ///< Maximum payload length
......
/** @file
* @brief MAVLink comm protocol.
* @see http://pixhawk.ethz.ch/software/mavlink
* Generated on Tuesday, August 9 2011, 16:16 UTC
* Generated on Tuesday, August 9 2011, 16:49 UTC
*/
#ifndef MAVLINK_H
#define MAVLINK_H
......
......@@ -8,7 +8,7 @@ typedef struct __mavlink_pattern_detected_t
{
float confidence; ///< Confidence of detection
uint8_t type; ///< 0: Pattern, 1: Letter
uint8_t file[100]; ///< Pattern file name
char file[100]; ///< Pattern file name
uint8_t detected; ///< Accepted as true detection, 0 no, 1 yes
} mavlink_pattern_detected_t;
......@@ -26,14 +26,14 @@ typedef struct __mavlink_pattern_detected_t
* @param detected Accepted as true detection, 0 no, 1 yes
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_pattern_detected_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t type, float confidence, const uint8_t* file, uint8_t detected)
static inline uint16_t mavlink_msg_pattern_detected_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t type, float confidence, const char* file, uint8_t detected)
{
mavlink_pattern_detected_t *p = (mavlink_pattern_detected_t *)&msg->payload[0];
msg->msgid = MAVLINK_MSG_ID_PATTERN_DETECTED;
p->type = type; // uint8_t:0: Pattern, 1: Letter
p->confidence = confidence; // float:Confidence of detection
memcpy(p->file, file, sizeof(p->file)); // uint8_t[100]:Pattern file name
memcpy(p->file, file, sizeof(p->file)); // char[100]:Pattern file name
p->detected = detected; // uint8_t:Accepted as true detection, 0 no, 1 yes
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PATTERN_DETECTED_LEN);
......@@ -51,14 +51,14 @@ static inline uint16_t mavlink_msg_pattern_detected_pack(uint8_t system_id, uint
* @param detected Accepted as true detection, 0 no, 1 yes
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_pattern_detected_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t type, float confidence, const uint8_t* file, uint8_t detected)
static inline uint16_t mavlink_msg_pattern_detected_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t type, float confidence, const char* file, uint8_t detected)
{
mavlink_pattern_detected_t *p = (mavlink_pattern_detected_t *)&msg->payload[0];
msg->msgid = MAVLINK_MSG_ID_PATTERN_DETECTED;
p->type = type; // uint8_t:0: Pattern, 1: Letter
p->confidence = confidence; // float:Confidence of detection
memcpy(p->file, file, sizeof(p->file)); // uint8_t[100]:Pattern file name
memcpy(p->file, file, sizeof(p->file)); // char[100]:Pattern file name
p->detected = detected; // uint8_t:Accepted as true detection, 0 no, 1 yes
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PATTERN_DETECTED_LEN);
......@@ -89,7 +89,7 @@ static inline uint16_t mavlink_msg_pattern_detected_encode(uint8_t system_id, ui
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_pattern_detected_send(mavlink_channel_t chan, uint8_t type, float confidence, const uint8_t* file, uint8_t detected)
static inline void mavlink_msg_pattern_detected_send(mavlink_channel_t chan, uint8_t type, float confidence, const char* file, uint8_t detected)
{
mavlink_header_t hdr;
mavlink_pattern_detected_t payload;
......@@ -98,7 +98,7 @@ static inline void mavlink_msg_pattern_detected_send(mavlink_channel_t chan, uin
p->type = type; // uint8_t:0: Pattern, 1: Letter
p->confidence = confidence; // float:Confidence of detection
memcpy(p->file, file, sizeof(p->file)); // uint8_t[100]:Pattern file name
memcpy(p->file, file, sizeof(p->file)); // char[100]:Pattern file name
p->detected = detected; // uint8_t:Accepted as true detection, 0 no, 1 yes
hdr.STX = MAVLINK_STX;
......@@ -150,7 +150,7 @@ static inline float mavlink_msg_pattern_detected_get_confidence(const mavlink_me
*
* @return Pattern file name
*/
static inline uint16_t mavlink_msg_pattern_detected_get_file(const mavlink_message_t* msg, uint8_t* file)
static inline uint16_t mavlink_msg_pattern_detected_get_file(const mavlink_message_t* msg, char* file)
{
mavlink_pattern_detected_t *p = (mavlink_pattern_detected_t *)&msg->payload[0];
......
......@@ -13,7 +13,7 @@ typedef struct __mavlink_point_of_interest_t
uint8_t type; ///< 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug
uint8_t color; ///< 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta
uint8_t coordinate_system; ///< 0: global, 1:local
uint8_t name[26]; ///< POI name
char name[26]; ///< POI name
} mavlink_point_of_interest_t;
#define MAVLINK_MSG_POINT_OF_INTEREST_FIELD_NAME_LEN 26
......@@ -34,7 +34,7 @@ typedef struct __mavlink_point_of_interest_t
* @param name POI name
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_point_of_interest_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t type, uint8_t color, uint8_t coordinate_system, uint16_t timeout, float x, float y, float z, const uint8_t* name)
static inline uint16_t mavlink_msg_point_of_interest_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t type, uint8_t color, uint8_t coordinate_system, uint16_t timeout, float x, float y, float z, const char* name)
{
mavlink_point_of_interest_t *p = (mavlink_point_of_interest_t *)&msg->payload[0];
msg->msgid = MAVLINK_MSG_ID_POINT_OF_INTEREST;
......@@ -46,7 +46,7 @@ static inline uint16_t mavlink_msg_point_of_interest_pack(uint8_t system_id, uin
p->x = x; // float:X Position
p->y = y; // float:Y Position
p->z = z; // float:Z Position
memcpy(p->name, name, sizeof(p->name)); // uint8_t[26]:POI name
memcpy(p->name, name, sizeof(p->name)); // char[26]:POI name
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_POINT_OF_INTEREST_LEN);
}
......@@ -67,7 +67,7 @@ static inline uint16_t mavlink_msg_point_of_interest_pack(uint8_t system_id, uin
* @param name POI name
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_point_of_interest_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t type, uint8_t color, uint8_t coordinate_system, uint16_t timeout, float x, float y, float z, const uint8_t* name)
static inline uint16_t mavlink_msg_point_of_interest_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t type, uint8_t color, uint8_t coordinate_system, uint16_t timeout, float x, float y, float z, const char* name)
{
mavlink_point_of_interest_t *p = (mavlink_point_of_interest_t *)&msg->payload[0];
msg->msgid = MAVLINK_MSG_ID_POINT_OF_INTEREST;
......@@ -79,7 +79,7 @@ static inline uint16_t mavlink_msg_point_of_interest_pack_chan(uint8_t system_id
p->x = x; // float:X Position
p->y = y; // float:Y Position
p->z = z; // float:Z Position
memcpy(p->name, name, sizeof(p->name)); // uint8_t[26]:POI name
memcpy(p->name, name, sizeof(p->name)); // char[26]:POI name
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_POINT_OF_INTEREST_LEN);
}
......@@ -113,7 +113,7 @@ static inline uint16_t mavlink_msg_point_of_interest_encode(uint8_t system_id, u
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_point_of_interest_send(mavlink_channel_t chan, uint8_t type, uint8_t color, uint8_t coordinate_system, uint16_t timeout, float x, float y, float z, const uint8_t* name)
static inline void mavlink_msg_point_of_interest_send(mavlink_channel_t chan, uint8_t type, uint8_t color, uint8_t coordinate_system, uint16_t timeout, float x, float y, float z, const char* name)
{
mavlink_header_t hdr;
mavlink_point_of_interest_t payload;
......@@ -127,7 +127,7 @@ static inline void mavlink_msg_point_of_interest_send(mavlink_channel_t chan, ui
p->x = x; // float:X Position
p->y = y; // float:Y Position
p->z = z; // float:Z Position
memcpy(p->name, name, sizeof(p->name)); // uint8_t[26]:POI name
memcpy(p->name, name, sizeof(p->name)); // char[26]:POI name
hdr.STX = MAVLINK_STX;
hdr.len = MAVLINK_MSG_ID_POINT_OF_INTEREST_LEN;
......@@ -233,7 +233,7 @@ static inline float mavlink_msg_point_of_interest_get_z(const mavlink_message_t*
*
* @return POI name
*/
static inline uint16_t mavlink_msg_point_of_interest_get_name(const mavlink_message_t* msg, uint8_t* name)
static inline uint16_t mavlink_msg_point_of_interest_get_name(const mavlink_message_t* msg, char* name)
{
mavlink_point_of_interest_t *p = (mavlink_point_of_interest_t *)&msg->payload[0];
......
......@@ -16,7 +16,7 @@ typedef struct __mavlink_point_of_interest_connection_t
uint8_t type; ///< 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug
uint8_t color; ///< 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta
uint8_t coordinate_system; ///< 0: global, 1:local
uint8_t name[26]; ///< POI connection name
char name[26]; ///< POI connection name
} mavlink_point_of_interest_connection_t;
#define MAVLINK_MSG_POINT_OF_INTEREST_CONNECTION_FIELD_NAME_LEN 26
......@@ -40,7 +40,7 @@ typedef struct __mavlink_point_of_interest_connection_t
* @param name POI connection name
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_point_of_interest_connection_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t type, uint8_t color, uint8_t coordinate_system, uint16_t timeout, float xp1, float yp1, float zp1, float xp2, float yp2, float zp2, const uint8_t* name)
static inline uint16_t mavlink_msg_point_of_interest_connection_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t type, uint8_t color, uint8_t coordinate_system, uint16_t timeout, float xp1, float yp1, float zp1, float xp2, float yp2, float zp2, const char* name)
{
mavlink_point_of_interest_connection_t *p = (mavlink_point_of_interest_connection_t *)&msg->payload[0];
msg->msgid = MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION;
......@@ -55,7 +55,7 @@ static inline uint16_t mavlink_msg_point_of_interest_connection_pack(uint8_t sys
p->xp2 = xp2; // float:X2 Position
p->yp2 = yp2; // float:Y2 Position
p->zp2 = zp2; // float:Z2 Position
memcpy(p->name, name, sizeof(p->name)); // uint8_t[26]:POI connection name
memcpy(p->name, name, sizeof(p->name)); // char[26]:POI connection name
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION_LEN);
}
......@@ -79,7 +79,7 @@ static inline uint16_t mavlink_msg_point_of_interest_connection_pack(uint8_t sys
* @param name POI connection name
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_point_of_interest_connection_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t type, uint8_t color, uint8_t coordinate_system, uint16_t timeout, float xp1, float yp1, float zp1, float xp2, float yp2, float zp2, const uint8_t* name)
static inline uint16_t mavlink_msg_point_of_interest_connection_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t type, uint8_t color, uint8_t coordinate_system, uint16_t timeout, float xp1, float yp1, float zp1, float xp2, float yp2, float zp2, const char* name)
{
mavlink_point_of_interest_connection_t *p = (mavlink_point_of_interest_connection_t *)&msg->payload[0];
msg->msgid = MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION;
......@@ -94,7 +94,7 @@ static inline uint16_t mavlink_msg_point_of_interest_connection_pack_chan(uint8_
p->xp2 = xp2; // float:X2 Position
p->yp2 = yp2; // float:Y2 Position
p->zp2 = zp2; // float:Z2 Position
memcpy(p->name, name, sizeof(p->name)); // uint8_t[26]:POI connection name
memcpy(p->name, name, sizeof(p->name)); // char[26]:POI connection name
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION_LEN);
}
......@@ -131,7 +131,7 @@ static inline uint16_t mavlink_msg_point_of_interest_connection_encode(uint8_t s
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_point_of_interest_connection_send(mavlink_channel_t chan, uint8_t type, uint8_t color, uint8_t coordinate_system, uint16_t timeout, float xp1, float yp1, float zp1, float xp2, float yp2, float zp2, const uint8_t* name)
static inline void mavlink_msg_point_of_interest_connection_send(mavlink_channel_t chan, uint8_t type, uint8_t color, uint8_t coordinate_system, uint16_t timeout, float xp1, float yp1, float zp1, float xp2, float yp2, float zp2, const char* name)
{
mavlink_header_t hdr;
mavlink_point_of_interest_connection_t payload;
......@@ -148,7 +148,7 @@ static inline void mavlink_msg_point_of_interest_connection_send(mavlink_channel
p->xp2 = xp2; // float:X2 Position
p->yp2 = yp2; // float:Y2 Position
p->zp2 = zp2; // float:Z2 Position
memcpy(p->name, name, sizeof(p->name)); // uint8_t[26]:POI connection name
memcpy(p->name, name, sizeof(p->name)); // char[26]:POI connection name
hdr.STX = MAVLINK_STX;
hdr.len = MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION_LEN;
......@@ -287,7 +287,7 @@ static inline float mavlink_msg_point_of_interest_connection_get_zp2(const mavli
*
* @return POI connection name
*/
static inline uint16_t mavlink_msg_point_of_interest_connection_get_name(const mavlink_message_t* msg, uint8_t* name)
static inline uint16_t mavlink_msg_point_of_interest_connection_get_name(const mavlink_message_t* msg, char* name)
{
mavlink_point_of_interest_connection_t *p = (mavlink_point_of_interest_connection_t *)&msg->payload[0];
......
......@@ -9,8 +9,8 @@ typedef struct __mavlink_watchdog_process_info_t
int32_t timeout; ///< Timeout (seconds)
uint16_t watchdog_id; ///< Watchdog ID
uint16_t process_id; ///< Process ID
uint8_t name[100]; ///< Process name
uint8_t arguments[147]; ///< Process arguments
char name[100]; ///< Process name
char arguments[147]; ///< Process arguments
} mavlink_watchdog_process_info_t;
#define MAVLINK_MSG_WATCHDOG_PROCESS_INFO_FIELD_NAME_LEN 100
......@@ -29,15 +29,15 @@ typedef struct __mavlink_watchdog_process_info_t
* @param timeout Timeout (seconds)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_watchdog_process_info_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint16_t watchdog_id, uint16_t process_id, const uint8_t* name, const uint8_t* arguments, int32_t timeout)
static inline uint16_t mavlink_msg_watchdog_process_info_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint16_t watchdog_id, uint16_t process_id, const char* name, const char* arguments, int32_t timeout)
{
mavlink_watchdog_process_info_t *p = (mavlink_watchdog_process_info_t *)&msg->payload[0];
msg->msgid = MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO;
p->watchdog_id = watchdog_id; // uint16_t:Watchdog ID
p->process_id = process_id; // uint16_t:Process ID
memcpy(p->name, name, sizeof(p->name)); // uint8_t[100]:Process name
memcpy(p->arguments, arguments, sizeof(p->arguments)); // uint8_t[147]:Process arguments
memcpy(p->name, name, sizeof(p->name)); // char[100]:Process name
memcpy(p->arguments, arguments, sizeof(p->arguments)); // char[147]:Process arguments
p->timeout = timeout; // int32_t:Timeout (seconds)
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO_LEN);
......@@ -56,15 +56,15 @@ static inline uint16_t mavlink_msg_watchdog_process_info_pack(uint8_t system_id,
* @param timeout Timeout (seconds)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_watchdog_process_info_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint16_t watchdog_id, uint16_t process_id, const uint8_t* name, const uint8_t* arguments, int32_t timeout)
static inline uint16_t mavlink_msg_watchdog_process_info_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint16_t watchdog_id, uint16_t process_id, const char* name, const char* arguments, int32_t timeout)
{
mavlink_watchdog_process_info_t *p = (mavlink_watchdog_process_info_t *)&msg->payload[0];
msg->msgid = MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO;
p->watchdog_id = watchdog_id; // uint16_t:Watchdog ID
p->process_id = process_id; // uint16_t:Process ID
memcpy(p->name, name, sizeof(p->name)); // uint8_t[100]:Process name
memcpy(p->arguments, arguments, sizeof(p->arguments)); // uint8_t[147]:Process arguments
memcpy(p->name, name, sizeof(p->name)); // char[100]:Process name
memcpy(p->arguments, arguments, sizeof(p->arguments)); // char[147]:Process arguments
p->timeout = timeout; // int32_t:Timeout (seconds)
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO_LEN);
......@@ -96,7 +96,7 @@ static inline uint16_t mavlink_msg_watchdog_process_info_encode(uint8_t system_i
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_watchdog_process_info_send(mavlink_channel_t chan, uint16_t watchdog_id, uint16_t process_id, const uint8_t* name, const uint8_t* arguments, int32_t timeout)
static inline void mavlink_msg_watchdog_process_info_send(mavlink_channel_t chan, uint16_t watchdog_id, uint16_t process_id, const char* name, const char* arguments, int32_t timeout)
{
mavlink_header_t hdr;
mavlink_watchdog_process_info_t payload;
......@@ -105,8 +105,8 @@ static inline void mavlink_msg_watchdog_process_info_send(mavlink_channel_t chan
p->watchdog_id = watchdog_id; // uint16_t:Watchdog ID
p->process_id = process_id; // uint16_t:Process ID
memcpy(p->name, name, sizeof(p->name)); // uint8_t[100]:Process name
memcpy(p->arguments, arguments, sizeof(p->arguments)); // uint8_t[147]:Process arguments
memcpy(p->name, name, sizeof(p->name)); // char[100]:Process name
memcpy(p->arguments, arguments, sizeof(p->arguments)); // char[147]:Process arguments
p->timeout = timeout; // int32_t:Timeout (seconds)
hdr.STX = MAVLINK_STX;
......@@ -158,7 +158,7 @@ static inline uint16_t mavlink_msg_watchdog_process_info_get_process_id(const ma
*
* @return Process name
*/
static inline uint16_t mavlink_msg_watchdog_process_info_get_name(const mavlink_message_t* msg, uint8_t* name)
static inline uint16_t mavlink_msg_watchdog_process_info_get_name(const mavlink_message_t* msg, char* name)
{
mavlink_watchdog_process_info_t *p = (mavlink_watchdog_process_info_t *)&msg->payload[0];
......@@ -171,7 +171,7 @@ static inline uint16_t mavlink_msg_watchdog_process_info_get_name(const mavlink_
*
* @return Process arguments
*/
static inline uint16_t mavlink_msg_watchdog_process_info_get_arguments(const mavlink_message_t* msg, uint8_t* arguments)
static inline uint16_t mavlink_msg_watchdog_process_info_get_arguments(const mavlink_message_t* msg, char* arguments)
{
mavlink_watchdog_process_info_t *p = (mavlink_watchdog_process_info_t *)&msg->payload[0];
......
/** @file
* @brief MAVLink comm protocol.
* @see http://qgroundcontrol.org/mavlink/
* Generated on Tuesday, August 9 2011, 16:16 UTC
* Generated on Tuesday, August 9 2011, 16:49 UTC
*/
#ifndef PIXHAWK_H
#define PIXHAWK_H
......@@ -71,7 +71,7 @@ enum DATA_TYPES
// MESSAGE CRC KEYS
#undef MAVLINK_MESSAGE_KEYS
#define MAVLINK_MESSAGE_KEYS { 71, 249, 232, 226, 76, 126, 117, 186, 0, 165, 44, 249, 133, 0, 0, 0, 0, 0, 0, 0, 112, 34, 81, 152, 0, 223, 28, 99, 28, 21, 243, 240, 204, 21, 111, 43, 192, 234, 22, 197, 192, 192, 166, 34, 233, 34, 166, 158, 142, 60, 10, 75, 249, 247, 234, 157, 125, 0, 0, 0, 85, 211, 62, 75, 185, 18, 42, 38, 0, 127, 200, 0, 0, 53, 251, 20, 22, 0, 0, 0, 0, 0, 0, 0, 0, 127, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 8, 238, 165, 0, 0, 0, 0, 0, 0, 0, 218, 218, 235, 0, 0, 0, 0, 0, 0, 225, 114, 0, 0, 0, 0, 0, 0, 0, 0, 221, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 171, 122, 0, 0, 0, 0, 0, 0, 0, 92, 114, 4, 169, 10, 0, 0, 0, 0, 0, 72, 62, 83, 0, 0, 0, 0, 0, 0, 0, 200, 135, 217, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 43, 141, 211, 166 }
#define MAVLINK_MESSAGE_KEYS { 71, 249, 232, 226, 76, 126, 117, 186, 0, 144, 0, 249, 133, 0, 0, 0, 0, 0, 0, 0, 33, 34, 163, 45, 0, 223, 28, 99, 28, 21, 243, 240, 204, 21, 111, 43, 192, 234, 22, 197, 192, 192, 166, 34, 233, 34, 166, 158, 142, 60, 10, 75, 249, 247, 234, 157, 125, 0, 0, 0, 85, 211, 62, 75, 185, 18, 42, 38, 0, 127, 200, 0, 0, 53, 251, 20, 22, 0, 0, 0, 0, 0, 0, 0, 0, 127, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 8, 238, 165, 0, 0, 0, 0, 0, 0, 0, 218, 218, 235, 0, 0, 0, 0, 0, 0, 225, 114, 0, 0, 0, 0, 0, 0, 0, 0, 221, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 171, 122, 0, 0, 0, 0, 0, 0, 0, 92, 99, 4, 169, 10, 0, 0, 0, 0, 0, 52, 163, 16, 0, 0, 0, 0, 0, 0, 0, 200, 135, 217, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 43, 141, 211, 144 }
#ifdef __cplusplus
}
......
......@@ -322,18 +322,19 @@ static inline uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_messag
status->parse_state = MAVLINK_PARSE_STATE_IDLE;
if (c == MAVLINK_STX)
{
status->parse_state = MAVLINK_PARSE_STATE_GOT_STX;
mavlink_start_checksum(rxmsg);
status->parse_state = MAVLINK_PARSE_STATE_GOT_STX;
mavlink_start_checksum(rxmsg);
}
}
}
else
{
// Successfully got message
status->msg_received = 1;
status->parse_state = MAVLINK_PARSE_STATE_IDLE;
if ( r_message != NULL )
memcpy(r_message, rxmsg, sizeof(mavlink_message_t));
else ;
// Successfully got message
status->msg_received = 1;
status->parse_state = MAVLINK_PARSE_STATE_IDLE;
if ( r_message != NULL )
{
memcpy(r_message, rxmsg, sizeof(mavlink_message_t));
}
}
break;
}
......
......@@ -676,17 +676,11 @@
<description>Emit an encrypted signature / key identifying this system. PLEASE NOTE: This protocol has been kept simple, so transmitting the key requires an encrypted channel for true safety.</description>
<field type="char[32]" name="key">key</field>
</message>
<message id="9" name="ACTION_ACK">
<message id="9" name="CMD_ACK">
<description>This message acknowledges an action. IMPORTANT: The acknowledgement can be also negative, e.g. the MAV rejects a reset message because it is in-flight. The action ids are defined in ENUM MAV_ACTION in mavlink/include/mavlink_types.h</description>
<field type="uint8_t" name="action">The action id</field>
<field type="uint8_t" name="cmd">The MAV_CMD ID</field>
<field type="uint8_t" name="result">0: Action DENIED, 1: Action executed</field>
</message>
<message id="10" name="ACTION">
<description>An action message allows to execute a certain onboard action. These include liftoff, land, storing parameters too EEPROM, shutddown, etc. The action ids are defined in ENUM MAV_ACTION in mavlink/include/mavlink_types.h</description>
<field type="uint8_t" name="target">The system executing the action</field>
<field type="uint8_t" name="target_component">The component executing the action</field>
<field type="uint8_t" name="action">The action id</field>
</message>
<message id="11" name="SET_MODE">
<description>Set the system mode, as defined by enum MAV_MODE in mavlink/include/mavlink_types.h. There is no target component id as the mode is by definition for the overall aircraft, not only for one component.</description>
<field type="uint8_t" name="target">The system setting the mode</field>
......@@ -701,7 +695,7 @@
<description>Request to read the onboard parameter with the param_id string id. Onboard parameters are stored as key[const char*] -> value[float]. This allows to send a parameter to any other component (such as the GCS) without the need of previous knowledge of possible parameter names. Thus the same GCS can store different parameters for different autopilots. See also http://qgroundcontrol.org/parameter_interface for a full documentation of QGroundControl and IMU code.</description>
<field type="uint8_t" name="target_system">System ID</field>
<field type="uint8_t" name="target_component">Component ID</field>
<field type="uint8_t[16]" name="param_id">Onboard parameter id</field>
<field type="char[16]" name="param_id">Onboard parameter id</field>
<field type="int16_t" name="param_index">Parameter index. Send -1 to use the param ID field as identifier</field>
</message>
<message id="21" name="PARAM_REQUEST_LIST">
......@@ -711,7 +705,7 @@
</message>
<message id="22" name="PARAM_VALUE">
<description>Emit the value of a onboard parameter. The inclusion of param_count and param_index in the message allows the recipient to keep track of received parameters and allows him to re-request missing parameters after a loss or timeout.</description>
<field type="uint8_t[16]" name="param_id">Onboard parameter id</field>
<field type="char[16]" name="param_id">Onboard parameter id</field>
<field type="float" name="param_value">Onboard parameter value</field>
<field type="uint16_t" name="param_count">Total number of onboard parameters</field>
<field type="uint16_t" name="param_index">Index of this onboard parameter</field>
......@@ -720,7 +714,7 @@
<description>Set a parameter value TEMPORARILY to RAM. It will be reset to default on system reboot. Send the ACTION MAV_ACTION_STORAGE_WRITE to PERMANENTLY write the RAM contents to EEPROM. IMPORTANT: The receiving component should acknowledge the new parameter value by sending a param_value message to all communication partners. This will also ensure that multiple GCS all have an up-to-date list of all parameters. If the sending GCS did not receive a PARAM_VALUE message within its timeout time, it should re-send the PARAM_SET message.</description>
<field type="uint8_t" name="target_system">System ID</field>
<field type="uint8_t" name="target_component">Component ID</field>
<field type="uint8_t[16]" name="param_id">Onboard parameter id</field>
<field type="char[16]" name="param_id">Onboard parameter id</field>
<field type="float" name="param_value">Onboard parameter value</field>
</message>
<message id="25" name="GPS_RAW_INT">
......@@ -1174,7 +1168,7 @@
<message id="254" name="STATUSTEXT">
<description>Status text message. These messages are printed in yellow in the COMM console of QGroundControl. WARNING: They consume quite some bandwidth, so use only for important status and error messages. If implemented wisely, these messages are buffered on the MCU and sent only at a limited rate (e.g. 10 Hz).</description>
<field type="uint8_t" name="severity">Severity of status, 0 = info message, 255 = critical fault</field>
<field type="int8_t[50]" name="text">Status text message, without null termination character</field>
<field type="char[50]" name="text">Status text message, without null termination character</field>
</message>
<message id="255" name="DEBUG">
<description>Send a debug value. The index is used to discriminate between values. These values show up in the plot of QGroundControl as DEBUG N.</description>
......
......@@ -155,8 +155,8 @@
<message id="151" name="WATCHDOG_PROCESS_INFO">
<field type="uint16_t" name="watchdog_id">Watchdog ID</field>
<field type="uint16_t" name="process_id">Process ID</field>
<field type="uint8_t[100]" name="name">Process name</field>
<field type="uint8_t[147]" name="arguments">Process arguments</field>
<field type="char[100]" name="name">Process name</field>
<field type="char[147]" name="arguments">Process arguments</field>
<field type="int32_t" name="timeout">Timeout (seconds)</field>
</message>
<message id="152" name="WATCHDOG_PROCESS_STATUS">
......@@ -176,7 +176,7 @@
<message id="160" name="PATTERN_DETECTED">
<field type="uint8_t" name="type">0: Pattern, 1: Letter</field>
<field type="float" name="confidence">Confidence of detection</field>
<field type="uint8_t[100]" name="file">Pattern file name</field>
<field type="char[100]" name="file">Pattern file name</field>
<field type="uint8_t" name="detected">Accepted as true detection, 0 no, 1 yes</field>
</message>
<message id="161" name="POINT_OF_INTEREST">
......@@ -191,7 +191,7 @@
<field type="float" name="x">X Position</field>
<field type="float" name="y">Y Position</field>
<field type="float" name="z">Z Position</field>
<field type="uint8_t[26]" name="name">POI name</field>
<field type="char[26]" name="name">POI name</field>
</message>
<message id="162" name="POINT_OF_INTEREST_CONNECTION">
<description>Notifies the operator about the connection of two point of interests (POI). This can be anything detected by the
......@@ -208,7 +208,7 @@
<field type="float" name="xp2">X2 Position</field>
<field type="float" name="yp2">Y2 Position</field>
<field type="float" name="zp2">Z2 Position</field>
<field type="uint8_t[26]" name="name">POI connection name</field>
<field type="char[26]" name="name">POI connection name</field>
</message>
<message id="170" name="DATA_TRANSMISSION_HANDSHAKE">
<field type="uint8_t" name="type">type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h)</field>
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment