Update to current MAVLink dev branch protocol version. This has NOT been tested yet.

git-svn-id: https://arducopter.googlecode.com/svn/trunk@1494 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
DrZiplok 2011-01-12 08:57:54 +00:00
parent 3f663597b5
commit e552b7c7e1
83 changed files with 4632 additions and 885 deletions

View File

@ -2,8 +2,18 @@
<xsl:stylesheet version="1.0" xmlns:xsl="http://www.w3.org/1999/XSL/Transform">
<xsl:template match="//include">
<h1>MAVLink Include Files</h1>
<p><strong><em>Including files: </em><xsl:value-of select="." /></strong></p>
</xsl:template>
<xsl:template match="//enums">
<h1>MAVLink Type Enumerations</h1>
<xsl:apply-templates />
</xsl:template>
<xsl:template match="//messages">
<h4>MAVLink Messages</h4>
<h1>MAVLink Messages</h1>
<xsl:apply-templates />
</xsl:template>
@ -33,4 +43,32 @@
</tr>
</xsl:template>
<xsl:template match="//version">
<h1>MAVLink Protocol Version</h1>
<p>This file has protocol version: <xsl:value-of select="." />. The version numbers range from 1-255.</p>
</xsl:template>
<xsl:template match="//enum">
<h3 class="mavlink_message_name"><xsl:value-of select="@name" /></h3>
<p class="description"><xsl:value-of select="description" /></p>
<table class="sortable">
<thead>
<tr>
<th class="mavlink_field_header">Field Name</th>
</tr>
</thead>
<tbody>
<xsl:apply-templates select="entry" />
</tbody>
</table>
</xsl:template>
<xsl:template match="//entry">
<tr class="mavlink_field">
<td class="mavlink_name"><xsl:value-of select="@name" /></td>
</tr>
</xsl:template>
</xsl:stylesheet>

View File

@ -1,7 +1,7 @@
/** @file
* @brief MAVLink comm protocol.
* @see http://pixhawk.ethz.ch/software/mavlink
* Generated on Friday, December 10 2010, 07:24 UTC
* Generated on Friday, January 7 2011, 10:04 UTC
*/
#ifndef COMMON_H
#define COMMON_H
@ -15,6 +15,17 @@ extern "C" {
#define MAVLINK_ENABLED_COMMON
// MAVLINK VERSION
#ifndef MAVLINK_VERSION
#define MAVLINK_VERSION 1
#endif
#if (MAVLINK_VERSION == 0)
#undef MAVLINK_VERSION
#define MAVLINK_VERSION 1
#endif
// ENUM DEFINITIONS
@ -66,6 +77,7 @@ extern "C" {
#include "./mavlink_msg_debug_vect.h"
#include "./mavlink_msg_gps_local_origin_set.h"
#include "./mavlink_msg_airspeed.h"
#include "./mavlink_msg_global_position_int.h"
#include "./mavlink_msg_statustext.h"
#include "./mavlink_msg_debug.h"
#ifdef __cplusplus

View File

@ -1,7 +1,7 @@
/** @file
* @brief MAVLink comm protocol.
* @see http://pixhawk.ethz.ch/software/mavlink
* Generated on Friday, December 10 2010, 07:24 UTC
* Generated on Friday, January 7 2011, 10:04 UTC
*/
#ifndef MAVLINK_H
#define MAVLINK_H

View File

@ -13,7 +13,10 @@ typedef struct __mavlink_action_t
/**
* @brief Send a action message
* @brief Pack a action 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 target The system executing the action
* @param target_component The component executing the action
@ -25,30 +28,57 @@ static inline uint16_t mavlink_msg_action_pack(uint8_t system_id, uint8_t compon
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_ACTION;
i += put_uint8_t_by_index(target, i, msg->payload); //The system executing the action
i += put_uint8_t_by_index(target_component, i, msg->payload); //The component executing the action
i += put_uint8_t_by_index(action, i, msg->payload); //The action id
i += put_uint8_t_by_index(target, i, msg->payload); // The system executing the action
i += put_uint8_t_by_index(target_component, i, msg->payload); // The component executing the action
i += put_uint8_t_by_index(action, i, msg->payload); // The action id
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a action 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 target The system executing the action
* @param target_component The component executing the action
* @param action The action id
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_action_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target, uint8_t target_component, uint8_t action)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_ACTION;
i += put_uint8_t_by_index(target, i, msg->payload); //The system executing the action
i += put_uint8_t_by_index(target_component, i, msg->payload); //The component executing the action
i += put_uint8_t_by_index(action, i, msg->payload); //The action id
i += put_uint8_t_by_index(target, i, msg->payload); // The system executing the action
i += put_uint8_t_by_index(target_component, i, msg->payload); // The component executing the action
i += put_uint8_t_by_index(action, i, msg->payload); // The action id
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a action 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 action C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_action_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_action_t* action)
{
return mavlink_msg_action_pack(system_id, component_id, msg, action->target, action->target_component, action->action);
}
/**
* @brief Send a action message
* @param chan MAVLink channel to send the message
*
* @param target The system executing the action
* @param target_component The component executing the action
* @param action The action id
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_action_send(mavlink_channel_t chan, uint8_t target, uint8_t target_component, uint8_t action)
@ -91,6 +121,12 @@ static inline uint8_t mavlink_msg_action_get_action(const mavlink_message_t* msg
return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0];
}
/**
* @brief Decode a action message into a struct
*
* @param msg The message to decode
* @param action C-struct to decode the message contents into
*/
static inline void mavlink_msg_action_decode(const mavlink_message_t* msg, mavlink_action_t* action)
{
action->target = mavlink_msg_action_get_target(msg);

View File

@ -12,7 +12,10 @@ typedef struct __mavlink_action_ack_t
/**
* @brief Send a action_ack message
* @brief Pack a action_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 action The action id
* @param result 0: Action DENIED, 1: Action executed
@ -23,28 +26,53 @@ static inline uint16_t mavlink_msg_action_ack_pack(uint8_t system_id, uint8_t co
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_ACTION_ACK;
i += put_uint8_t_by_index(action, i, msg->payload); //The action id
i += put_uint8_t_by_index(result, i, msg->payload); //0: Action DENIED, 1: Action executed
i += put_uint8_t_by_index(action, i, msg->payload); // The action id
i += put_uint8_t_by_index(result, i, msg->payload); // 0: Action DENIED, 1: Action executed
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a action_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 action The action 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_action_ack_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t action, uint8_t result)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_ACTION_ACK;
i += put_uint8_t_by_index(action, i, msg->payload); //The action id
i += put_uint8_t_by_index(result, i, msg->payload); //0: Action DENIED, 1: Action executed
i += put_uint8_t_by_index(action, i, msg->payload); // The action id
i += put_uint8_t_by_index(result, i, msg->payload); // 0: Action DENIED, 1: Action executed
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a action_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 action_ack C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_action_ack_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_action_ack_t* action_ack)
{
return mavlink_msg_action_ack_pack(system_id, component_id, msg, action_ack->action, action_ack->result);
}
/**
* @brief Send a action_ack message
* @param chan MAVLink channel to send the message
*
* @param action The action id
* @param result 0: Action DENIED, 1: Action executed
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_action_ack_send(mavlink_channel_t chan, uint8_t action, uint8_t result)
@ -77,6 +105,12 @@ static inline uint8_t mavlink_msg_action_ack_get_result(const mavlink_message_t*
return (uint8_t)(msg->payload+sizeof(uint8_t))[0];
}
/**
* @brief Decode a action_ack message into a struct
*
* @param msg The message to decode
* @param action_ack C-struct to decode the message contents into
*/
static inline void mavlink_msg_action_ack_decode(const mavlink_message_t* msg, mavlink_action_ack_t* action_ack)
{
action_ack->action = mavlink_msg_action_ack_get_action(msg);

View File

@ -11,7 +11,10 @@ typedef struct __mavlink_airspeed_t
/**
* @brief Send a airspeed message
* @brief Pack a airspeed 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 airspeed meters/second
* @return length of the message in bytes (excluding serial stream start sign)
@ -21,26 +24,49 @@ static inline uint16_t mavlink_msg_airspeed_pack(uint8_t system_id, uint8_t comp
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_AIRSPEED;
i += put_float_by_index(airspeed, i, msg->payload); //meters/second
i += put_float_by_index(airspeed, i, msg->payload); // meters/second
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a airspeed 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 airspeed meters/second
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_airspeed_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, float airspeed)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_AIRSPEED;
i += put_float_by_index(airspeed, i, msg->payload); //meters/second
i += put_float_by_index(airspeed, i, msg->payload); // meters/second
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a airspeed 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 airspeed C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_airspeed_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_airspeed_t* airspeed)
{
return mavlink_msg_airspeed_pack(system_id, component_id, msg, airspeed->airspeed);
}
/**
* @brief Send a airspeed message
* @param chan MAVLink channel to send the message
*
* @param airspeed meters/second
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_airspeed_send(mavlink_channel_t chan, float airspeed)
@ -68,6 +94,12 @@ static inline float mavlink_msg_airspeed_get_airspeed(const mavlink_message_t* m
return (float)r.f;
}
/**
* @brief Decode a airspeed message into a struct
*
* @param msg The message to decode
* @param airspeed C-struct to decode the message contents into
*/
static inline void mavlink_msg_airspeed_decode(const mavlink_message_t* msg, mavlink_airspeed_t* airspeed)
{
airspeed->airspeed = mavlink_msg_airspeed_get_airspeed(msg);

View File

@ -17,7 +17,10 @@ typedef struct __mavlink_attitude_t
/**
* @brief Send a attitude message
* @brief Pack a attitude 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 usec Timestamp (microseconds)
* @param roll Roll angle (rad)
@ -33,38 +36,73 @@ static inline uint16_t mavlink_msg_attitude_pack(uint8_t system_id, uint8_t comp
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_ATTITUDE;
i += put_uint64_t_by_index(usec, i, msg->payload); //Timestamp (microseconds)
i += put_float_by_index(roll, i, msg->payload); //Roll angle (rad)
i += put_float_by_index(pitch, i, msg->payload); //Pitch angle (rad)
i += put_float_by_index(yaw, i, msg->payload); //Yaw angle (rad)
i += put_float_by_index(rollspeed, i, msg->payload); //Roll angular speed (rad/s)
i += put_float_by_index(pitchspeed, i, msg->payload); //Pitch angular speed (rad/s)
i += put_float_by_index(yawspeed, i, msg->payload); //Yaw angular speed (rad/s)
i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds)
i += put_float_by_index(roll, i, msg->payload); // Roll angle (rad)
i += put_float_by_index(pitch, i, msg->payload); // Pitch angle (rad)
i += put_float_by_index(yaw, i, msg->payload); // Yaw angle (rad)
i += put_float_by_index(rollspeed, i, msg->payload); // Roll angular speed (rad/s)
i += put_float_by_index(pitchspeed, i, msg->payload); // Pitch angular speed (rad/s)
i += put_float_by_index(yawspeed, i, msg->payload); // Yaw angular speed (rad/s)
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a attitude 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 usec Timestamp (microseconds)
* @param roll Roll angle (rad)
* @param pitch Pitch angle (rad)
* @param yaw Yaw angle (rad)
* @param rollspeed Roll angular speed (rad/s)
* @param pitchspeed Pitch angular speed (rad/s)
* @param yawspeed Yaw angular speed (rad/s)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_attitude_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint64_t usec, float roll, float pitch, float yaw, float rollspeed, float pitchspeed, float yawspeed)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_ATTITUDE;
i += put_uint64_t_by_index(usec, i, msg->payload); //Timestamp (microseconds)
i += put_float_by_index(roll, i, msg->payload); //Roll angle (rad)
i += put_float_by_index(pitch, i, msg->payload); //Pitch angle (rad)
i += put_float_by_index(yaw, i, msg->payload); //Yaw angle (rad)
i += put_float_by_index(rollspeed, i, msg->payload); //Roll angular speed (rad/s)
i += put_float_by_index(pitchspeed, i, msg->payload); //Pitch angular speed (rad/s)
i += put_float_by_index(yawspeed, i, msg->payload); //Yaw angular speed (rad/s)
i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds)
i += put_float_by_index(roll, i, msg->payload); // Roll angle (rad)
i += put_float_by_index(pitch, i, msg->payload); // Pitch angle (rad)
i += put_float_by_index(yaw, i, msg->payload); // Yaw angle (rad)
i += put_float_by_index(rollspeed, i, msg->payload); // Roll angular speed (rad/s)
i += put_float_by_index(pitchspeed, i, msg->payload); // Pitch angular speed (rad/s)
i += put_float_by_index(yawspeed, i, msg->payload); // Yaw angular speed (rad/s)
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a attitude 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 attitude C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_attitude_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_attitude_t* attitude)
{
return mavlink_msg_attitude_pack(system_id, component_id, msg, attitude->usec, attitude->roll, attitude->pitch, attitude->yaw, attitude->rollspeed, attitude->pitchspeed, attitude->yawspeed);
}
/**
* @brief Send a attitude message
* @param chan MAVLink channel to send the message
*
* @param usec Timestamp (microseconds)
* @param roll Roll angle (rad)
* @param pitch Pitch angle (rad)
* @param yaw Yaw angle (rad)
* @param rollspeed Roll angular speed (rad/s)
* @param pitchspeed Pitch angular speed (rad/s)
* @param yawspeed Yaw angular speed (rad/s)
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_attitude_send(mavlink_channel_t chan, uint64_t usec, float roll, float pitch, float yaw, float rollspeed, float pitchspeed, float yawspeed)
@ -186,6 +224,12 @@ static inline float mavlink_msg_attitude_get_yawspeed(const mavlink_message_t* m
return (float)r.f;
}
/**
* @brief Decode a attitude message into a struct
*
* @param msg The message to decode
* @param attitude C-struct to decode the message contents into
*/
static inline void mavlink_msg_attitude_decode(const mavlink_message_t* msg, mavlink_attitude_t* attitude)
{
attitude->usec = mavlink_msg_attitude_get_usec(msg);

View File

@ -15,7 +15,10 @@ typedef struct __mavlink_attitude_controller_output_t
/**
* @brief Send a attitude_controller_output message
* @brief Pack a attitude_controller_output 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 enabled 1: enabled, 0: disabled
* @param roll Attitude roll: -128: -100%, 127: +100%
@ -29,34 +32,65 @@ static inline uint16_t mavlink_msg_attitude_controller_output_pack(uint8_t syste
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_ATTITUDE_CONTROLLER_OUTPUT;
i += put_uint8_t_by_index(enabled, i, msg->payload); //1: enabled, 0: disabled
i += put_int8_t_by_index(roll, i, msg->payload); //Attitude roll: -128: -100%, 127: +100%
i += put_int8_t_by_index(pitch, i, msg->payload); //Attitude pitch: -128: -100%, 127: +100%
i += put_int8_t_by_index(yaw, i, msg->payload); //Attitude yaw: -128: -100%, 127: +100%
i += put_int8_t_by_index(thrust, i, msg->payload); //Attitude thrust: -128: -100%, 127: +100%
i += put_uint8_t_by_index(enabled, i, msg->payload); // 1: enabled, 0: disabled
i += put_int8_t_by_index(roll, i, msg->payload); // Attitude roll: -128: -100%, 127: +100%
i += put_int8_t_by_index(pitch, i, msg->payload); // Attitude pitch: -128: -100%, 127: +100%
i += put_int8_t_by_index(yaw, i, msg->payload); // Attitude yaw: -128: -100%, 127: +100%
i += put_int8_t_by_index(thrust, i, msg->payload); // Attitude thrust: -128: -100%, 127: +100%
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a attitude_controller_output 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 enabled 1: enabled, 0: disabled
* @param roll Attitude roll: -128: -100%, 127: +100%
* @param pitch Attitude pitch: -128: -100%, 127: +100%
* @param yaw Attitude yaw: -128: -100%, 127: +100%
* @param thrust Attitude thrust: -128: -100%, 127: +100%
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_attitude_controller_output_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t enabled, int8_t roll, int8_t pitch, int8_t yaw, int8_t thrust)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_ATTITUDE_CONTROLLER_OUTPUT;
i += put_uint8_t_by_index(enabled, i, msg->payload); //1: enabled, 0: disabled
i += put_int8_t_by_index(roll, i, msg->payload); //Attitude roll: -128: -100%, 127: +100%
i += put_int8_t_by_index(pitch, i, msg->payload); //Attitude pitch: -128: -100%, 127: +100%
i += put_int8_t_by_index(yaw, i, msg->payload); //Attitude yaw: -128: -100%, 127: +100%
i += put_int8_t_by_index(thrust, i, msg->payload); //Attitude thrust: -128: -100%, 127: +100%
i += put_uint8_t_by_index(enabled, i, msg->payload); // 1: enabled, 0: disabled
i += put_int8_t_by_index(roll, i, msg->payload); // Attitude roll: -128: -100%, 127: +100%
i += put_int8_t_by_index(pitch, i, msg->payload); // Attitude pitch: -128: -100%, 127: +100%
i += put_int8_t_by_index(yaw, i, msg->payload); // Attitude yaw: -128: -100%, 127: +100%
i += put_int8_t_by_index(thrust, i, msg->payload); // Attitude thrust: -128: -100%, 127: +100%
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a attitude_controller_output 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 attitude_controller_output C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_attitude_controller_output_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_attitude_controller_output_t* attitude_controller_output)
{
return mavlink_msg_attitude_controller_output_pack(system_id, component_id, msg, attitude_controller_output->enabled, attitude_controller_output->roll, attitude_controller_output->pitch, attitude_controller_output->yaw, attitude_controller_output->thrust);
}
/**
* @brief Send a attitude_controller_output message
* @param chan MAVLink channel to send the message
*
* @param enabled 1: enabled, 0: disabled
* @param roll Attitude roll: -128: -100%, 127: +100%
* @param pitch Attitude pitch: -128: -100%, 127: +100%
* @param yaw Attitude yaw: -128: -100%, 127: +100%
* @param thrust Attitude thrust: -128: -100%, 127: +100%
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_attitude_controller_output_send(mavlink_channel_t chan, uint8_t enabled, int8_t roll, int8_t pitch, int8_t yaw, int8_t thrust)
@ -119,6 +153,12 @@ static inline int8_t mavlink_msg_attitude_controller_output_get_thrust(const mav
return (int8_t)(msg->payload+sizeof(uint8_t)+sizeof(int8_t)+sizeof(int8_t)+sizeof(int8_t))[0];
}
/**
* @brief Decode a attitude_controller_output message into a struct
*
* @param msg The message to decode
* @param attitude_controller_output C-struct to decode the message contents into
*/
static inline void mavlink_msg_attitude_controller_output_decode(const mavlink_message_t* msg, mavlink_attitude_controller_output_t* attitude_controller_output)
{
attitude_controller_output->enabled = mavlink_msg_attitude_controller_output_get_enabled(msg);

View File

@ -11,7 +11,10 @@ typedef struct __mavlink_boot_t
/**
* @brief Send a boot message
* @brief Pack a boot 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 version The onboard software version
* @return length of the message in bytes (excluding serial stream start sign)
@ -21,26 +24,49 @@ static inline uint16_t mavlink_msg_boot_pack(uint8_t system_id, uint8_t componen
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_BOOT;
i += put_uint32_t_by_index(version, i, msg->payload); //The onboard software version
i += put_uint32_t_by_index(version, i, msg->payload); // The onboard software version
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a boot 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 version The onboard software version
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_boot_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint32_t version)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_BOOT;
i += put_uint32_t_by_index(version, i, msg->payload); //The onboard software version
i += put_uint32_t_by_index(version, i, msg->payload); // The onboard software version
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a boot 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 boot C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_boot_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_boot_t* boot)
{
return mavlink_msg_boot_pack(system_id, component_id, msg, boot->version);
}
/**
* @brief Send a boot message
* @param chan MAVLink channel to send the message
*
* @param version The onboard software version
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_boot_send(mavlink_channel_t chan, uint32_t version)
@ -68,6 +94,12 @@ static inline uint32_t mavlink_msg_boot_get_version(const mavlink_message_t* msg
return (uint32_t)r.i;
}
/**
* @brief Decode a boot message into a struct
*
* @param msg The message to decode
* @param boot C-struct to decode the message contents into
*/
static inline void mavlink_msg_boot_decode(const mavlink_message_t* msg, mavlink_boot_t* boot)
{
boot->version = mavlink_msg_boot_get_version(msg);

View File

@ -12,7 +12,10 @@ typedef struct __mavlink_debug_t
/**
* @brief Send a debug message
* @brief Pack a debug 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 ind index of debug variable
* @param value DEBUG value
@ -23,28 +26,53 @@ static inline uint16_t mavlink_msg_debug_pack(uint8_t system_id, uint8_t compone
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_DEBUG;
i += put_uint8_t_by_index(ind, i, msg->payload); //index of debug variable
i += put_float_by_index(value, i, msg->payload); //DEBUG value
i += put_uint8_t_by_index(ind, i, msg->payload); // index of debug variable
i += put_float_by_index(value, i, msg->payload); // DEBUG value
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a debug 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 ind index of debug variable
* @param value DEBUG value
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_debug_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t ind, float value)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_DEBUG;
i += put_uint8_t_by_index(ind, i, msg->payload); //index of debug variable
i += put_float_by_index(value, i, msg->payload); //DEBUG value
i += put_uint8_t_by_index(ind, i, msg->payload); // index of debug variable
i += put_float_by_index(value, i, msg->payload); // DEBUG value
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a debug 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 debug C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_debug_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_debug_t* debug)
{
return mavlink_msg_debug_pack(system_id, component_id, msg, debug->ind, debug->value);
}
/**
* @brief Send a debug message
* @param chan MAVLink channel to send the message
*
* @param ind index of debug variable
* @param value DEBUG value
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_debug_send(mavlink_channel_t chan, uint8_t ind, float value)
@ -82,6 +110,12 @@ static inline float mavlink_msg_debug_get_value(const mavlink_message_t* msg)
return (float)r.f;
}
/**
* @brief Decode a debug message into a struct
*
* @param msg The message to decode
* @param debug C-struct to decode the message contents into
*/
static inline void mavlink_msg_debug_decode(const mavlink_message_t* msg, mavlink_debug_t* debug)
{
debug->ind = mavlink_msg_debug_get_ind(msg);

View File

@ -16,7 +16,10 @@ typedef struct __mavlink_debug_vect_t
/**
* @brief Send a debug_vect message
* @brief Pack a debug_vect 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 name Name
* @param usec Timestamp
@ -30,34 +33,65 @@ static inline uint16_t mavlink_msg_debug_vect_pack(uint8_t system_id, uint8_t co
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_DEBUG_VECT;
i += put_array_by_index(name, 10, i, msg->payload); //Name
i += put_uint64_t_by_index(usec, i, msg->payload); //Timestamp
i += put_float_by_index(x, i, msg->payload); //x
i += put_float_by_index(y, i, msg->payload); //y
i += put_float_by_index(z, i, msg->payload); //z
i += put_array_by_index(name, 10, i, msg->payload); // Name
i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp
i += put_float_by_index(x, i, msg->payload); // x
i += put_float_by_index(y, i, msg->payload); // y
i += put_float_by_index(z, i, msg->payload); // z
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a debug_vect 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 name Name
* @param usec Timestamp
* @param x x
* @param y y
* @param z z
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_debug_vect_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const int8_t* name, uint64_t usec, float x, float y, float z)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_DEBUG_VECT;
i += put_array_by_index(name, 10, i, msg->payload); //Name
i += put_uint64_t_by_index(usec, i, msg->payload); //Timestamp
i += put_float_by_index(x, i, msg->payload); //x
i += put_float_by_index(y, i, msg->payload); //y
i += put_float_by_index(z, i, msg->payload); //z
i += put_array_by_index(name, 10, i, msg->payload); // Name
i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp
i += put_float_by_index(x, i, msg->payload); // x
i += put_float_by_index(y, i, msg->payload); // y
i += put_float_by_index(z, i, msg->payload); // z
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a debug_vect 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 debug_vect C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_debug_vect_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_debug_vect_t* debug_vect)
{
return mavlink_msg_debug_vect_pack(system_id, component_id, msg, debug_vect->name, debug_vect->usec, debug_vect->x, debug_vect->y, debug_vect->z);
}
/**
* @brief Send a debug_vect message
* @param chan MAVLink channel to send the message
*
* @param name Name
* @param usec Timestamp
* @param x x
* @param y y
* @param z z
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_debug_vect_send(mavlink_channel_t chan, const int8_t* name, uint64_t usec, float x, float y, float z)
@ -146,6 +180,12 @@ static inline float mavlink_msg_debug_vect_get_z(const mavlink_message_t* msg)
return (float)r.f;
}
/**
* @brief Decode a debug_vect message into a struct
*
* @param msg The message to decode
* @param debug_vect C-struct to decode the message contents into
*/
static inline void mavlink_msg_debug_vect_decode(const mavlink_message_t* msg, mavlink_debug_vect_t* debug_vect)
{
mavlink_msg_debug_vect_get_name(msg, debug_vect->name);

View File

@ -17,7 +17,10 @@ typedef struct __mavlink_global_position_t
/**
* @brief Send a global_position message
* @brief Pack a global_position 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 usec Timestamp (microseconds since unix epoch)
* @param lat X Position
@ -33,38 +36,73 @@ static inline uint16_t mavlink_msg_global_position_pack(uint8_t system_id, uint8
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION;
i += put_uint64_t_by_index(usec, i, msg->payload); //Timestamp (microseconds since unix epoch)
i += put_float_by_index(lat, i, msg->payload); //X Position
i += put_float_by_index(lon, i, msg->payload); //Y Position
i += put_float_by_index(alt, i, msg->payload); //Z Position
i += put_float_by_index(vx, i, msg->payload); //X Speed
i += put_float_by_index(vy, i, msg->payload); //Y Speed
i += put_float_by_index(vz, i, msg->payload); //Z Speed
i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since unix epoch)
i += put_float_by_index(lat, i, msg->payload); // X Position
i += put_float_by_index(lon, i, msg->payload); // Y Position
i += put_float_by_index(alt, i, msg->payload); // Z Position
i += put_float_by_index(vx, i, msg->payload); // X Speed
i += put_float_by_index(vy, i, msg->payload); // Y Speed
i += put_float_by_index(vz, i, msg->payload); // Z Speed
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a global_position 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 usec Timestamp (microseconds since unix epoch)
* @param lat X Position
* @param lon Y Position
* @param alt Z Position
* @param vx X Speed
* @param vy Y Speed
* @param vz Z Speed
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_global_position_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint64_t usec, float lat, float lon, float alt, float vx, float vy, float vz)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION;
i += put_uint64_t_by_index(usec, i, msg->payload); //Timestamp (microseconds since unix epoch)
i += put_float_by_index(lat, i, msg->payload); //X Position
i += put_float_by_index(lon, i, msg->payload); //Y Position
i += put_float_by_index(alt, i, msg->payload); //Z Position
i += put_float_by_index(vx, i, msg->payload); //X Speed
i += put_float_by_index(vy, i, msg->payload); //Y Speed
i += put_float_by_index(vz, i, msg->payload); //Z Speed
i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since unix epoch)
i += put_float_by_index(lat, i, msg->payload); // X Position
i += put_float_by_index(lon, i, msg->payload); // Y Position
i += put_float_by_index(alt, i, msg->payload); // Z Position
i += put_float_by_index(vx, i, msg->payload); // X Speed
i += put_float_by_index(vy, i, msg->payload); // Y Speed
i += put_float_by_index(vz, i, msg->payload); // Z Speed
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a global_position 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 global_position C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_global_position_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_global_position_t* global_position)
{
return mavlink_msg_global_position_pack(system_id, component_id, msg, global_position->usec, global_position->lat, global_position->lon, global_position->alt, global_position->vx, global_position->vy, global_position->vz);
}
/**
* @brief Send a global_position message
* @param chan MAVLink channel to send the message
*
* @param usec Timestamp (microseconds since unix epoch)
* @param lat X Position
* @param lon Y Position
* @param alt Z Position
* @param vx X Speed
* @param vy Y Speed
* @param vz Z Speed
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_global_position_send(mavlink_channel_t chan, uint64_t usec, float lat, float lon, float alt, float vx, float vy, float vz)
@ -186,6 +224,12 @@ static inline float mavlink_msg_global_position_get_vz(const mavlink_message_t*
return (float)r.f;
}
/**
* @brief Decode a global_position message into a struct
*
* @param msg The message to decode
* @param global_position C-struct to decode the message contents into
*/
static inline void mavlink_msg_global_position_decode(const mavlink_message_t* msg, mavlink_global_position_t* global_position)
{
global_position->usec = mavlink_msg_global_position_get_usec(msg);

View File

@ -0,0 +1,210 @@
// MESSAGE GLOBAL_POSITION_INT PACKING
#define MAVLINK_MSG_ID_GLOBAL_POSITION_INT 73
typedef struct __mavlink_global_position_int_t
{
int32_t lat; ///< Latitude / X Position, expressed as * 1E7
int32_t lon; ///< Longitude / Y Position, expressed as * 1E7
int32_t alt; ///< Altitude / negative Z Position, expressed as * 1000
int16_t vx; ///< Ground X Speed, expressed as m/s * 100
int16_t vy; ///< Ground Y Speed, expressed as m/s * 100
int16_t vz; ///< Ground Z Speed, expressed as m/s * 100
} mavlink_global_position_int_t;
/**
* @brief Pack a global_position_int 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 lat Latitude / X Position, expressed as * 1E7
* @param lon Longitude / Y Position, expressed as * 1E7
* @param alt Altitude / negative Z Position, expressed as * 1000
* @param vx Ground X Speed, expressed as m/s * 100
* @param vy Ground Y Speed, expressed as m/s * 100
* @param vz Ground Z Speed, expressed as m/s * 100
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_global_position_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION_INT;
i += put_int32_t_by_index(lat, i, msg->payload); // Latitude / X Position, expressed as * 1E7
i += put_int32_t_by_index(lon, i, msg->payload); // Longitude / Y Position, expressed as * 1E7
i += put_int32_t_by_index(alt, i, msg->payload); // Altitude / negative Z Position, expressed as * 1000
i += put_int16_t_by_index(vx, i, msg->payload); // Ground X Speed, expressed as m/s * 100
i += put_int16_t_by_index(vy, i, msg->payload); // Ground Y Speed, expressed as m/s * 100
i += put_int16_t_by_index(vz, i, msg->payload); // Ground Z Speed, expressed as m/s * 100
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a global_position_int 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 lat Latitude / X Position, expressed as * 1E7
* @param lon Longitude / Y Position, expressed as * 1E7
* @param alt Altitude / negative Z Position, expressed as * 1000
* @param vx Ground X Speed, expressed as m/s * 100
* @param vy Ground Y Speed, expressed as m/s * 100
* @param vz Ground Z Speed, expressed as m/s * 100
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_global_position_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION_INT;
i += put_int32_t_by_index(lat, i, msg->payload); // Latitude / X Position, expressed as * 1E7
i += put_int32_t_by_index(lon, i, msg->payload); // Longitude / Y Position, expressed as * 1E7
i += put_int32_t_by_index(alt, i, msg->payload); // Altitude / negative Z Position, expressed as * 1000
i += put_int16_t_by_index(vx, i, msg->payload); // Ground X Speed, expressed as m/s * 100
i += put_int16_t_by_index(vy, i, msg->payload); // Ground Y Speed, expressed as m/s * 100
i += put_int16_t_by_index(vz, i, msg->payload); // Ground Z Speed, expressed as m/s * 100
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a global_position_int 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 global_position_int C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_global_position_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_global_position_int_t* global_position_int)
{
return mavlink_msg_global_position_int_pack(system_id, component_id, msg, global_position_int->lat, global_position_int->lon, global_position_int->alt, global_position_int->vx, global_position_int->vy, global_position_int->vz);
}
/**
* @brief Send a global_position_int message
* @param chan MAVLink channel to send the message
*
* @param lat Latitude / X Position, expressed as * 1E7
* @param lon Longitude / Y Position, expressed as * 1E7
* @param alt Altitude / negative Z Position, expressed as * 1000
* @param vx Ground X Speed, expressed as m/s * 100
* @param vy Ground Y Speed, expressed as m/s * 100
* @param vz Ground Z Speed, expressed as m/s * 100
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_global_position_int_send(mavlink_channel_t chan, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz)
{
mavlink_message_t msg;
mavlink_msg_global_position_int_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, lat, lon, alt, vx, vy, vz);
mavlink_send_uart(chan, &msg);
}
#endif
// MESSAGE GLOBAL_POSITION_INT UNPACKING
/**
* @brief Get field lat from global_position_int message
*
* @return Latitude / X Position, expressed as * 1E7
*/
static inline int32_t mavlink_msg_global_position_int_get_lat(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload)[0];
r.b[2] = (msg->payload)[1];
r.b[1] = (msg->payload)[2];
r.b[0] = (msg->payload)[3];
return (int32_t)r.i;
}
/**
* @brief Get field lon from global_position_int message
*
* @return Longitude / Y Position, expressed as * 1E7
*/
static inline int32_t mavlink_msg_global_position_int_get_lon(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(int32_t))[0];
r.b[2] = (msg->payload+sizeof(int32_t))[1];
r.b[1] = (msg->payload+sizeof(int32_t))[2];
r.b[0] = (msg->payload+sizeof(int32_t))[3];
return (int32_t)r.i;
}
/**
* @brief Get field alt from global_position_int message
*
* @return Altitude / negative Z Position, expressed as * 1000
*/
static inline int32_t mavlink_msg_global_position_int_get_alt(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(int32_t)+sizeof(int32_t))[0];
r.b[2] = (msg->payload+sizeof(int32_t)+sizeof(int32_t))[1];
r.b[1] = (msg->payload+sizeof(int32_t)+sizeof(int32_t))[2];
r.b[0] = (msg->payload+sizeof(int32_t)+sizeof(int32_t))[3];
return (int32_t)r.i;
}
/**
* @brief Get field vx from global_position_int message
*
* @return Ground X Speed, expressed as m/s * 100
*/
static inline int16_t mavlink_msg_global_position_int_get_vx(const mavlink_message_t* msg)
{
generic_16bit r;
r.b[1] = (msg->payload+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t))[0];
r.b[0] = (msg->payload+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t))[1];
return (int16_t)r.s;
}
/**
* @brief Get field vy from global_position_int message
*
* @return Ground Y Speed, expressed as m/s * 100
*/
static inline int16_t mavlink_msg_global_position_int_get_vy(const mavlink_message_t* msg)
{
generic_16bit r;
r.b[1] = (msg->payload+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int16_t))[0];
r.b[0] = (msg->payload+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int16_t))[1];
return (int16_t)r.s;
}
/**
* @brief Get field vz from global_position_int message
*
* @return Ground Z Speed, expressed as m/s * 100
*/
static inline int16_t mavlink_msg_global_position_int_get_vz(const mavlink_message_t* msg)
{
generic_16bit r;
r.b[1] = (msg->payload+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int16_t)+sizeof(int16_t))[0];
r.b[0] = (msg->payload+sizeof(int32_t)+sizeof(int32_t)+sizeof(int32_t)+sizeof(int16_t)+sizeof(int16_t))[1];
return (int16_t)r.s;
}
/**
* @brief Decode a global_position_int message into a struct
*
* @param msg The message to decode
* @param global_position_int C-struct to decode the message contents into
*/
static inline void mavlink_msg_global_position_int_decode(const mavlink_message_t* msg, mavlink_global_position_int_t* global_position_int)
{
global_position_int->lat = mavlink_msg_global_position_int_get_lat(msg);
global_position_int->lon = mavlink_msg_global_position_int_get_lon(msg);
global_position_int->alt = mavlink_msg_global_position_int_get_alt(msg);
global_position_int->vx = mavlink_msg_global_position_int_get_vx(msg);
global_position_int->vy = mavlink_msg_global_position_int_get_vy(msg);
global_position_int->vz = mavlink_msg_global_position_int_get_vz(msg);
}

View File

@ -4,69 +4,87 @@
typedef struct __mavlink_gps_local_origin_set_t
{
float latitude; ///< Latitude (WGS84)
float longitude; ///< Longitude (WGS84)
float altitude; ///< Altitude(WGS84)
float x; ///< Local X coordinate in meters
float y; ///< Local Y coordinate in meters
float z; ///< Local Z coordinate in meters
int32_t latitude; ///< Latitude (WGS84), expressed as * 1E7
int32_t longitude; ///< Longitude (WGS84), expressed as * 1E7
int32_t altitude; ///< Altitude(WGS84), expressed as * 1000
} mavlink_gps_local_origin_set_t;
/**
* @brief Send a gps_local_origin_set message
* @brief Pack a gps_local_origin_set 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 latitude Latitude (WGS84)
* @param longitude Longitude (WGS84)
* @param altitude Altitude(WGS84)
* @param x Local X coordinate in meters
* @param y Local Y coordinate in meters
* @param z Local Z coordinate in meters
* @param latitude Latitude (WGS84), expressed as * 1E7
* @param longitude Longitude (WGS84), expressed as * 1E7
* @param altitude Altitude(WGS84), expressed as * 1000
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_gps_local_origin_set_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, float latitude, float longitude, float altitude, float x, float y, float z)
static inline uint16_t mavlink_msg_gps_local_origin_set_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, int32_t latitude, int32_t longitude, int32_t altitude)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_GPS_LOCAL_ORIGIN_SET;
i += put_float_by_index(latitude, i, msg->payload); //Latitude (WGS84)
i += put_float_by_index(longitude, i, msg->payload); //Longitude (WGS84)
i += put_float_by_index(altitude, i, msg->payload); //Altitude(WGS84)
i += put_float_by_index(x, i, msg->payload); //Local X coordinate in meters
i += put_float_by_index(y, i, msg->payload); //Local Y coordinate in meters
i += put_float_by_index(z, i, msg->payload); //Local Z coordinate in meters
i += put_int32_t_by_index(latitude, i, msg->payload); // Latitude (WGS84), expressed as * 1E7
i += put_int32_t_by_index(longitude, i, msg->payload); // Longitude (WGS84), expressed as * 1E7
i += put_int32_t_by_index(altitude, i, msg->payload); // Altitude(WGS84), expressed as * 1000
return mavlink_finalize_message(msg, system_id, component_id, i);
}
static inline uint16_t mavlink_msg_gps_local_origin_set_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, float latitude, float longitude, float altitude, float x, float y, float z)
/**
* @brief Pack a gps_local_origin_set 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 latitude Latitude (WGS84), expressed as * 1E7
* @param longitude Longitude (WGS84), expressed as * 1E7
* @param altitude Altitude(WGS84), expressed as * 1000
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_gps_local_origin_set_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, int32_t latitude, int32_t longitude, int32_t altitude)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_GPS_LOCAL_ORIGIN_SET;
i += put_float_by_index(latitude, i, msg->payload); //Latitude (WGS84)
i += put_float_by_index(longitude, i, msg->payload); //Longitude (WGS84)
i += put_float_by_index(altitude, i, msg->payload); //Altitude(WGS84)
i += put_float_by_index(x, i, msg->payload); //Local X coordinate in meters
i += put_float_by_index(y, i, msg->payload); //Local Y coordinate in meters
i += put_float_by_index(z, i, msg->payload); //Local Z coordinate in meters
i += put_int32_t_by_index(latitude, i, msg->payload); // Latitude (WGS84), expressed as * 1E7
i += put_int32_t_by_index(longitude, i, msg->payload); // Longitude (WGS84), expressed as * 1E7
i += put_int32_t_by_index(altitude, i, msg->payload); // Altitude(WGS84), expressed as * 1000
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a gps_local_origin_set 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 gps_local_origin_set C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_gps_local_origin_set_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_local_origin_set_t* gps_local_origin_set)
{
return mavlink_msg_gps_local_origin_set_pack(system_id, component_id, msg, gps_local_origin_set->latitude, gps_local_origin_set->longitude, gps_local_origin_set->altitude, gps_local_origin_set->x, gps_local_origin_set->y, gps_local_origin_set->z);
return mavlink_msg_gps_local_origin_set_pack(system_id, component_id, msg, gps_local_origin_set->latitude, gps_local_origin_set->longitude, gps_local_origin_set->altitude);
}
/**
* @brief Send a gps_local_origin_set message
* @param chan MAVLink channel to send the message
*
* @param latitude Latitude (WGS84), expressed as * 1E7
* @param longitude Longitude (WGS84), expressed as * 1E7
* @param altitude Altitude(WGS84), expressed as * 1000
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_gps_local_origin_set_send(mavlink_channel_t chan, float latitude, float longitude, float altitude, float x, float y, float z)
static inline void mavlink_msg_gps_local_origin_set_send(mavlink_channel_t chan, int32_t latitude, int32_t longitude, int32_t altitude)
{
mavlink_message_t msg;
mavlink_msg_gps_local_origin_set_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, latitude, longitude, altitude, x, y, z);
mavlink_msg_gps_local_origin_set_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, latitude, longitude, altitude);
mavlink_send_uart(chan, &msg);
}
@ -76,99 +94,57 @@ static inline void mavlink_msg_gps_local_origin_set_send(mavlink_channel_t chan,
/**
* @brief Get field latitude from gps_local_origin_set message
*
* @return Latitude (WGS84)
* @return Latitude (WGS84), expressed as * 1E7
*/
static inline float mavlink_msg_gps_local_origin_set_get_latitude(const mavlink_message_t* msg)
static inline int32_t mavlink_msg_gps_local_origin_set_get_latitude(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload)[0];
r.b[2] = (msg->payload)[1];
r.b[1] = (msg->payload)[2];
r.b[0] = (msg->payload)[3];
return (float)r.f;
return (int32_t)r.i;
}
/**
* @brief Get field longitude from gps_local_origin_set message
*
* @return Longitude (WGS84)
* @return Longitude (WGS84), expressed as * 1E7
*/
static inline float mavlink_msg_gps_local_origin_set_get_longitude(const mavlink_message_t* msg)
static inline int32_t mavlink_msg_gps_local_origin_set_get_longitude(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(float))[3];
return (float)r.f;
r.b[3] = (msg->payload+sizeof(int32_t))[0];
r.b[2] = (msg->payload+sizeof(int32_t))[1];
r.b[1] = (msg->payload+sizeof(int32_t))[2];
r.b[0] = (msg->payload+sizeof(int32_t))[3];
return (int32_t)r.i;
}
/**
* @brief Get field altitude from gps_local_origin_set message
*
* @return Altitude(WGS84)
* @return Altitude(WGS84), expressed as * 1000
*/
static inline float mavlink_msg_gps_local_origin_set_get_altitude(const mavlink_message_t* msg)
static inline int32_t mavlink_msg_gps_local_origin_set_get_altitude(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(float)+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(float)+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(float)+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(float)+sizeof(float))[3];
return (float)r.f;
r.b[3] = (msg->payload+sizeof(int32_t)+sizeof(int32_t))[0];
r.b[2] = (msg->payload+sizeof(int32_t)+sizeof(int32_t))[1];
r.b[1] = (msg->payload+sizeof(int32_t)+sizeof(int32_t))[2];
r.b[0] = (msg->payload+sizeof(int32_t)+sizeof(int32_t))[3];
return (int32_t)r.i;
}
/**
* @brief Get field x from gps_local_origin_set message
* @brief Decode a gps_local_origin_set message into a struct
*
* @return Local X coordinate in meters
* @param msg The message to decode
* @param gps_local_origin_set C-struct to decode the message contents into
*/
static inline float mavlink_msg_gps_local_origin_set_get_x(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float))[3];
return (float)r.f;
}
/**
* @brief Get field y from gps_local_origin_set message
*
* @return Local Y coordinate in meters
*/
static inline float mavlink_msg_gps_local_origin_set_get_y(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
return (float)r.f;
}
/**
* @brief Get field z from gps_local_origin_set message
*
* @return Local Z coordinate in meters
*/
static inline float mavlink_msg_gps_local_origin_set_get_z(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
return (float)r.f;
}
static inline void mavlink_msg_gps_local_origin_set_decode(const mavlink_message_t* msg, mavlink_gps_local_origin_set_t* gps_local_origin_set)
{
gps_local_origin_set->latitude = mavlink_msg_gps_local_origin_set_get_latitude(msg);
gps_local_origin_set->longitude = mavlink_msg_gps_local_origin_set_get_longitude(msg);
gps_local_origin_set->altitude = mavlink_msg_gps_local_origin_set_get_altitude(msg);
gps_local_origin_set->x = mavlink_msg_gps_local_origin_set_get_x(msg);
gps_local_origin_set->y = mavlink_msg_gps_local_origin_set_get_y(msg);
gps_local_origin_set->z = mavlink_msg_gps_local_origin_set_get_z(msg);
}

View File

@ -19,7 +19,10 @@ typedef struct __mavlink_gps_raw_t
/**
* @brief Send a gps_raw message
* @brief Pack a gps_raw 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 usec Timestamp (microseconds since unix epoch)
* @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix
@ -37,42 +40,81 @@ static inline uint16_t mavlink_msg_gps_raw_pack(uint8_t system_id, uint8_t compo
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_GPS_RAW;
i += put_uint64_t_by_index(usec, i, msg->payload); //Timestamp (microseconds since unix epoch)
i += put_uint8_t_by_index(fix_type, i, msg->payload); //0-1: no fix, 2: 2D fix, 3: 3D fix
i += put_float_by_index(lat, i, msg->payload); //X Position
i += put_float_by_index(lon, i, msg->payload); //Y Position
i += put_float_by_index(alt, i, msg->payload); //Z Position in meters
i += put_float_by_index(eph, i, msg->payload); //Uncertainty in meters of latitude
i += put_float_by_index(epv, i, msg->payload); //Uncertainty in meters of longitude
i += put_float_by_index(v, i, msg->payload); //Overall speed
i += put_float_by_index(hdg, i, msg->payload); //Heading, in FIXME
i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since unix epoch)
i += put_uint8_t_by_index(fix_type, i, msg->payload); // 0-1: no fix, 2: 2D fix, 3: 3D fix
i += put_float_by_index(lat, i, msg->payload); // X Position
i += put_float_by_index(lon, i, msg->payload); // Y Position
i += put_float_by_index(alt, i, msg->payload); // Z Position in meters
i += put_float_by_index(eph, i, msg->payload); // Uncertainty in meters of latitude
i += put_float_by_index(epv, i, msg->payload); // Uncertainty in meters of longitude
i += put_float_by_index(v, i, msg->payload); // Overall speed
i += put_float_by_index(hdg, i, msg->payload); // Heading, in FIXME
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a gps_raw 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 usec Timestamp (microseconds since unix epoch)
* @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix
* @param lat X Position
* @param lon Y Position
* @param alt Z Position in meters
* @param eph Uncertainty in meters of latitude
* @param epv Uncertainty in meters of longitude
* @param v Overall speed
* @param hdg Heading, in FIXME
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_gps_raw_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint64_t usec, uint8_t fix_type, float lat, float lon, float alt, float eph, float epv, float v, float hdg)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_GPS_RAW;
i += put_uint64_t_by_index(usec, i, msg->payload); //Timestamp (microseconds since unix epoch)
i += put_uint8_t_by_index(fix_type, i, msg->payload); //0-1: no fix, 2: 2D fix, 3: 3D fix
i += put_float_by_index(lat, i, msg->payload); //X Position
i += put_float_by_index(lon, i, msg->payload); //Y Position
i += put_float_by_index(alt, i, msg->payload); //Z Position in meters
i += put_float_by_index(eph, i, msg->payload); //Uncertainty in meters of latitude
i += put_float_by_index(epv, i, msg->payload); //Uncertainty in meters of longitude
i += put_float_by_index(v, i, msg->payload); //Overall speed
i += put_float_by_index(hdg, i, msg->payload); //Heading, in FIXME
i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since unix epoch)
i += put_uint8_t_by_index(fix_type, i, msg->payload); // 0-1: no fix, 2: 2D fix, 3: 3D fix
i += put_float_by_index(lat, i, msg->payload); // X Position
i += put_float_by_index(lon, i, msg->payload); // Y Position
i += put_float_by_index(alt, i, msg->payload); // Z Position in meters
i += put_float_by_index(eph, i, msg->payload); // Uncertainty in meters of latitude
i += put_float_by_index(epv, i, msg->payload); // Uncertainty in meters of longitude
i += put_float_by_index(v, i, msg->payload); // Overall speed
i += put_float_by_index(hdg, i, msg->payload); // Heading, in FIXME
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a gps_raw 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 gps_raw C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_gps_raw_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_raw_t* gps_raw)
{
return mavlink_msg_gps_raw_pack(system_id, component_id, msg, gps_raw->usec, gps_raw->fix_type, gps_raw->lat, gps_raw->lon, gps_raw->alt, gps_raw->eph, gps_raw->epv, gps_raw->v, gps_raw->hdg);
}
/**
* @brief Send a gps_raw message
* @param chan MAVLink channel to send the message
*
* @param usec Timestamp (microseconds since unix epoch)
* @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix
* @param lat X Position
* @param lon Y Position
* @param alt Z Position in meters
* @param eph Uncertainty in meters of latitude
* @param epv Uncertainty in meters of longitude
* @param v Overall speed
* @param hdg Heading, in FIXME
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_gps_raw_send(mavlink_channel_t chan, uint64_t usec, uint8_t fix_type, float lat, float lon, float alt, float eph, float epv, float v, float hdg)
@ -219,6 +261,12 @@ static inline float mavlink_msg_gps_raw_get_hdg(const mavlink_message_t* msg)
return (float)r.f;
}
/**
* @brief Decode a gps_raw message into a struct
*
* @param msg The message to decode
* @param gps_raw C-struct to decode the message contents into
*/
static inline void mavlink_msg_gps_raw_decode(const mavlink_message_t* msg, mavlink_gps_raw_t* gps_raw)
{
gps_raw->usec = mavlink_msg_gps_raw_get_usec(msg);

View File

@ -21,7 +21,10 @@ typedef struct __mavlink_gps_status_t
/**
* @brief Send a gps_status message
* @brief Pack a gps_status 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 satellites_visible Number of satellites visible
* @param satellite_prn Global satellite ID
@ -36,36 +39,69 @@ static inline uint16_t mavlink_msg_gps_status_pack(uint8_t system_id, uint8_t co
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_GPS_STATUS;
i += put_uint8_t_by_index(satellites_visible, i, msg->payload); //Number of satellites visible
i += put_array_by_index(satellite_prn, 20, i, msg->payload); //Global satellite ID
i += put_array_by_index(satellite_used, 20, i, msg->payload); //0: Satellite not used, 1: used for localization
i += put_array_by_index(satellite_elevation, 20, i, msg->payload); //Elevation (0: right on top of receiver, 90: on the horizon) of satellite
i += put_array_by_index(satellite_azimuth, 20, i, msg->payload); //Direction of satellite, 0: 0 deg, 255: 360 deg.
i += put_array_by_index(satellite_snr, 20, i, msg->payload); //Signal to noise ratio of satellite
i += put_uint8_t_by_index(satellites_visible, i, msg->payload); // Number of satellites visible
i += put_array_by_index(satellite_prn, 20, i, msg->payload); // Global satellite ID
i += put_array_by_index(satellite_used, 20, i, msg->payload); // 0: Satellite not used, 1: used for localization
i += put_array_by_index(satellite_elevation, 20, i, msg->payload); // Elevation (0: right on top of receiver, 90: on the horizon) of satellite
i += put_array_by_index(satellite_azimuth, 20, i, msg->payload); // Direction of satellite, 0: 0 deg, 255: 360 deg.
i += put_array_by_index(satellite_snr, 20, i, msg->payload); // Signal to noise ratio of satellite
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a gps_status 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 satellites_visible Number of satellites visible
* @param satellite_prn Global satellite ID
* @param satellite_used 0: Satellite not used, 1: used for localization
* @param satellite_elevation Elevation (0: right on top of receiver, 90: on the horizon) of satellite
* @param satellite_azimuth Direction of satellite, 0: 0 deg, 255: 360 deg.
* @param satellite_snr Signal to noise ratio of satellite
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_gps_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t satellites_visible, const int8_t* satellite_prn, const int8_t* satellite_used, const int8_t* satellite_elevation, const int8_t* satellite_azimuth, const int8_t* satellite_snr)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_GPS_STATUS;
i += put_uint8_t_by_index(satellites_visible, i, msg->payload); //Number of satellites visible
i += put_array_by_index(satellite_prn, 20, i, msg->payload); //Global satellite ID
i += put_array_by_index(satellite_used, 20, i, msg->payload); //0: Satellite not used, 1: used for localization
i += put_array_by_index(satellite_elevation, 20, i, msg->payload); //Elevation (0: right on top of receiver, 90: on the horizon) of satellite
i += put_array_by_index(satellite_azimuth, 20, i, msg->payload); //Direction of satellite, 0: 0 deg, 255: 360 deg.
i += put_array_by_index(satellite_snr, 20, i, msg->payload); //Signal to noise ratio of satellite
i += put_uint8_t_by_index(satellites_visible, i, msg->payload); // Number of satellites visible
i += put_array_by_index(satellite_prn, 20, i, msg->payload); // Global satellite ID
i += put_array_by_index(satellite_used, 20, i, msg->payload); // 0: Satellite not used, 1: used for localization
i += put_array_by_index(satellite_elevation, 20, i, msg->payload); // Elevation (0: right on top of receiver, 90: on the horizon) of satellite
i += put_array_by_index(satellite_azimuth, 20, i, msg->payload); // Direction of satellite, 0: 0 deg, 255: 360 deg.
i += put_array_by_index(satellite_snr, 20, i, msg->payload); // Signal to noise ratio of satellite
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a gps_status 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 gps_status C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_gps_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_status_t* gps_status)
{
return mavlink_msg_gps_status_pack(system_id, component_id, msg, gps_status->satellites_visible, gps_status->satellite_prn, gps_status->satellite_used, gps_status->satellite_elevation, gps_status->satellite_azimuth, gps_status->satellite_snr);
}
/**
* @brief Send a gps_status message
* @param chan MAVLink channel to send the message
*
* @param satellites_visible Number of satellites visible
* @param satellite_prn Global satellite ID
* @param satellite_used 0: Satellite not used, 1: used for localization
* @param satellite_elevation Elevation (0: right on top of receiver, 90: on the horizon) of satellite
* @param satellite_azimuth Direction of satellite, 0: 0 deg, 255: 360 deg.
* @param satellite_snr Signal to noise ratio of satellite
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_gps_status_send(mavlink_channel_t chan, uint8_t satellites_visible, const int8_t* satellite_prn, const int8_t* satellite_used, const int8_t* satellite_elevation, const int8_t* satellite_azimuth, const int8_t* satellite_snr)
@ -148,6 +184,12 @@ static inline uint16_t mavlink_msg_gps_status_get_satellite_snr(const mavlink_me
return 20;
}
/**
* @brief Decode a gps_status message into a struct
*
* @param msg The message to decode
* @param gps_status C-struct to decode the message contents into
*/
static inline void mavlink_msg_gps_status_decode(const mavlink_message_t* msg, mavlink_gps_status_t* gps_status)
{
gps_status->satellites_visible = mavlink_msg_gps_status_get_satellites_visible(msg);

View File

@ -6,13 +6,17 @@ typedef struct __mavlink_heartbeat_t
{
uint8_t type; ///< Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
uint8_t autopilot; ///< Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM
uint8_t mavlink_version; ///< MAVLink version
} mavlink_heartbeat_t;
/**
* @brief Send a heartbeat message
* @brief Pack a heartbeat 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 type Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
* @param autopilot Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM
@ -23,28 +27,55 @@ static inline uint16_t mavlink_msg_heartbeat_pack(uint8_t system_id, uint8_t com
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_HEARTBEAT;
i += put_uint8_t_by_index(type, i, msg->payload); //Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
i += put_uint8_t_by_index(autopilot, i, msg->payload); //Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM
i += put_uint8_t_by_index(type, i, msg->payload); // Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
i += put_uint8_t_by_index(autopilot, i, msg->payload); // Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM
i += put_uint8_t_by_index(1, i, msg->payload); // MAVLink version
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a heartbeat 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 type Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
* @param autopilot Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_heartbeat_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t type, uint8_t autopilot)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_HEARTBEAT;
i += put_uint8_t_by_index(type, i, msg->payload); //Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
i += put_uint8_t_by_index(autopilot, i, msg->payload); //Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM
i += put_uint8_t_by_index(type, i, msg->payload); // Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
i += put_uint8_t_by_index(autopilot, i, msg->payload); // Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM
i += put_uint8_t_by_index(1, i, msg->payload); // MAVLink version
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a heartbeat 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 heartbeat C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_heartbeat_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_heartbeat_t* heartbeat)
{
return mavlink_msg_heartbeat_pack(system_id, component_id, msg, heartbeat->type, heartbeat->autopilot);
}
/**
* @brief Send a heartbeat message
* @param chan MAVLink channel to send the message
*
* @param type Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
* @param autopilot Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_heartbeat_send(mavlink_channel_t chan, uint8_t type, uint8_t autopilot)
@ -77,8 +108,25 @@ static inline uint8_t mavlink_msg_heartbeat_get_autopilot(const mavlink_message_
return (uint8_t)(msg->payload+sizeof(uint8_t))[0];
}
/**
* @brief Get field mavlink_version from heartbeat message
*
* @return MAVLink version
*/
static inline uint8_t mavlink_msg_heartbeat_get_mavlink_version(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0];
}
/**
* @brief Decode a heartbeat message into a struct
*
* @param msg The message to decode
* @param heartbeat C-struct to decode the message contents into
*/
static inline void mavlink_msg_heartbeat_decode(const mavlink_message_t* msg, mavlink_heartbeat_t* heartbeat)
{
heartbeat->type = mavlink_msg_heartbeat_get_type(msg);
heartbeat->autopilot = mavlink_msg_heartbeat_get_autopilot(msg);
heartbeat->mavlink_version = mavlink_msg_heartbeat_get_mavlink_version(msg);
}

View File

@ -17,7 +17,10 @@ typedef struct __mavlink_local_position_t
/**
* @brief Send a local_position message
* @brief Pack a local_position 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 usec Timestamp (microseconds since unix epoch)
* @param x X Position
@ -33,38 +36,73 @@ static inline uint16_t mavlink_msg_local_position_pack(uint8_t system_id, uint8_
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION;
i += put_uint64_t_by_index(usec, i, msg->payload); //Timestamp (microseconds since unix epoch)
i += put_float_by_index(x, i, msg->payload); //X Position
i += put_float_by_index(y, i, msg->payload); //Y Position
i += put_float_by_index(z, i, msg->payload); //Z Position
i += put_float_by_index(vx, i, msg->payload); //X Speed
i += put_float_by_index(vy, i, msg->payload); //Y Speed
i += put_float_by_index(vz, i, msg->payload); //Z Speed
i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since unix epoch)
i += put_float_by_index(x, i, msg->payload); // X Position
i += put_float_by_index(y, i, msg->payload); // Y Position
i += put_float_by_index(z, i, msg->payload); // Z Position
i += put_float_by_index(vx, i, msg->payload); // X Speed
i += put_float_by_index(vy, i, msg->payload); // Y Speed
i += put_float_by_index(vz, i, msg->payload); // Z Speed
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a local_position 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 usec Timestamp (microseconds since unix epoch)
* @param x X Position
* @param y Y Position
* @param z Z Position
* @param vx X Speed
* @param vy Y Speed
* @param vz Z Speed
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_local_position_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint64_t usec, float x, float y, float z, float vx, float vy, float vz)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION;
i += put_uint64_t_by_index(usec, i, msg->payload); //Timestamp (microseconds since unix epoch)
i += put_float_by_index(x, i, msg->payload); //X Position
i += put_float_by_index(y, i, msg->payload); //Y Position
i += put_float_by_index(z, i, msg->payload); //Z Position
i += put_float_by_index(vx, i, msg->payload); //X Speed
i += put_float_by_index(vy, i, msg->payload); //Y Speed
i += put_float_by_index(vz, i, msg->payload); //Z Speed
i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since unix epoch)
i += put_float_by_index(x, i, msg->payload); // X Position
i += put_float_by_index(y, i, msg->payload); // Y Position
i += put_float_by_index(z, i, msg->payload); // Z Position
i += put_float_by_index(vx, i, msg->payload); // X Speed
i += put_float_by_index(vy, i, msg->payload); // Y Speed
i += put_float_by_index(vz, i, msg->payload); // Z Speed
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a local_position 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 local_position C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_local_position_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_local_position_t* local_position)
{
return mavlink_msg_local_position_pack(system_id, component_id, msg, local_position->usec, local_position->x, local_position->y, local_position->z, local_position->vx, local_position->vy, local_position->vz);
}
/**
* @brief Send a local_position message
* @param chan MAVLink channel to send the message
*
* @param usec Timestamp (microseconds since unix epoch)
* @param x X Position
* @param y Y Position
* @param z Z Position
* @param vx X Speed
* @param vy Y Speed
* @param vz Z Speed
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_local_position_send(mavlink_channel_t chan, uint64_t usec, float x, float y, float z, float vx, float vy, float vz)
@ -186,6 +224,12 @@ static inline float mavlink_msg_local_position_get_vz(const mavlink_message_t* m
return (float)r.f;
}
/**
* @brief Decode a local_position message into a struct
*
* @param msg The message to decode
* @param local_position C-struct to decode the message contents into
*/
static inline void mavlink_msg_local_position_decode(const mavlink_message_t* msg, mavlink_local_position_t* local_position)
{
local_position->usec = mavlink_msg_local_position_get_usec(msg);

View File

@ -14,7 +14,10 @@ typedef struct __mavlink_local_position_setpoint_t
/**
* @brief Send a local_position_setpoint message
* @brief Pack a local_position_setpoint 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 x x position 1
* @param y y position 1
@ -27,32 +30,61 @@ static inline uint16_t mavlink_msg_local_position_setpoint_pack(uint8_t system_i
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT;
i += put_float_by_index(x, i, msg->payload); //x position 1
i += put_float_by_index(y, i, msg->payload); //y position 1
i += put_float_by_index(z, i, msg->payload); //z position 1
i += put_float_by_index(yaw, i, msg->payload); //x position 2
i += put_float_by_index(x, i, msg->payload); // x position 1
i += put_float_by_index(y, i, msg->payload); // y position 1
i += put_float_by_index(z, i, msg->payload); // z position 1
i += put_float_by_index(yaw, i, msg->payload); // x position 2
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a local_position_setpoint 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 x x position 1
* @param y y position 1
* @param z z position 1
* @param yaw x position 2
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_local_position_setpoint_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, float x, float y, float z, float yaw)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT;
i += put_float_by_index(x, i, msg->payload); //x position 1
i += put_float_by_index(y, i, msg->payload); //y position 1
i += put_float_by_index(z, i, msg->payload); //z position 1
i += put_float_by_index(yaw, i, msg->payload); //x position 2
i += put_float_by_index(x, i, msg->payload); // x position 1
i += put_float_by_index(y, i, msg->payload); // y position 1
i += put_float_by_index(z, i, msg->payload); // z position 1
i += put_float_by_index(yaw, i, msg->payload); // x position 2
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a local_position_setpoint 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 local_position_setpoint C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_local_position_setpoint_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_local_position_setpoint_t* local_position_setpoint)
{
return mavlink_msg_local_position_setpoint_pack(system_id, component_id, msg, local_position_setpoint->x, local_position_setpoint->y, local_position_setpoint->z, local_position_setpoint->yaw);
}
/**
* @brief Send a local_position_setpoint message
* @param chan MAVLink channel to send the message
*
* @param x x position 1
* @param y y position 1
* @param z z position 1
* @param yaw x position 2
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_local_position_setpoint_send(mavlink_channel_t chan, float x, float y, float z, float yaw)
@ -125,6 +157,12 @@ static inline float mavlink_msg_local_position_setpoint_get_yaw(const mavlink_me
return (float)r.f;
}
/**
* @brief Decode a local_position_setpoint message into a struct
*
* @param msg The message to decode
* @param local_position_setpoint C-struct to decode the message contents into
*/
static inline void mavlink_msg_local_position_setpoint_decode(const mavlink_message_t* msg, mavlink_local_position_setpoint_t* local_position_setpoint)
{
local_position_setpoint->x = mavlink_msg_local_position_setpoint_get_x(msg);

View File

@ -16,7 +16,10 @@ typedef struct __mavlink_local_position_setpoint_set_t
/**
* @brief Send a local_position_setpoint_set message
* @brief Pack a local_position_setpoint_set 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 target_system System ID
* @param target_component Component ID
@ -31,36 +34,69 @@ static inline uint16_t mavlink_msg_local_position_setpoint_set_pack(uint8_t syst
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_SET;
i += put_uint8_t_by_index(target_system, i, msg->payload); //System ID
i += put_uint8_t_by_index(target_component, i, msg->payload); //Component ID
i += put_float_by_index(x, i, msg->payload); //x position 1
i += put_float_by_index(y, i, msg->payload); //y position 1
i += put_float_by_index(z, i, msg->payload); //z position 1
i += put_float_by_index(yaw, i, msg->payload); //x position 2
i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID
i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID
i += put_float_by_index(x, i, msg->payload); // x position 1
i += put_float_by_index(y, i, msg->payload); // y position 1
i += put_float_by_index(z, i, msg->payload); // z position 1
i += put_float_by_index(yaw, i, msg->payload); // x position 2
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a local_position_setpoint_set 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 target_system System ID
* @param target_component Component ID
* @param x x position 1
* @param y y position 1
* @param z z position 1
* @param yaw x position 2
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_local_position_setpoint_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, float x, float y, float z, float yaw)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_SET;
i += put_uint8_t_by_index(target_system, i, msg->payload); //System ID
i += put_uint8_t_by_index(target_component, i, msg->payload); //Component ID
i += put_float_by_index(x, i, msg->payload); //x position 1
i += put_float_by_index(y, i, msg->payload); //y position 1
i += put_float_by_index(z, i, msg->payload); //z position 1
i += put_float_by_index(yaw, i, msg->payload); //x position 2
i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID
i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID
i += put_float_by_index(x, i, msg->payload); // x position 1
i += put_float_by_index(y, i, msg->payload); // y position 1
i += put_float_by_index(z, i, msg->payload); // z position 1
i += put_float_by_index(yaw, i, msg->payload); // x position 2
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a local_position_setpoint_set 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 local_position_setpoint_set C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_local_position_setpoint_set_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_local_position_setpoint_set_t* local_position_setpoint_set)
{
return mavlink_msg_local_position_setpoint_set_pack(system_id, component_id, msg, local_position_setpoint_set->target_system, local_position_setpoint_set->target_component, local_position_setpoint_set->x, local_position_setpoint_set->y, local_position_setpoint_set->z, local_position_setpoint_set->yaw);
}
/**
* @brief Send a local_position_setpoint_set message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID
* @param target_component Component ID
* @param x x position 1
* @param y y position 1
* @param z z position 1
* @param yaw x position 2
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_local_position_setpoint_set_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, float x, float y, float z, float yaw)
@ -153,6 +189,12 @@ static inline float mavlink_msg_local_position_setpoint_set_get_yaw(const mavlin
return (float)r.f;
}
/**
* @brief Decode a local_position_setpoint_set message into a struct
*
* @param msg The message to decode
* @param local_position_setpoint_set C-struct to decode the message contents into
*/
static inline void mavlink_msg_local_position_setpoint_set_decode(const mavlink_message_t* msg, mavlink_local_position_setpoint_set_t* local_position_setpoint_set)
{
local_position_setpoint_set->target_system = mavlink_msg_local_position_setpoint_set_get_target_system(msg);

View File

@ -19,7 +19,10 @@ typedef struct __mavlink_manual_control_t
/**
* @brief Send a manual_control message
* @brief Pack a manual_control 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 target The system to be controlled
* @param roll roll
@ -37,42 +40,81 @@ static inline uint16_t mavlink_msg_manual_control_pack(uint8_t system_id, uint8_
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_MANUAL_CONTROL;
i += put_uint8_t_by_index(target, i, msg->payload); //The system to be controlled
i += put_float_by_index(roll, i, msg->payload); //roll
i += put_float_by_index(pitch, i, msg->payload); //pitch
i += put_float_by_index(yaw, i, msg->payload); //yaw
i += put_float_by_index(thrust, i, msg->payload); //thrust
i += put_uint8_t_by_index(roll_manual, i, msg->payload); //roll control enabled auto:0, manual:1
i += put_uint8_t_by_index(pitch_manual, i, msg->payload); //pitch auto:0, manual:1
i += put_uint8_t_by_index(yaw_manual, i, msg->payload); //yaw auto:0, manual:1
i += put_uint8_t_by_index(thrust_manual, i, msg->payload); //thrust auto:0, manual:1
i += put_uint8_t_by_index(target, i, msg->payload); // The system to be controlled
i += put_float_by_index(roll, i, msg->payload); // roll
i += put_float_by_index(pitch, i, msg->payload); // pitch
i += put_float_by_index(yaw, i, msg->payload); // yaw
i += put_float_by_index(thrust, i, msg->payload); // thrust
i += put_uint8_t_by_index(roll_manual, i, msg->payload); // roll control enabled auto:0, manual:1
i += put_uint8_t_by_index(pitch_manual, i, msg->payload); // pitch auto:0, manual:1
i += put_uint8_t_by_index(yaw_manual, i, msg->payload); // yaw auto:0, manual:1
i += put_uint8_t_by_index(thrust_manual, i, msg->payload); // thrust auto:0, manual:1
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a manual_control 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 target The system to be controlled
* @param roll roll
* @param pitch pitch
* @param yaw yaw
* @param thrust thrust
* @param roll_manual roll control enabled auto:0, manual:1
* @param pitch_manual pitch auto:0, manual:1
* @param yaw_manual yaw auto:0, manual:1
* @param thrust_manual thrust auto:0, manual:1
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_manual_control_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target, float roll, float pitch, float yaw, float thrust, uint8_t roll_manual, uint8_t pitch_manual, uint8_t yaw_manual, uint8_t thrust_manual)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_MANUAL_CONTROL;
i += put_uint8_t_by_index(target, i, msg->payload); //The system to be controlled
i += put_float_by_index(roll, i, msg->payload); //roll
i += put_float_by_index(pitch, i, msg->payload); //pitch
i += put_float_by_index(yaw, i, msg->payload); //yaw
i += put_float_by_index(thrust, i, msg->payload); //thrust
i += put_uint8_t_by_index(roll_manual, i, msg->payload); //roll control enabled auto:0, manual:1
i += put_uint8_t_by_index(pitch_manual, i, msg->payload); //pitch auto:0, manual:1
i += put_uint8_t_by_index(yaw_manual, i, msg->payload); //yaw auto:0, manual:1
i += put_uint8_t_by_index(thrust_manual, i, msg->payload); //thrust auto:0, manual:1
i += put_uint8_t_by_index(target, i, msg->payload); // The system to be controlled
i += put_float_by_index(roll, i, msg->payload); // roll
i += put_float_by_index(pitch, i, msg->payload); // pitch
i += put_float_by_index(yaw, i, msg->payload); // yaw
i += put_float_by_index(thrust, i, msg->payload); // thrust
i += put_uint8_t_by_index(roll_manual, i, msg->payload); // roll control enabled auto:0, manual:1
i += put_uint8_t_by_index(pitch_manual, i, msg->payload); // pitch auto:0, manual:1
i += put_uint8_t_by_index(yaw_manual, i, msg->payload); // yaw auto:0, manual:1
i += put_uint8_t_by_index(thrust_manual, i, msg->payload); // thrust auto:0, manual:1
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a manual_control 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 manual_control C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_manual_control_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_manual_control_t* manual_control)
{
return mavlink_msg_manual_control_pack(system_id, component_id, msg, manual_control->target, manual_control->roll, manual_control->pitch, manual_control->yaw, manual_control->thrust, manual_control->roll_manual, manual_control->pitch_manual, manual_control->yaw_manual, manual_control->thrust_manual);
}
/**
* @brief Send a manual_control message
* @param chan MAVLink channel to send the message
*
* @param target The system to be controlled
* @param roll roll
* @param pitch pitch
* @param yaw yaw
* @param thrust thrust
* @param roll_manual roll control enabled auto:0, manual:1
* @param pitch_manual pitch auto:0, manual:1
* @param yaw_manual yaw auto:0, manual:1
* @param thrust_manual thrust auto:0, manual:1
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_manual_control_send(mavlink_channel_t chan, uint8_t target, float roll, float pitch, float yaw, float thrust, uint8_t roll_manual, uint8_t pitch_manual, uint8_t yaw_manual, uint8_t thrust_manual)
@ -195,6 +237,12 @@ static inline uint8_t mavlink_msg_manual_control_get_thrust_manual(const mavlink
return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[0];
}
/**
* @brief Decode a manual_control message into a struct
*
* @param msg The message to decode
* @param manual_control C-struct to decode the message contents into
*/
static inline void mavlink_msg_manual_control_decode(const mavlink_message_t* msg, mavlink_manual_control_t* manual_control)
{
manual_control->target = mavlink_msg_manual_control_get_target(msg);

View File

@ -12,7 +12,10 @@ typedef struct __mavlink_param_request_list_t
/**
* @brief Send a param_request_list message
* @brief Pack a param_request_list 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 target_system System ID
* @param target_component Component ID
@ -23,28 +26,53 @@ static inline uint16_t mavlink_msg_param_request_list_pack(uint8_t system_id, ui
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_PARAM_REQUEST_LIST;
i += put_uint8_t_by_index(target_system, i, msg->payload); //System ID
i += put_uint8_t_by_index(target_component, i, msg->payload); //Component ID
i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID
i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a param_request_list 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 target_system System ID
* @param target_component Component ID
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_param_request_list_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)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_PARAM_REQUEST_LIST;
i += put_uint8_t_by_index(target_system, i, msg->payload); //System ID
i += put_uint8_t_by_index(target_component, i, msg->payload); //Component ID
i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID
i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a param_request_list 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 param_request_list C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_param_request_list_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_param_request_list_t* param_request_list)
{
return mavlink_msg_param_request_list_pack(system_id, component_id, msg, param_request_list->target_system, param_request_list->target_component);
}
/**
* @brief Send a param_request_list message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID
* @param target_component Component ID
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_param_request_list_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component)
@ -77,6 +105,12 @@ static inline uint8_t mavlink_msg_param_request_list_get_target_component(const
return (uint8_t)(msg->payload+sizeof(uint8_t))[0];
}
/**
* @brief Decode a param_request_list message into a struct
*
* @param msg The message to decode
* @param param_request_list C-struct to decode the message contents into
*/
static inline void mavlink_msg_param_request_list_decode(const mavlink_message_t* msg, mavlink_param_request_list_t* param_request_list)
{
param_request_list->target_system = mavlink_msg_param_request_list_get_target_system(msg);

View File

@ -15,7 +15,10 @@ typedef struct __mavlink_param_request_read_t
/**
* @brief Send a param_request_read message
* @brief Pack a param_request_read 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 target_system System ID
* @param target_component Component ID
@ -28,32 +31,61 @@ static inline uint16_t mavlink_msg_param_request_read_pack(uint8_t system_id, ui
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_PARAM_REQUEST_READ;
i += put_uint8_t_by_index(target_system, i, msg->payload); //System ID
i += put_uint8_t_by_index(target_component, i, msg->payload); //Component ID
i += put_array_by_index(param_id, 15, i, msg->payload); //Onboard parameter id
i += put_uint16_t_by_index(param_index, i, msg->payload); //Parameter index
i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID
i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID
i += put_array_by_index(param_id, 15, i, msg->payload); // Onboard parameter id
i += put_uint16_t_by_index(param_index, i, msg->payload); // Parameter index
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a param_request_read 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 target_system System ID
* @param target_component Component ID
* @param param_id Onboard parameter id
* @param param_index Parameter index
* @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 int8_t* param_id, uint16_t param_index)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_PARAM_REQUEST_READ;
i += put_uint8_t_by_index(target_system, i, msg->payload); //System ID
i += put_uint8_t_by_index(target_component, i, msg->payload); //Component ID
i += put_array_by_index(param_id, 15, i, msg->payload); //Onboard parameter id
i += put_uint16_t_by_index(param_index, i, msg->payload); //Parameter index
i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID
i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID
i += put_array_by_index(param_id, 15, i, msg->payload); // Onboard parameter id
i += put_uint16_t_by_index(param_index, i, msg->payload); // Parameter index
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a param_request_read 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 param_request_read C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_param_request_read_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_param_request_read_t* param_request_read)
{
return mavlink_msg_param_request_read_pack(system_id, component_id, msg, param_request_read->target_system, param_request_read->target_component, param_request_read->param_id, param_request_read->param_index);
}
/**
* @brief Send a param_request_read message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID
* @param target_component Component ID
* @param param_id Onboard parameter id
* @param param_index Parameter index
*/
#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 int8_t* param_id, uint16_t param_index)
@ -111,6 +143,12 @@ static inline uint16_t mavlink_msg_param_request_read_get_param_index(const mavl
return (uint16_t)r.s;
}
/**
* @brief Decode a param_request_read message into a struct
*
* @param msg The message to decode
* @param param_request_read C-struct to decode the message contents into
*/
static inline void mavlink_msg_param_request_read_decode(const mavlink_message_t* msg, mavlink_param_request_read_t* param_request_read)
{
param_request_read->target_system = mavlink_msg_param_request_read_get_target_system(msg);

View File

@ -15,7 +15,10 @@ typedef struct __mavlink_param_set_t
/**
* @brief Send a param_set message
* @brief Pack a param_set 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 target_system System ID
* @param target_component Component ID
@ -28,32 +31,61 @@ static inline uint16_t mavlink_msg_param_set_pack(uint8_t system_id, uint8_t com
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_PARAM_SET;
i += put_uint8_t_by_index(target_system, i, msg->payload); //System ID
i += put_uint8_t_by_index(target_component, i, msg->payload); //Component ID
i += put_array_by_index(param_id, 15, i, msg->payload); //Onboard parameter id
i += put_float_by_index(param_value, i, msg->payload); //Onboard parameter value
i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID
i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID
i += put_array_by_index(param_id, 15, i, msg->payload); // Onboard parameter id
i += put_float_by_index(param_value, i, msg->payload); // Onboard parameter value
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a param_set 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 target_system System ID
* @param target_component Component ID
* @param param_id Onboard parameter id
* @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 int8_t* param_id, float param_value)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_PARAM_SET;
i += put_uint8_t_by_index(target_system, i, msg->payload); //System ID
i += put_uint8_t_by_index(target_component, i, msg->payload); //Component ID
i += put_array_by_index(param_id, 15, i, msg->payload); //Onboard parameter id
i += put_float_by_index(param_value, i, msg->payload); //Onboard parameter value
i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID
i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID
i += put_array_by_index(param_id, 15, i, msg->payload); // Onboard parameter id
i += put_float_by_index(param_value, i, msg->payload); // Onboard parameter value
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a param_set 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 param_set C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_param_set_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_param_set_t* param_set)
{
return mavlink_msg_param_set_pack(system_id, component_id, msg, param_set->target_system, param_set->target_component, param_set->param_id, param_set->param_value);
}
/**
* @brief Send a param_set message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID
* @param target_component Component ID
* @param param_id Onboard parameter id
* @param param_value Onboard parameter value
*/
#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 int8_t* param_id, float param_value)
@ -113,6 +145,12 @@ static inline float mavlink_msg_param_set_get_param_value(const mavlink_message_
return (float)r.f;
}
/**
* @brief Decode a param_set message into a struct
*
* @param msg The message to decode
* @param param_set C-struct to decode the message contents into
*/
static inline void mavlink_msg_param_set_decode(const mavlink_message_t* msg, mavlink_param_set_t* param_set)
{
param_set->target_system = mavlink_msg_param_set_get_target_system(msg);

View File

@ -15,7 +15,10 @@ typedef struct __mavlink_param_value_t
/**
* @brief Send a param_value message
* @brief Pack a param_value 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 param_id Onboard parameter id
* @param param_value Onboard parameter value
@ -28,32 +31,61 @@ static inline uint16_t mavlink_msg_param_value_pack(uint8_t system_id, uint8_t c
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_PARAM_VALUE;
i += put_array_by_index(param_id, 15, i, msg->payload); //Onboard parameter id
i += put_float_by_index(param_value, i, msg->payload); //Onboard parameter value
i += put_uint16_t_by_index(param_count, i, msg->payload); //Total number of onboard parameters
i += put_uint16_t_by_index(param_index, i, msg->payload); //Index of this onboard parameter
i += put_array_by_index(param_id, 15, i, msg->payload); // Onboard parameter id
i += put_float_by_index(param_value, i, msg->payload); // Onboard parameter value
i += put_uint16_t_by_index(param_count, i, msg->payload); // Total number of onboard parameters
i += put_uint16_t_by_index(param_index, i, msg->payload); // Index of this onboard parameter
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a param_value 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 param_id Onboard parameter id
* @param param_value Onboard parameter value
* @param param_count Total number of onboard parameters
* @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 int8_t* param_id, float param_value, uint16_t param_count, uint16_t param_index)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_PARAM_VALUE;
i += put_array_by_index(param_id, 15, i, msg->payload); //Onboard parameter id
i += put_float_by_index(param_value, i, msg->payload); //Onboard parameter value
i += put_uint16_t_by_index(param_count, i, msg->payload); //Total number of onboard parameters
i += put_uint16_t_by_index(param_index, i, msg->payload); //Index of this onboard parameter
i += put_array_by_index(param_id, 15, i, msg->payload); // Onboard parameter id
i += put_float_by_index(param_value, i, msg->payload); // Onboard parameter value
i += put_uint16_t_by_index(param_count, i, msg->payload); // Total number of onboard parameters
i += put_uint16_t_by_index(param_index, i, msg->payload); // Index of this onboard parameter
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a param_value 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 param_value C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_param_value_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_param_value_t* param_value)
{
return mavlink_msg_param_value_pack(system_id, component_id, msg, param_value->param_id, param_value->param_value, param_value->param_count, param_value->param_index);
}
/**
* @brief Send a param_value message
* @param chan MAVLink channel to send the message
*
* @param param_id Onboard parameter id
* @param param_value Onboard parameter value
* @param param_count Total number of onboard parameters
* @param param_index Index of this onboard parameter
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_param_value_send(mavlink_channel_t chan, const int8_t* param_id, float param_value, uint16_t param_count, uint16_t param_index)
@ -119,6 +151,12 @@ static inline uint16_t mavlink_msg_param_value_get_param_index(const mavlink_mes
return (uint16_t)r.s;
}
/**
* @brief Decode a param_value message into a struct
*
* @param msg The message to decode
* @param param_value C-struct to decode the message contents into
*/
static inline void mavlink_msg_param_value_decode(const mavlink_message_t* msg, mavlink_param_value_t* param_value)
{
mavlink_msg_param_value_get_param_id(msg, param_value->param_id);

View File

@ -14,7 +14,10 @@ typedef struct __mavlink_ping_t
/**
* @brief Send a ping message
* @brief Pack a ping 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 seq PING sequence
* @param target_system 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system
@ -27,32 +30,61 @@ static inline uint16_t mavlink_msg_ping_pack(uint8_t system_id, uint8_t componen
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_PING;
i += put_uint32_t_by_index(seq, i, msg->payload); //PING sequence
i += put_uint8_t_by_index(target_system, i, msg->payload); //0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system
i += put_uint8_t_by_index(target_component, i, msg->payload); //0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system
i += put_uint64_t_by_index(time, i, msg->payload); //Unix timestamp in microseconds
i += put_uint32_t_by_index(seq, i, msg->payload); // PING sequence
i += put_uint8_t_by_index(target_system, i, msg->payload); // 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system
i += put_uint8_t_by_index(target_component, i, msg->payload); // 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system
i += put_uint64_t_by_index(time, i, msg->payload); // Unix timestamp in microseconds
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a ping 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 seq PING sequence
* @param target_system 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system
* @param target_component 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system
* @param time Unix timestamp in microseconds
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_ping_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint32_t seq, uint8_t target_system, uint8_t target_component, uint64_t time)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_PING;
i += put_uint32_t_by_index(seq, i, msg->payload); //PING sequence
i += put_uint8_t_by_index(target_system, i, msg->payload); //0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system
i += put_uint8_t_by_index(target_component, i, msg->payload); //0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system
i += put_uint64_t_by_index(time, i, msg->payload); //Unix timestamp in microseconds
i += put_uint32_t_by_index(seq, i, msg->payload); // PING sequence
i += put_uint8_t_by_index(target_system, i, msg->payload); // 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system
i += put_uint8_t_by_index(target_component, i, msg->payload); // 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system
i += put_uint64_t_by_index(time, i, msg->payload); // Unix timestamp in microseconds
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a ping 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 ping C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_ping_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_ping_t* ping)
{
return mavlink_msg_ping_pack(system_id, component_id, msg, ping->seq, ping->target_system, ping->target_component, ping->time);
}
/**
* @brief Send a ping message
* @param chan MAVLink channel to send the message
*
* @param seq PING sequence
* @param target_system 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system
* @param target_component 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system
* @param time Unix timestamp in microseconds
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_ping_send(mavlink_channel_t chan, uint32_t seq, uint8_t target_system, uint8_t target_component, uint64_t time)
@ -119,6 +151,12 @@ static inline uint64_t mavlink_msg_ping_get_time(const mavlink_message_t* msg)
return (uint64_t)r.ll;
}
/**
* @brief Decode a ping message into a struct
*
* @param msg The message to decode
* @param ping C-struct to decode the message contents into
*/
static inline void mavlink_msg_ping_decode(const mavlink_message_t* msg, mavlink_ping_t* ping)
{
ping->seq = mavlink_msg_ping_get_seq(msg);

View File

@ -15,7 +15,10 @@ typedef struct __mavlink_position_controller_output_t
/**
* @brief Send a position_controller_output message
* @brief Pack a position_controller_output 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 enabled 1: enabled, 0: disabled
* @param x Position x: -128: -100%, 127: +100%
@ -29,34 +32,65 @@ static inline uint16_t mavlink_msg_position_controller_output_pack(uint8_t syste
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_POSITION_CONTROLLER_OUTPUT;
i += put_uint8_t_by_index(enabled, i, msg->payload); //1: enabled, 0: disabled
i += put_int8_t_by_index(x, i, msg->payload); //Position x: -128: -100%, 127: +100%
i += put_int8_t_by_index(y, i, msg->payload); //Position y: -128: -100%, 127: +100%
i += put_int8_t_by_index(z, i, msg->payload); //Position z: -128: -100%, 127: +100%
i += put_int8_t_by_index(yaw, i, msg->payload); //Position yaw: -128: -100%, 127: +100%
i += put_uint8_t_by_index(enabled, i, msg->payload); // 1: enabled, 0: disabled
i += put_int8_t_by_index(x, i, msg->payload); // Position x: -128: -100%, 127: +100%
i += put_int8_t_by_index(y, i, msg->payload); // Position y: -128: -100%, 127: +100%
i += put_int8_t_by_index(z, i, msg->payload); // Position z: -128: -100%, 127: +100%
i += put_int8_t_by_index(yaw, i, msg->payload); // Position yaw: -128: -100%, 127: +100%
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a position_controller_output 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 enabled 1: enabled, 0: disabled
* @param x Position x: -128: -100%, 127: +100%
* @param y Position y: -128: -100%, 127: +100%
* @param z Position z: -128: -100%, 127: +100%
* @param yaw Position yaw: -128: -100%, 127: +100%
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_position_controller_output_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t enabled, int8_t x, int8_t y, int8_t z, int8_t yaw)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_POSITION_CONTROLLER_OUTPUT;
i += put_uint8_t_by_index(enabled, i, msg->payload); //1: enabled, 0: disabled
i += put_int8_t_by_index(x, i, msg->payload); //Position x: -128: -100%, 127: +100%
i += put_int8_t_by_index(y, i, msg->payload); //Position y: -128: -100%, 127: +100%
i += put_int8_t_by_index(z, i, msg->payload); //Position z: -128: -100%, 127: +100%
i += put_int8_t_by_index(yaw, i, msg->payload); //Position yaw: -128: -100%, 127: +100%
i += put_uint8_t_by_index(enabled, i, msg->payload); // 1: enabled, 0: disabled
i += put_int8_t_by_index(x, i, msg->payload); // Position x: -128: -100%, 127: +100%
i += put_int8_t_by_index(y, i, msg->payload); // Position y: -128: -100%, 127: +100%
i += put_int8_t_by_index(z, i, msg->payload); // Position z: -128: -100%, 127: +100%
i += put_int8_t_by_index(yaw, i, msg->payload); // Position yaw: -128: -100%, 127: +100%
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a position_controller_output 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 position_controller_output C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_position_controller_output_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_position_controller_output_t* position_controller_output)
{
return mavlink_msg_position_controller_output_pack(system_id, component_id, msg, position_controller_output->enabled, position_controller_output->x, position_controller_output->y, position_controller_output->z, position_controller_output->yaw);
}
/**
* @brief Send a position_controller_output message
* @param chan MAVLink channel to send the message
*
* @param enabled 1: enabled, 0: disabled
* @param x Position x: -128: -100%, 127: +100%
* @param y Position y: -128: -100%, 127: +100%
* @param z Position z: -128: -100%, 127: +100%
* @param yaw Position yaw: -128: -100%, 127: +100%
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_position_controller_output_send(mavlink_channel_t chan, uint8_t enabled, int8_t x, int8_t y, int8_t z, int8_t yaw)
@ -119,6 +153,12 @@ static inline int8_t mavlink_msg_position_controller_output_get_yaw(const mavlin
return (int8_t)(msg->payload+sizeof(uint8_t)+sizeof(int8_t)+sizeof(int8_t)+sizeof(int8_t))[0];
}
/**
* @brief Decode a position_controller_output message into a struct
*
* @param msg The message to decode
* @param position_controller_output C-struct to decode the message contents into
*/
static inline void mavlink_msg_position_controller_output_decode(const mavlink_message_t* msg, mavlink_position_controller_output_t* position_controller_output)
{
position_controller_output->enabled = mavlink_msg_position_controller_output_get_enabled(msg);

View File

@ -14,7 +14,10 @@ typedef struct __mavlink_position_target_t
/**
* @brief Send a position_target message
* @brief Pack a position_target 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 x x position
* @param y y position
@ -27,32 +30,61 @@ static inline uint16_t mavlink_msg_position_target_pack(uint8_t system_id, uint8
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_POSITION_TARGET;
i += put_float_by_index(x, i, msg->payload); //x position
i += put_float_by_index(y, i, msg->payload); //y position
i += put_float_by_index(z, i, msg->payload); //z position
i += put_float_by_index(yaw, i, msg->payload); //yaw orientation in radians, 0 = NORTH
i += put_float_by_index(x, i, msg->payload); // x position
i += put_float_by_index(y, i, msg->payload); // y position
i += put_float_by_index(z, i, msg->payload); // z position
i += put_float_by_index(yaw, i, msg->payload); // yaw orientation in radians, 0 = NORTH
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a position_target 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 x x position
* @param y y position
* @param z z position
* @param yaw yaw orientation in radians, 0 = NORTH
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_position_target_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, float x, float y, float z, float yaw)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_POSITION_TARGET;
i += put_float_by_index(x, i, msg->payload); //x position
i += put_float_by_index(y, i, msg->payload); //y position
i += put_float_by_index(z, i, msg->payload); //z position
i += put_float_by_index(yaw, i, msg->payload); //yaw orientation in radians, 0 = NORTH
i += put_float_by_index(x, i, msg->payload); // x position
i += put_float_by_index(y, i, msg->payload); // y position
i += put_float_by_index(z, i, msg->payload); // z position
i += put_float_by_index(yaw, i, msg->payload); // yaw orientation in radians, 0 = NORTH
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a position_target 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 position_target C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_position_target_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_position_target_t* position_target)
{
return mavlink_msg_position_target_pack(system_id, component_id, msg, position_target->x, position_target->y, position_target->z, position_target->yaw);
}
/**
* @brief Send a position_target message
* @param chan MAVLink channel to send the message
*
* @param x x position
* @param y y position
* @param z z position
* @param yaw yaw orientation in radians, 0 = NORTH
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_position_target_send(mavlink_channel_t chan, float x, float y, float z, float yaw)
@ -125,6 +157,12 @@ static inline float mavlink_msg_position_target_get_yaw(const mavlink_message_t*
return (float)r.f;
}
/**
* @brief Decode a position_target message into a struct
*
* @param msg The message to decode
* @param position_target C-struct to decode the message contents into
*/
static inline void mavlink_msg_position_target_decode(const mavlink_message_t* msg, mavlink_position_target_t* position_target)
{
position_target->x = mavlink_msg_position_target_get_x(msg);

View File

@ -20,7 +20,10 @@ typedef struct __mavlink_raw_imu_t
/**
* @brief Send a raw_imu message
* @brief Pack a raw_imu 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 usec Timestamp (microseconds since UNIX epoch)
* @param xacc X acceleration (mg raw)
@ -39,44 +42,85 @@ static inline uint16_t mavlink_msg_raw_imu_pack(uint8_t system_id, uint8_t compo
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_RAW_IMU;
i += put_uint64_t_by_index(usec, i, msg->payload); //Timestamp (microseconds since UNIX epoch)
i += put_int16_t_by_index(xacc, i, msg->payload); //X acceleration (mg raw)
i += put_int16_t_by_index(yacc, i, msg->payload); //Y acceleration (mg raw)
i += put_int16_t_by_index(zacc, i, msg->payload); //Z acceleration (mg raw)
i += put_int16_t_by_index(xgyro, i, msg->payload); //Angular speed around X axis (millirad /sec)
i += put_int16_t_by_index(ygyro, i, msg->payload); //Angular speed around Y axis (millirad /sec)
i += put_int16_t_by_index(zgyro, i, msg->payload); //Angular speed around Z axis (millirad /sec)
i += put_int16_t_by_index(xmag, i, msg->payload); //X Magnetic field (milli tesla)
i += put_int16_t_by_index(ymag, i, msg->payload); //Y Magnetic field (milli tesla)
i += put_int16_t_by_index(zmag, i, msg->payload); //Z Magnetic field (milli tesla)
i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since UNIX epoch)
i += put_int16_t_by_index(xacc, i, msg->payload); // X acceleration (mg raw)
i += put_int16_t_by_index(yacc, i, msg->payload); // Y acceleration (mg raw)
i += put_int16_t_by_index(zacc, i, msg->payload); // Z acceleration (mg raw)
i += put_int16_t_by_index(xgyro, i, msg->payload); // Angular speed around X axis (millirad /sec)
i += put_int16_t_by_index(ygyro, i, msg->payload); // Angular speed around Y axis (millirad /sec)
i += put_int16_t_by_index(zgyro, i, msg->payload); // Angular speed around Z axis (millirad /sec)
i += put_int16_t_by_index(xmag, i, msg->payload); // X Magnetic field (milli tesla)
i += put_int16_t_by_index(ymag, i, msg->payload); // Y Magnetic field (milli tesla)
i += put_int16_t_by_index(zmag, i, msg->payload); // Z Magnetic field (milli tesla)
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a raw_imu 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 usec Timestamp (microseconds since UNIX epoch)
* @param xacc X acceleration (mg raw)
* @param yacc Y acceleration (mg raw)
* @param zacc Z acceleration (mg raw)
* @param xgyro Angular speed around X axis (millirad /sec)
* @param ygyro Angular speed around Y axis (millirad /sec)
* @param zgyro Angular speed around Z axis (millirad /sec)
* @param xmag X Magnetic field (milli tesla)
* @param ymag Y Magnetic field (milli tesla)
* @param zmag Z Magnetic field (milli tesla)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_raw_imu_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint64_t usec, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_RAW_IMU;
i += put_uint64_t_by_index(usec, i, msg->payload); //Timestamp (microseconds since UNIX epoch)
i += put_int16_t_by_index(xacc, i, msg->payload); //X acceleration (mg raw)
i += put_int16_t_by_index(yacc, i, msg->payload); //Y acceleration (mg raw)
i += put_int16_t_by_index(zacc, i, msg->payload); //Z acceleration (mg raw)
i += put_int16_t_by_index(xgyro, i, msg->payload); //Angular speed around X axis (millirad /sec)
i += put_int16_t_by_index(ygyro, i, msg->payload); //Angular speed around Y axis (millirad /sec)
i += put_int16_t_by_index(zgyro, i, msg->payload); //Angular speed around Z axis (millirad /sec)
i += put_int16_t_by_index(xmag, i, msg->payload); //X Magnetic field (milli tesla)
i += put_int16_t_by_index(ymag, i, msg->payload); //Y Magnetic field (milli tesla)
i += put_int16_t_by_index(zmag, i, msg->payload); //Z Magnetic field (milli tesla)
i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since UNIX epoch)
i += put_int16_t_by_index(xacc, i, msg->payload); // X acceleration (mg raw)
i += put_int16_t_by_index(yacc, i, msg->payload); // Y acceleration (mg raw)
i += put_int16_t_by_index(zacc, i, msg->payload); // Z acceleration (mg raw)
i += put_int16_t_by_index(xgyro, i, msg->payload); // Angular speed around X axis (millirad /sec)
i += put_int16_t_by_index(ygyro, i, msg->payload); // Angular speed around Y axis (millirad /sec)
i += put_int16_t_by_index(zgyro, i, msg->payload); // Angular speed around Z axis (millirad /sec)
i += put_int16_t_by_index(xmag, i, msg->payload); // X Magnetic field (milli tesla)
i += put_int16_t_by_index(ymag, i, msg->payload); // Y Magnetic field (milli tesla)
i += put_int16_t_by_index(zmag, i, msg->payload); // Z Magnetic field (milli tesla)
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a raw_imu 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 raw_imu C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_raw_imu_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_raw_imu_t* raw_imu)
{
return mavlink_msg_raw_imu_pack(system_id, component_id, msg, raw_imu->usec, raw_imu->xacc, raw_imu->yacc, raw_imu->zacc, raw_imu->xgyro, raw_imu->ygyro, raw_imu->zgyro, raw_imu->xmag, raw_imu->ymag, raw_imu->zmag);
}
/**
* @brief Send a raw_imu message
* @param chan MAVLink channel to send the message
*
* @param usec Timestamp (microseconds since UNIX epoch)
* @param xacc X acceleration (mg raw)
* @param yacc Y acceleration (mg raw)
* @param zacc Z acceleration (mg raw)
* @param xgyro Angular speed around X axis (millirad /sec)
* @param ygyro Angular speed around Y axis (millirad /sec)
* @param zgyro Angular speed around Z axis (millirad /sec)
* @param xmag X Magnetic field (milli tesla)
* @param ymag Y Magnetic field (milli tesla)
* @param zmag Z Magnetic field (milli tesla)
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_raw_imu_send(mavlink_channel_t chan, uint64_t usec, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag)
@ -225,6 +269,12 @@ static inline int16_t mavlink_msg_raw_imu_get_zmag(const mavlink_message_t* msg)
return (int16_t)r.s;
}
/**
* @brief Decode a raw_imu message into a struct
*
* @param msg The message to decode
* @param raw_imu C-struct to decode the message contents into
*/
static inline void mavlink_msg_raw_imu_decode(const mavlink_message_t* msg, mavlink_raw_imu_t* raw_imu)
{
raw_imu->usec = mavlink_msg_raw_imu_get_usec(msg);

View File

@ -15,7 +15,10 @@ typedef struct __mavlink_raw_pressure_t
/**
* @brief Send a raw_pressure message
* @brief Pack a raw_pressure 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 usec Timestamp (microseconds since UNIX epoch)
* @param press_abs Absolute pressure (hectopascal)
@ -29,39 +32,71 @@ static inline uint16_t mavlink_msg_raw_pressure_pack(uint8_t system_id, uint8_t
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_RAW_PRESSURE;
i += put_uint64_t_by_index(usec, i, msg->payload); //Timestamp (microseconds since UNIX epoch)
i += put_int16_t_by_index(press_abs, i, msg->payload); //Absolute pressure (hectopascal)
i += put_int16_t_by_index(press_diff1, i, msg->payload); //Differential pressure 1 (hectopascal)
i += put_int16_t_by_index(press_diff2, i, msg->payload); //Differential pressure 2 (hectopascal)
i += put_int16_t_by_index(temperature, i, msg->payload); //Raw Temperature measurement
i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since UNIX epoch)
i += put_int16_t_by_index(press_abs, i, msg->payload); // Absolute pressure (hectopascal)
i += put_int16_t_by_index(press_diff1, i, msg->payload); // Differential pressure 1 (hectopascal)
i += put_int16_t_by_index(press_diff2, i, msg->payload); // Differential pressure 2 (hectopascal)
i += put_int16_t_by_index(temperature, i, msg->payload); // Raw Temperature measurement
return mavlink_finalize_message(msg, system_id, component_id, i);
}
static inline uint16_t mavlink_msg_raw_pressure_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint64_t usec, int32_t press_abs, int32_t press_diff1, int32_t press_diff2)
/**
* @brief Pack a raw_pressure 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 usec Timestamp (microseconds since UNIX epoch)
* @param press_abs Absolute pressure (hectopascal)
* @param press_diff1 Differential pressure 1 (hectopascal)
* @param press_diff2 Differential pressure 2 (hectopascal)
* @param temperature Raw Temperature measurement
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_raw_pressure_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint64_t usec, int16_t press_abs, int16_t press_diff1, int16_t press_diff2, int16_t temperature)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_RAW_PRESSURE;
i += put_uint64_t_by_index(usec, i, msg->payload); //Timestamp (microseconds since UNIX epoch)
i += put_int32_t_by_index(press_abs, i, msg->payload); //Absolute pressure (hectopascal)
i += put_int32_t_by_index(press_diff1, i, msg->payload); //Differential pressure 1 (hectopascal)
i += put_int32_t_by_index(press_diff2, i, msg->payload); //Differential pressure 2 (hectopascal)
i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since UNIX epoch)
i += put_int16_t_by_index(press_abs, i, msg->payload); // Absolute pressure (hectopascal)
i += put_int16_t_by_index(press_diff1, i, msg->payload); // Differential pressure 1 (hectopascal)
i += put_int16_t_by_index(press_diff2, i, msg->payload); // Differential pressure 2 (hectopascal)
i += put_int16_t_by_index(temperature, i, msg->payload); // Raw Temperature measurement
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a raw_pressure 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 raw_pressure C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_raw_pressure_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_raw_pressure_t* raw_pressure)
{
return mavlink_msg_raw_pressure_pack(system_id, component_id, msg, raw_pressure->usec, raw_pressure->press_abs, raw_pressure->press_diff1, raw_pressure->press_diff2, raw_pressure->temperature);
}
/**
* @brief Send a raw_pressure message
* @param chan MAVLink channel to send the message
*
* @param usec Timestamp (microseconds since UNIX epoch)
* @param press_abs Absolute pressure (hectopascal)
* @param press_diff1 Differential pressure 1 (hectopascal)
* @param press_diff2 Differential pressure 2 (hectopascal)
* @param temperature Raw Temperature measurement
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_raw_pressure_send(mavlink_channel_t chan, uint64_t usec, int16_t press_abs, int16_t press_diff1, int16_t press_diff2, int16_t temperature)
{
mavlink_message_t msg;
mavlink_msg_raw_pressure_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, usec, press_abs, press_diff1, press_diff2);
mavlink_msg_raw_pressure_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, usec, press_abs, press_diff1, press_diff2, temperature);
mavlink_send_uart(chan, &msg);
}
@ -139,6 +174,12 @@ static inline int16_t mavlink_msg_raw_pressure_get_temperature(const mavlink_mes
return (int16_t)r.s;
}
/**
* @brief Decode a raw_pressure message into a struct
*
* @param msg The message to decode
* @param raw_pressure C-struct to decode the message contents into
*/
static inline void mavlink_msg_raw_pressure_decode(const mavlink_message_t* msg, mavlink_raw_pressure_t* raw_pressure)
{
raw_pressure->usec = mavlink_msg_raw_pressure_get_usec(msg);

View File

@ -19,7 +19,10 @@ typedef struct __mavlink_rc_channels_raw_t
/**
* @brief Send a rc_channels_raw message
* @brief Pack a rc_channels_raw 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 chan1_raw RC channel 1 value, in microseconds
* @param chan2_raw RC channel 2 value, in microseconds
@ -37,42 +40,81 @@ static inline uint16_t mavlink_msg_rc_channels_raw_pack(uint8_t system_id, uint8
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS_RAW;
i += put_uint16_t_by_index(chan1_raw, i, msg->payload); //RC channel 1 value, in microseconds
i += put_uint16_t_by_index(chan2_raw, i, msg->payload); //RC channel 2 value, in microseconds
i += put_uint16_t_by_index(chan3_raw, i, msg->payload); //RC channel 3 value, in microseconds
i += put_uint16_t_by_index(chan4_raw, i, msg->payload); //RC channel 4 value, in microseconds
i += put_uint16_t_by_index(chan5_raw, i, msg->payload); //RC channel 5 value, in microseconds
i += put_uint16_t_by_index(chan6_raw, i, msg->payload); //RC channel 6 value, in microseconds
i += put_uint16_t_by_index(chan7_raw, i, msg->payload); //RC channel 7 value, in microseconds
i += put_uint16_t_by_index(chan8_raw, i, msg->payload); //RC channel 8 value, in microseconds
i += put_uint8_t_by_index(rssi, i, msg->payload); //Receive signal strength indicator, 0: 0%, 255: 100%
i += put_uint16_t_by_index(chan1_raw, i, msg->payload); // RC channel 1 value, in microseconds
i += put_uint16_t_by_index(chan2_raw, i, msg->payload); // RC channel 2 value, in microseconds
i += put_uint16_t_by_index(chan3_raw, i, msg->payload); // RC channel 3 value, in microseconds
i += put_uint16_t_by_index(chan4_raw, i, msg->payload); // RC channel 4 value, in microseconds
i += put_uint16_t_by_index(chan5_raw, i, msg->payload); // RC channel 5 value, in microseconds
i += put_uint16_t_by_index(chan6_raw, i, msg->payload); // RC channel 6 value, in microseconds
i += put_uint16_t_by_index(chan7_raw, i, msg->payload); // RC channel 7 value, in microseconds
i += put_uint16_t_by_index(chan8_raw, i, msg->payload); // RC channel 8 value, in microseconds
i += put_uint8_t_by_index(rssi, i, msg->payload); // Receive signal strength indicator, 0: 0%, 255: 100%
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a rc_channels_raw 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 chan1_raw RC channel 1 value, in microseconds
* @param chan2_raw RC channel 2 value, in microseconds
* @param chan3_raw RC channel 3 value, in microseconds
* @param chan4_raw RC channel 4 value, in microseconds
* @param chan5_raw RC channel 5 value, in microseconds
* @param chan6_raw RC channel 6 value, in microseconds
* @param chan7_raw RC channel 7 value, in microseconds
* @param chan8_raw RC channel 8 value, in microseconds
* @param rssi Receive signal strength indicator, 0: 0%, 255: 100%
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_rc_channels_raw_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw, uint8_t rssi)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS_RAW;
i += put_uint16_t_by_index(chan1_raw, i, msg->payload); //RC channel 1 value, in microseconds
i += put_uint16_t_by_index(chan2_raw, i, msg->payload); //RC channel 2 value, in microseconds
i += put_uint16_t_by_index(chan3_raw, i, msg->payload); //RC channel 3 value, in microseconds
i += put_uint16_t_by_index(chan4_raw, i, msg->payload); //RC channel 4 value, in microseconds
i += put_uint16_t_by_index(chan5_raw, i, msg->payload); //RC channel 5 value, in microseconds
i += put_uint16_t_by_index(chan6_raw, i, msg->payload); //RC channel 6 value, in microseconds
i += put_uint16_t_by_index(chan7_raw, i, msg->payload); //RC channel 7 value, in microseconds
i += put_uint16_t_by_index(chan8_raw, i, msg->payload); //RC channel 8 value, in microseconds
i += put_uint8_t_by_index(rssi, i, msg->payload); //Receive signal strength indicator, 0: 0%, 255: 100%
i += put_uint16_t_by_index(chan1_raw, i, msg->payload); // RC channel 1 value, in microseconds
i += put_uint16_t_by_index(chan2_raw, i, msg->payload); // RC channel 2 value, in microseconds
i += put_uint16_t_by_index(chan3_raw, i, msg->payload); // RC channel 3 value, in microseconds
i += put_uint16_t_by_index(chan4_raw, i, msg->payload); // RC channel 4 value, in microseconds
i += put_uint16_t_by_index(chan5_raw, i, msg->payload); // RC channel 5 value, in microseconds
i += put_uint16_t_by_index(chan6_raw, i, msg->payload); // RC channel 6 value, in microseconds
i += put_uint16_t_by_index(chan7_raw, i, msg->payload); // RC channel 7 value, in microseconds
i += put_uint16_t_by_index(chan8_raw, i, msg->payload); // RC channel 8 value, in microseconds
i += put_uint8_t_by_index(rssi, i, msg->payload); // Receive signal strength indicator, 0: 0%, 255: 100%
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a rc_channels_raw 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 rc_channels_raw C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_rc_channels_raw_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_rc_channels_raw_t* rc_channels_raw)
{
return mavlink_msg_rc_channels_raw_pack(system_id, component_id, msg, rc_channels_raw->chan1_raw, rc_channels_raw->chan2_raw, rc_channels_raw->chan3_raw, rc_channels_raw->chan4_raw, rc_channels_raw->chan5_raw, rc_channels_raw->chan6_raw, rc_channels_raw->chan7_raw, rc_channels_raw->chan8_raw, rc_channels_raw->rssi);
}
/**
* @brief Send a rc_channels_raw message
* @param chan MAVLink channel to send the message
*
* @param chan1_raw RC channel 1 value, in microseconds
* @param chan2_raw RC channel 2 value, in microseconds
* @param chan3_raw RC channel 3 value, in microseconds
* @param chan4_raw RC channel 4 value, in microseconds
* @param chan5_raw RC channel 5 value, in microseconds
* @param chan6_raw RC channel 6 value, in microseconds
* @param chan7_raw RC channel 7 value, in microseconds
* @param chan8_raw RC channel 8 value, in microseconds
* @param rssi Receive signal strength indicator, 0: 0%, 255: 100%
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_rc_channels_raw_send(mavlink_channel_t chan, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw, uint8_t rssi)
@ -199,6 +241,12 @@ static inline uint8_t mavlink_msg_rc_channels_raw_get_rssi(const mavlink_message
return (uint8_t)(msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[0];
}
/**
* @brief Decode a rc_channels_raw message into a struct
*
* @param msg The message to decode
* @param rc_channels_raw C-struct to decode the message contents into
*/
static inline void mavlink_msg_rc_channels_raw_decode(const mavlink_message_t* msg, mavlink_rc_channels_raw_t* rc_channels_raw)
{
rc_channels_raw->chan1_raw = mavlink_msg_rc_channels_raw_get_chan1_raw(msg);

View File

@ -19,7 +19,10 @@ typedef struct __mavlink_rc_channels_scaled_t
/**
* @brief Send a rc_channels_scaled message
* @brief Pack a rc_channels_scaled 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 chan1_scaled RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
* @param chan2_scaled RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
@ -37,42 +40,81 @@ static inline uint16_t mavlink_msg_rc_channels_scaled_pack(uint8_t system_id, ui
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS_SCALED;
i += put_int16_t_by_index(chan1_scaled, i, msg->payload); //RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
i += put_int16_t_by_index(chan2_scaled, i, msg->payload); //RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
i += put_int16_t_by_index(chan3_scaled, i, msg->payload); //RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
i += put_int16_t_by_index(chan4_scaled, i, msg->payload); //RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
i += put_int16_t_by_index(chan5_scaled, i, msg->payload); //RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
i += put_int16_t_by_index(chan6_scaled, i, msg->payload); //RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
i += put_int16_t_by_index(chan7_scaled, i, msg->payload); //RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
i += put_int16_t_by_index(chan8_scaled, i, msg->payload); //RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
i += put_uint8_t_by_index(rssi, i, msg->payload); //Receive signal strength indicator, 0: 0%, 255: 100%
i += put_int16_t_by_index(chan1_scaled, i, msg->payload); // RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
i += put_int16_t_by_index(chan2_scaled, i, msg->payload); // RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
i += put_int16_t_by_index(chan3_scaled, i, msg->payload); // RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
i += put_int16_t_by_index(chan4_scaled, i, msg->payload); // RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
i += put_int16_t_by_index(chan5_scaled, i, msg->payload); // RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
i += put_int16_t_by_index(chan6_scaled, i, msg->payload); // RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
i += put_int16_t_by_index(chan7_scaled, i, msg->payload); // RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
i += put_int16_t_by_index(chan8_scaled, i, msg->payload); // RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
i += put_uint8_t_by_index(rssi, i, msg->payload); // Receive signal strength indicator, 0: 0%, 255: 100%
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a rc_channels_scaled 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 chan1_scaled RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
* @param chan2_scaled RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
* @param chan3_scaled RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
* @param chan4_scaled RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
* @param chan5_scaled RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
* @param chan6_scaled RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
* @param chan7_scaled RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
* @param chan8_scaled RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
* @param rssi Receive signal strength indicator, 0: 0%, 255: 100%
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_rc_channels_scaled_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, int16_t chan1_scaled, int16_t chan2_scaled, int16_t chan3_scaled, int16_t chan4_scaled, int16_t chan5_scaled, int16_t chan6_scaled, int16_t chan7_scaled, int16_t chan8_scaled, uint8_t rssi)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS_SCALED;
i += put_int16_t_by_index(chan1_scaled, i, msg->payload); //RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
i += put_int16_t_by_index(chan2_scaled, i, msg->payload); //RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
i += put_int16_t_by_index(chan3_scaled, i, msg->payload); //RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
i += put_int16_t_by_index(chan4_scaled, i, msg->payload); //RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
i += put_int16_t_by_index(chan5_scaled, i, msg->payload); //RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
i += put_int16_t_by_index(chan6_scaled, i, msg->payload); //RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
i += put_int16_t_by_index(chan7_scaled, i, msg->payload); //RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
i += put_int16_t_by_index(chan8_scaled, i, msg->payload); //RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
i += put_uint8_t_by_index(rssi, i, msg->payload); //Receive signal strength indicator, 0: 0%, 255: 100%
i += put_int16_t_by_index(chan1_scaled, i, msg->payload); // RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
i += put_int16_t_by_index(chan2_scaled, i, msg->payload); // RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
i += put_int16_t_by_index(chan3_scaled, i, msg->payload); // RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
i += put_int16_t_by_index(chan4_scaled, i, msg->payload); // RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
i += put_int16_t_by_index(chan5_scaled, i, msg->payload); // RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
i += put_int16_t_by_index(chan6_scaled, i, msg->payload); // RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
i += put_int16_t_by_index(chan7_scaled, i, msg->payload); // RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
i += put_int16_t_by_index(chan8_scaled, i, msg->payload); // RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
i += put_uint8_t_by_index(rssi, i, msg->payload); // Receive signal strength indicator, 0: 0%, 255: 100%
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a rc_channels_scaled 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 rc_channels_scaled C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_rc_channels_scaled_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_rc_channels_scaled_t* rc_channels_scaled)
{
return mavlink_msg_rc_channels_scaled_pack(system_id, component_id, msg, rc_channels_scaled->chan1_scaled, rc_channels_scaled->chan2_scaled, rc_channels_scaled->chan3_scaled, rc_channels_scaled->chan4_scaled, rc_channels_scaled->chan5_scaled, rc_channels_scaled->chan6_scaled, rc_channels_scaled->chan7_scaled, rc_channels_scaled->chan8_scaled, rc_channels_scaled->rssi);
}
/**
* @brief Send a rc_channels_scaled message
* @param chan MAVLink channel to send the message
*
* @param chan1_scaled RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
* @param chan2_scaled RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
* @param chan3_scaled RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
* @param chan4_scaled RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
* @param chan5_scaled RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
* @param chan6_scaled RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
* @param chan7_scaled RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
* @param chan8_scaled RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
* @param rssi Receive signal strength indicator, 0: 0%, 255: 100%
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_rc_channels_scaled_send(mavlink_channel_t chan, int16_t chan1_scaled, int16_t chan2_scaled, int16_t chan3_scaled, int16_t chan4_scaled, int16_t chan5_scaled, int16_t chan6_scaled, int16_t chan7_scaled, int16_t chan8_scaled, uint8_t rssi)
@ -199,6 +241,12 @@ static inline uint8_t mavlink_msg_rc_channels_scaled_get_rssi(const mavlink_mess
return (uint8_t)(msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[0];
}
/**
* @brief Decode a rc_channels_scaled message into a struct
*
* @param msg The message to decode
* @param rc_channels_scaled C-struct to decode the message contents into
*/
static inline void mavlink_msg_rc_channels_scaled_decode(const mavlink_message_t* msg, mavlink_rc_channels_scaled_t* rc_channels_scaled)
{
rc_channels_scaled->chan1_scaled = mavlink_msg_rc_channels_scaled_get_chan1_scaled(msg);

View File

@ -15,7 +15,10 @@ typedef struct __mavlink_request_data_stream_t
/**
* @brief Send a request_data_stream message
* @brief Pack a request_data_stream 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 target_system The target requested to send the message stream.
* @param target_component The target requested to send the message stream.
@ -29,34 +32,65 @@ static inline uint16_t mavlink_msg_request_data_stream_pack(uint8_t system_id, u
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_REQUEST_DATA_STREAM;
i += put_uint8_t_by_index(target_system, i, msg->payload); //The target requested to send the message stream.
i += put_uint8_t_by_index(target_component, i, msg->payload); //The target requested to send the message stream.
i += put_uint8_t_by_index(req_stream_id, i, msg->payload); //The ID of the requested message type
i += put_uint16_t_by_index(req_message_rate, i, msg->payload); //The requested interval between two messages of this type
i += put_uint8_t_by_index(start_stop, i, msg->payload); //1 to start sending, 0 to stop sending.
i += put_uint8_t_by_index(target_system, i, msg->payload); // The target requested to send the message stream.
i += put_uint8_t_by_index(target_component, i, msg->payload); // The target requested to send the message stream.
i += put_uint8_t_by_index(req_stream_id, i, msg->payload); // The ID of the requested message type
i += put_uint16_t_by_index(req_message_rate, i, msg->payload); // The requested interval between two messages of this type
i += put_uint8_t_by_index(start_stop, i, msg->payload); // 1 to start sending, 0 to stop sending.
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a request_data_stream 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 target_system The target requested to send the message stream.
* @param target_component The target requested to send the message stream.
* @param req_stream_id The ID of the requested message type
* @param req_message_rate The requested interval between two messages of this type
* @param start_stop 1 to start sending, 0 to stop sending.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_request_data_stream_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, uint8_t req_stream_id, uint16_t req_message_rate, uint8_t start_stop)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_REQUEST_DATA_STREAM;
i += put_uint8_t_by_index(target_system, i, msg->payload); //The target requested to send the message stream.
i += put_uint8_t_by_index(target_component, i, msg->payload); //The target requested to send the message stream.
i += put_uint8_t_by_index(req_stream_id, i, msg->payload); //The ID of the requested message type
i += put_uint16_t_by_index(req_message_rate, i, msg->payload); //The requested interval between two messages of this type
i += put_uint8_t_by_index(start_stop, i, msg->payload); //1 to start sending, 0 to stop sending.
i += put_uint8_t_by_index(target_system, i, msg->payload); // The target requested to send the message stream.
i += put_uint8_t_by_index(target_component, i, msg->payload); // The target requested to send the message stream.
i += put_uint8_t_by_index(req_stream_id, i, msg->payload); // The ID of the requested message type
i += put_uint16_t_by_index(req_message_rate, i, msg->payload); // The requested interval between two messages of this type
i += put_uint8_t_by_index(start_stop, i, msg->payload); // 1 to start sending, 0 to stop sending.
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a request_data_stream 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 request_data_stream C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_request_data_stream_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_request_data_stream_t* request_data_stream)
{
return mavlink_msg_request_data_stream_pack(system_id, component_id, msg, request_data_stream->target_system, request_data_stream->target_component, request_data_stream->req_stream_id, request_data_stream->req_message_rate, request_data_stream->start_stop);
}
/**
* @brief Send a request_data_stream message
* @param chan MAVLink channel to send the message
*
* @param target_system The target requested to send the message stream.
* @param target_component The target requested to send the message stream.
* @param req_stream_id The ID of the requested message type
* @param req_message_rate The requested interval between two messages of this type
* @param start_stop 1 to start sending, 0 to stop sending.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_request_data_stream_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t req_stream_id, uint16_t req_message_rate, uint8_t start_stop)
@ -122,6 +156,12 @@ static inline uint8_t mavlink_msg_request_data_stream_get_start_stop(const mavli
return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t))[0];
}
/**
* @brief Decode a request_data_stream message into a struct
*
* @param msg The message to decode
* @param request_data_stream C-struct to decode the message contents into
*/
static inline void mavlink_msg_request_data_stream_decode(const mavlink_message_t* msg, mavlink_request_data_stream_t* request_data_stream)
{
request_data_stream->target_system = mavlink_msg_request_data_stream_get_target_system(msg);

View File

@ -15,7 +15,10 @@ typedef struct __mavlink_request_dynamic_gyro_calibration_t
/**
* @brief Send a request_dynamic_gyro_calibration message
* @brief Pack a request_dynamic_gyro_calibration 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 target_system The system which should auto-calibrate
* @param target_component The system component which should auto-calibrate
@ -29,34 +32,65 @@ static inline uint16_t mavlink_msg_request_dynamic_gyro_calibration_pack(uint8_t
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_REQUEST_DYNAMIC_GYRO_CALIBRATION;
i += put_uint8_t_by_index(target_system, i, msg->payload); //The system which should auto-calibrate
i += put_uint8_t_by_index(target_component, i, msg->payload); //The system component which should auto-calibrate
i += put_float_by_index(mode, i, msg->payload); //The current ground-truth rpm
i += put_uint8_t_by_index(axis, i, msg->payload); //The axis to calibrate: 0 roll, 1 pitch, 2 yaw
i += put_uint16_t_by_index(time, i, msg->payload); //The time to average over in ms
i += put_uint8_t_by_index(target_system, i, msg->payload); // The system which should auto-calibrate
i += put_uint8_t_by_index(target_component, i, msg->payload); // The system component which should auto-calibrate
i += put_float_by_index(mode, i, msg->payload); // The current ground-truth rpm
i += put_uint8_t_by_index(axis, i, msg->payload); // The axis to calibrate: 0 roll, 1 pitch, 2 yaw
i += put_uint16_t_by_index(time, i, msg->payload); // The time to average over in ms
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a request_dynamic_gyro_calibration 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 target_system The system which should auto-calibrate
* @param target_component The system component which should auto-calibrate
* @param mode The current ground-truth rpm
* @param axis The axis to calibrate: 0 roll, 1 pitch, 2 yaw
* @param time The time to average over in ms
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_request_dynamic_gyro_calibration_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, float mode, uint8_t axis, uint16_t time)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_REQUEST_DYNAMIC_GYRO_CALIBRATION;
i += put_uint8_t_by_index(target_system, i, msg->payload); //The system which should auto-calibrate
i += put_uint8_t_by_index(target_component, i, msg->payload); //The system component which should auto-calibrate
i += put_float_by_index(mode, i, msg->payload); //The current ground-truth rpm
i += put_uint8_t_by_index(axis, i, msg->payload); //The axis to calibrate: 0 roll, 1 pitch, 2 yaw
i += put_uint16_t_by_index(time, i, msg->payload); //The time to average over in ms
i += put_uint8_t_by_index(target_system, i, msg->payload); // The system which should auto-calibrate
i += put_uint8_t_by_index(target_component, i, msg->payload); // The system component which should auto-calibrate
i += put_float_by_index(mode, i, msg->payload); // The current ground-truth rpm
i += put_uint8_t_by_index(axis, i, msg->payload); // The axis to calibrate: 0 roll, 1 pitch, 2 yaw
i += put_uint16_t_by_index(time, i, msg->payload); // The time to average over in ms
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a request_dynamic_gyro_calibration 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 request_dynamic_gyro_calibration C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_request_dynamic_gyro_calibration_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_request_dynamic_gyro_calibration_t* request_dynamic_gyro_calibration)
{
return mavlink_msg_request_dynamic_gyro_calibration_pack(system_id, component_id, msg, request_dynamic_gyro_calibration->target_system, request_dynamic_gyro_calibration->target_component, request_dynamic_gyro_calibration->mode, request_dynamic_gyro_calibration->axis, request_dynamic_gyro_calibration->time);
}
/**
* @brief Send a request_dynamic_gyro_calibration message
* @param chan MAVLink channel to send the message
*
* @param target_system The system which should auto-calibrate
* @param target_component The system component which should auto-calibrate
* @param mode The current ground-truth rpm
* @param axis The axis to calibrate: 0 roll, 1 pitch, 2 yaw
* @param time The time to average over in ms
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_request_dynamic_gyro_calibration_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, float mode, uint8_t axis, uint16_t time)
@ -127,6 +161,12 @@ static inline uint16_t mavlink_msg_request_dynamic_gyro_calibration_get_time(con
return (uint16_t)r.s;
}
/**
* @brief Decode a request_dynamic_gyro_calibration message into a struct
*
* @param msg The message to decode
* @param request_dynamic_gyro_calibration C-struct to decode the message contents into
*/
static inline void mavlink_msg_request_dynamic_gyro_calibration_decode(const mavlink_message_t* msg, mavlink_request_dynamic_gyro_calibration_t* request_dynamic_gyro_calibration)
{
request_dynamic_gyro_calibration->target_system = mavlink_msg_request_dynamic_gyro_calibration_get_target_system(msg);

View File

@ -13,7 +13,10 @@ typedef struct __mavlink_request_static_calibration_t
/**
* @brief Send a request_static_calibration message
* @brief Pack a request_static_calibration 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 target_system The system which should auto-calibrate
* @param target_component The system component which should auto-calibrate
@ -25,30 +28,57 @@ static inline uint16_t mavlink_msg_request_static_calibration_pack(uint8_t syste
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_REQUEST_STATIC_CALIBRATION;
i += put_uint8_t_by_index(target_system, i, msg->payload); //The system which should auto-calibrate
i += put_uint8_t_by_index(target_component, i, msg->payload); //The system component which should auto-calibrate
i += put_uint16_t_by_index(time, i, msg->payload); //The time to average over in ms
i += put_uint8_t_by_index(target_system, i, msg->payload); // The system which should auto-calibrate
i += put_uint8_t_by_index(target_component, i, msg->payload); // The system component which should auto-calibrate
i += put_uint16_t_by_index(time, i, msg->payload); // The time to average over in ms
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a request_static_calibration 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 target_system The system which should auto-calibrate
* @param target_component The system component which should auto-calibrate
* @param time The time to average over in ms
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_request_static_calibration_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, uint16_t time)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_REQUEST_STATIC_CALIBRATION;
i += put_uint8_t_by_index(target_system, i, msg->payload); //The system which should auto-calibrate
i += put_uint8_t_by_index(target_component, i, msg->payload); //The system component which should auto-calibrate
i += put_uint16_t_by_index(time, i, msg->payload); //The time to average over in ms
i += put_uint8_t_by_index(target_system, i, msg->payload); // The system which should auto-calibrate
i += put_uint8_t_by_index(target_component, i, msg->payload); // The system component which should auto-calibrate
i += put_uint16_t_by_index(time, i, msg->payload); // The time to average over in ms
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a request_static_calibration 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 request_static_calibration C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_request_static_calibration_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_request_static_calibration_t* request_static_calibration)
{
return mavlink_msg_request_static_calibration_pack(system_id, component_id, msg, request_static_calibration->target_system, request_static_calibration->target_component, request_static_calibration->time);
}
/**
* @brief Send a request_static_calibration message
* @param chan MAVLink channel to send the message
*
* @param target_system The system which should auto-calibrate
* @param target_component The system component which should auto-calibrate
* @param time The time to average over in ms
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_request_static_calibration_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t time)
@ -94,6 +124,12 @@ static inline uint16_t mavlink_msg_request_static_calibration_get_time(const mav
return (uint16_t)r.s;
}
/**
* @brief Decode a request_static_calibration message into a struct
*
* @param msg The message to decode
* @param request_static_calibration C-struct to decode the message contents into
*/
static inline void mavlink_msg_request_static_calibration_decode(const mavlink_message_t* msg, mavlink_request_static_calibration_t* request_static_calibration)
{
request_static_calibration->target_system = mavlink_msg_request_static_calibration_get_target_system(msg);

View File

@ -12,7 +12,10 @@ typedef struct __mavlink_set_altitude_t
/**
* @brief Send a set_altitude message
* @brief Pack a set_altitude 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 target The system setting the altitude
* @param mode The new altitude in meters
@ -23,28 +26,53 @@ static inline uint16_t mavlink_msg_set_altitude_pack(uint8_t system_id, uint8_t
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_SET_ALTITUDE;
i += put_uint8_t_by_index(target, i, msg->payload); //The system setting the altitude
i += put_uint32_t_by_index(mode, i, msg->payload); //The new altitude in meters
i += put_uint8_t_by_index(target, i, msg->payload); // The system setting the altitude
i += put_uint32_t_by_index(mode, i, msg->payload); // The new altitude in meters
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a set_altitude 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 target The system setting the altitude
* @param mode The new altitude in meters
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_set_altitude_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target, uint32_t mode)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_SET_ALTITUDE;
i += put_uint8_t_by_index(target, i, msg->payload); //The system setting the altitude
i += put_uint32_t_by_index(mode, i, msg->payload); //The new altitude in meters
i += put_uint8_t_by_index(target, i, msg->payload); // The system setting the altitude
i += put_uint32_t_by_index(mode, i, msg->payload); // The new altitude in meters
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a set_altitude 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 set_altitude C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_set_altitude_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_altitude_t* set_altitude)
{
return mavlink_msg_set_altitude_pack(system_id, component_id, msg, set_altitude->target, set_altitude->mode);
}
/**
* @brief Send a set_altitude message
* @param chan MAVLink channel to send the message
*
* @param target The system setting the altitude
* @param mode The new altitude in meters
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_set_altitude_send(mavlink_channel_t chan, uint8_t target, uint32_t mode)
@ -82,6 +110,12 @@ static inline uint32_t mavlink_msg_set_altitude_get_mode(const mavlink_message_t
return (uint32_t)r.i;
}
/**
* @brief Decode a set_altitude message into a struct
*
* @param msg The message to decode
* @param set_altitude C-struct to decode the message contents into
*/
static inline void mavlink_msg_set_altitude_decode(const mavlink_message_t* msg, mavlink_set_altitude_t* set_altitude)
{
set_altitude->target = mavlink_msg_set_altitude_get_target(msg);

View File

@ -12,7 +12,10 @@ typedef struct __mavlink_set_mode_t
/**
* @brief Send a set_mode message
* @brief Pack a set_mode 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 target The system setting the mode
* @param mode The new mode
@ -23,28 +26,53 @@ static inline uint16_t mavlink_msg_set_mode_pack(uint8_t system_id, uint8_t comp
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_SET_MODE;
i += put_uint8_t_by_index(target, i, msg->payload); //The system setting the mode
i += put_uint8_t_by_index(mode, i, msg->payload); //The new mode
i += put_uint8_t_by_index(target, i, msg->payload); // The system setting the mode
i += put_uint8_t_by_index(mode, i, msg->payload); // The new mode
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a set_mode 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 target The system setting the mode
* @param mode The new mode
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_set_mode_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target, uint8_t mode)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_SET_MODE;
i += put_uint8_t_by_index(target, i, msg->payload); //The system setting the mode
i += put_uint8_t_by_index(mode, i, msg->payload); //The new mode
i += put_uint8_t_by_index(target, i, msg->payload); // The system setting the mode
i += put_uint8_t_by_index(mode, i, msg->payload); // The new mode
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a set_mode 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 set_mode C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_set_mode_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_mode_t* set_mode)
{
return mavlink_msg_set_mode_pack(system_id, component_id, msg, set_mode->target, set_mode->mode);
}
/**
* @brief Send a set_mode message
* @param chan MAVLink channel to send the message
*
* @param target The system setting the mode
* @param mode The new mode
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_set_mode_send(mavlink_channel_t chan, uint8_t target, uint8_t mode)
@ -77,6 +105,12 @@ static inline uint8_t mavlink_msg_set_mode_get_mode(const mavlink_message_t* msg
return (uint8_t)(msg->payload+sizeof(uint8_t))[0];
}
/**
* @brief Decode a set_mode message into a struct
*
* @param msg The message to decode
* @param set_mode C-struct to decode the message contents into
*/
static inline void mavlink_msg_set_mode_decode(const mavlink_message_t* msg, mavlink_set_mode_t* set_mode)
{
set_mode->target = mavlink_msg_set_mode_get_target(msg);

View File

@ -12,7 +12,10 @@ typedef struct __mavlink_set_nav_mode_t
/**
* @brief Send a set_nav_mode message
* @brief Pack a set_nav_mode 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 target The system setting the mode
* @param nav_mode The new navigation mode
@ -23,28 +26,53 @@ static inline uint16_t mavlink_msg_set_nav_mode_pack(uint8_t system_id, uint8_t
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_SET_NAV_MODE;
i += put_uint8_t_by_index(target, i, msg->payload); //The system setting the mode
i += put_uint8_t_by_index(nav_mode, i, msg->payload); //The new navigation mode
i += put_uint8_t_by_index(target, i, msg->payload); // The system setting the mode
i += put_uint8_t_by_index(nav_mode, i, msg->payload); // The new navigation mode
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a set_nav_mode 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 target The system setting the mode
* @param nav_mode The new navigation mode
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_set_nav_mode_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target, uint8_t nav_mode)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_SET_NAV_MODE;
i += put_uint8_t_by_index(target, i, msg->payload); //The system setting the mode
i += put_uint8_t_by_index(nav_mode, i, msg->payload); //The new navigation mode
i += put_uint8_t_by_index(target, i, msg->payload); // The system setting the mode
i += put_uint8_t_by_index(nav_mode, i, msg->payload); // The new navigation mode
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a set_nav_mode 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 set_nav_mode C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_set_nav_mode_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_nav_mode_t* set_nav_mode)
{
return mavlink_msg_set_nav_mode_pack(system_id, component_id, msg, set_nav_mode->target, set_nav_mode->nav_mode);
}
/**
* @brief Send a set_nav_mode message
* @param chan MAVLink channel to send the message
*
* @param target The system setting the mode
* @param nav_mode The new navigation mode
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_set_nav_mode_send(mavlink_channel_t chan, uint8_t target, uint8_t nav_mode)
@ -77,6 +105,12 @@ static inline uint8_t mavlink_msg_set_nav_mode_get_nav_mode(const mavlink_messag
return (uint8_t)(msg->payload+sizeof(uint8_t))[0];
}
/**
* @brief Decode a set_nav_mode message into a struct
*
* @param msg The message to decode
* @param set_nav_mode C-struct to decode the message contents into
*/
static inline void mavlink_msg_set_nav_mode_decode(const mavlink_message_t* msg, mavlink_set_nav_mode_t* set_nav_mode)
{
set_nav_mode->target = mavlink_msg_set_nav_mode_get_target(msg);

View File

@ -19,7 +19,10 @@ typedef struct __mavlink_state_correction_t
/**
* @brief Send a state_correction message
* @brief Pack a state_correction 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 xErr x position error
* @param yErr y position error
@ -37,42 +40,81 @@ static inline uint16_t mavlink_msg_state_correction_pack(uint8_t system_id, uint
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_STATE_CORRECTION;
i += put_float_by_index(xErr, i, msg->payload); //x position error
i += put_float_by_index(yErr, i, msg->payload); //y position error
i += put_float_by_index(zErr, i, msg->payload); //z position error
i += put_float_by_index(rollErr, i, msg->payload); //roll error (radians)
i += put_float_by_index(pitchErr, i, msg->payload); //pitch error (radians)
i += put_float_by_index(yawErr, i, msg->payload); //yaw error (radians)
i += put_float_by_index(vxErr, i, msg->payload); //x velocity
i += put_float_by_index(vyErr, i, msg->payload); //y velocity
i += put_float_by_index(vzErr, i, msg->payload); //z velocity
i += put_float_by_index(xErr, i, msg->payload); // x position error
i += put_float_by_index(yErr, i, msg->payload); // y position error
i += put_float_by_index(zErr, i, msg->payload); // z position error
i += put_float_by_index(rollErr, i, msg->payload); // roll error (radians)
i += put_float_by_index(pitchErr, i, msg->payload); // pitch error (radians)
i += put_float_by_index(yawErr, i, msg->payload); // yaw error (radians)
i += put_float_by_index(vxErr, i, msg->payload); // x velocity
i += put_float_by_index(vyErr, i, msg->payload); // y velocity
i += put_float_by_index(vzErr, i, msg->payload); // z velocity
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a state_correction 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 xErr x position error
* @param yErr y position error
* @param zErr z position error
* @param rollErr roll error (radians)
* @param pitchErr pitch error (radians)
* @param yawErr yaw error (radians)
* @param vxErr x velocity
* @param vyErr y velocity
* @param vzErr z velocity
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_state_correction_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, float xErr, float yErr, float zErr, float rollErr, float pitchErr, float yawErr, float vxErr, float vyErr, float vzErr)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_STATE_CORRECTION;
i += put_float_by_index(xErr, i, msg->payload); //x position error
i += put_float_by_index(yErr, i, msg->payload); //y position error
i += put_float_by_index(zErr, i, msg->payload); //z position error
i += put_float_by_index(rollErr, i, msg->payload); //roll error (radians)
i += put_float_by_index(pitchErr, i, msg->payload); //pitch error (radians)
i += put_float_by_index(yawErr, i, msg->payload); //yaw error (radians)
i += put_float_by_index(vxErr, i, msg->payload); //x velocity
i += put_float_by_index(vyErr, i, msg->payload); //y velocity
i += put_float_by_index(vzErr, i, msg->payload); //z velocity
i += put_float_by_index(xErr, i, msg->payload); // x position error
i += put_float_by_index(yErr, i, msg->payload); // y position error
i += put_float_by_index(zErr, i, msg->payload); // z position error
i += put_float_by_index(rollErr, i, msg->payload); // roll error (radians)
i += put_float_by_index(pitchErr, i, msg->payload); // pitch error (radians)
i += put_float_by_index(yawErr, i, msg->payload); // yaw error (radians)
i += put_float_by_index(vxErr, i, msg->payload); // x velocity
i += put_float_by_index(vyErr, i, msg->payload); // y velocity
i += put_float_by_index(vzErr, i, msg->payload); // z velocity
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a state_correction 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 state_correction C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_state_correction_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_state_correction_t* state_correction)
{
return mavlink_msg_state_correction_pack(system_id, component_id, msg, state_correction->xErr, state_correction->yErr, state_correction->zErr, state_correction->rollErr, state_correction->pitchErr, state_correction->yawErr, state_correction->vxErr, state_correction->vyErr, state_correction->vzErr);
}
/**
* @brief Send a state_correction message
* @param chan MAVLink channel to send the message
*
* @param xErr x position error
* @param yErr y position error
* @param zErr z position error
* @param rollErr roll error (radians)
* @param pitchErr pitch error (radians)
* @param yawErr yaw error (radians)
* @param vxErr x velocity
* @param vyErr y velocity
* @param vzErr z velocity
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_state_correction_send(mavlink_channel_t chan, float xErr, float yErr, float zErr, float rollErr, float pitchErr, float yawErr, float vxErr, float vyErr, float vzErr)
@ -220,6 +262,12 @@ static inline float mavlink_msg_state_correction_get_vzErr(const mavlink_message
return (float)r.f;
}
/**
* @brief Decode a state_correction message into a struct
*
* @param msg The message to decode
* @param state_correction C-struct to decode the message contents into
*/
static inline void mavlink_msg_state_correction_decode(const mavlink_message_t* msg, mavlink_state_correction_t* state_correction)
{
state_correction->xErr = mavlink_msg_state_correction_get_xErr(msg);

View File

@ -13,7 +13,10 @@ typedef struct __mavlink_statustext_t
/**
* @brief Send a statustext message
* @brief Pack a statustext 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 severity Severity of status, 0 = info message, 255 = critical fault
* @param text Status text message, without null termination character
@ -24,28 +27,53 @@ static inline uint16_t mavlink_msg_statustext_pack(uint8_t system_id, uint8_t co
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_STATUSTEXT;
i += put_uint8_t_by_index(severity, i, msg->payload); //Severity of status, 0 = info message, 255 = critical fault
i += put_array_by_index(text, 50, i, msg->payload); //Status text message, without null termination character
i += put_uint8_t_by_index(severity, i, msg->payload); // Severity of status, 0 = info message, 255 = critical fault
i += put_array_by_index(text, 50, i, msg->payload); // Status text message, without null termination character
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a statustext 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 severity Severity of status, 0 = info message, 255 = critical fault
* @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)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_STATUSTEXT;
i += put_uint8_t_by_index(severity, i, msg->payload); //Severity of status, 0 = info message, 255 = critical fault
i += put_array_by_index(text, 50, i, msg->payload); //Status text message, without null termination character
i += put_uint8_t_by_index(severity, i, msg->payload); // Severity of status, 0 = info message, 255 = critical fault
i += put_array_by_index(text, 50, i, msg->payload); // Status text message, without null termination character
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a statustext 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 statustext C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_statustext_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_statustext_t* statustext)
{
return mavlink_msg_statustext_pack(system_id, component_id, msg, statustext->severity, statustext->text);
}
/**
* @brief Send a statustext message
* @param chan MAVLink channel to send the message
*
* @param severity Severity of status, 0 = info message, 255 = critical fault
* @param text Status text message, without null termination character
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_statustext_send(mavlink_channel_t chan, uint8_t severity, const int8_t* text)
@ -80,6 +108,12 @@ static inline uint16_t mavlink_msg_statustext_get_text(const mavlink_message_t*
return 50;
}
/**
* @brief Decode a statustext message into a struct
*
* @param msg The message to decode
* @param statustext C-struct to decode the message contents into
*/
static inline void mavlink_msg_statustext_decode(const mavlink_message_t* msg, mavlink_statustext_t* statustext)
{
statustext->severity = mavlink_msg_statustext_get_severity(msg);

View File

@ -17,7 +17,10 @@ typedef struct __mavlink_sys_status_t
/**
* @brief Send a sys_status message
* @brief Pack a sys_status 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 mode System mode, see MAV_MODE ENUM in mavlink/include/mavlink_types.h
* @param nav_mode Navigation mode, see MAV_NAV_MODE ENUM
@ -33,38 +36,73 @@ static inline uint16_t mavlink_msg_sys_status_pack(uint8_t system_id, uint8_t co
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_SYS_STATUS;
i += put_uint8_t_by_index(mode, i, msg->payload); //System mode, see MAV_MODE ENUM in mavlink/include/mavlink_types.h
i += put_uint8_t_by_index(nav_mode, i, msg->payload); //Navigation mode, see MAV_NAV_MODE ENUM
i += put_uint8_t_by_index(status, i, msg->payload); //System status flag, see MAV_STATUS ENUM
i += put_uint16_t_by_index(load, i, msg->payload); //Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000
i += put_uint16_t_by_index(vbat, i, msg->payload); //Battery voltage, in millivolts (1 = 1 millivolt)
i += put_uint8_t_by_index(motor_block, i, msg->payload); //Motor block status flag, 0: Motors can be switched on (and could be either off or on), 1: Mechanical motor block switch is on, motors cannot be switched on (and are definitely off)
i += put_uint16_t_by_index(packet_drop, i, msg->payload); //Dropped packets (packets that were corrupted on reception on the MAV)
i += put_uint8_t_by_index(mode, i, msg->payload); // System mode, see MAV_MODE ENUM in mavlink/include/mavlink_types.h
i += put_uint8_t_by_index(nav_mode, i, msg->payload); // Navigation mode, see MAV_NAV_MODE ENUM
i += put_uint8_t_by_index(status, i, msg->payload); // System status flag, see MAV_STATUS ENUM
i += put_uint16_t_by_index(load, i, msg->payload); // Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000
i += put_uint16_t_by_index(vbat, i, msg->payload); // Battery voltage, in millivolts (1 = 1 millivolt)
i += put_uint8_t_by_index(motor_block, i, msg->payload); // Motor block status flag, 0: Motors can be switched on (and could be either off or on), 1: Mechanical motor block switch is on, motors cannot be switched on (and are definitely off)
i += put_uint16_t_by_index(packet_drop, i, msg->payload); // Dropped packets (packets that were corrupted on reception on the MAV)
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a sys_status 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 mode System mode, see MAV_MODE ENUM in mavlink/include/mavlink_types.h
* @param nav_mode Navigation mode, see MAV_NAV_MODE ENUM
* @param status System status flag, see MAV_STATUS ENUM
* @param load Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000
* @param vbat Battery voltage, in millivolts (1 = 1 millivolt)
* @param motor_block Motor block status flag, 0: Motors can be switched on (and could be either off or on), 1: Mechanical motor block switch is on, motors cannot be switched on (and are definitely off)
* @param packet_drop Dropped packets (packets that were corrupted on reception on the MAV)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_sys_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t mode, uint8_t nav_mode, uint8_t status, uint16_t load, uint16_t vbat, uint8_t motor_block, uint16_t packet_drop)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_SYS_STATUS;
i += put_uint8_t_by_index(mode, i, msg->payload); //System mode, see MAV_MODE ENUM in mavlink/include/mavlink_types.h
i += put_uint8_t_by_index(nav_mode, i, msg->payload); //Navigation mode, see MAV_NAV_MODE ENUM
i += put_uint8_t_by_index(status, i, msg->payload); //System status flag, see MAV_STATUS ENUM
i += put_uint16_t_by_index(load, i, msg->payload); //Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000
i += put_uint16_t_by_index(vbat, i, msg->payload); //Battery voltage, in millivolts (1 = 1 millivolt)
i += put_uint8_t_by_index(motor_block, i, msg->payload); //Motor block status flag, 0: Motors can be switched on (and could be either off or on), 1: Mechanical motor block switch is on, motors cannot be switched on (and are definitely off)
i += put_uint16_t_by_index(packet_drop, i, msg->payload); //Dropped packets (packets that were corrupted on reception on the MAV)
i += put_uint8_t_by_index(mode, i, msg->payload); // System mode, see MAV_MODE ENUM in mavlink/include/mavlink_types.h
i += put_uint8_t_by_index(nav_mode, i, msg->payload); // Navigation mode, see MAV_NAV_MODE ENUM
i += put_uint8_t_by_index(status, i, msg->payload); // System status flag, see MAV_STATUS ENUM
i += put_uint16_t_by_index(load, i, msg->payload); // Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000
i += put_uint16_t_by_index(vbat, i, msg->payload); // Battery voltage, in millivolts (1 = 1 millivolt)
i += put_uint8_t_by_index(motor_block, i, msg->payload); // Motor block status flag, 0: Motors can be switched on (and could be either off or on), 1: Mechanical motor block switch is on, motors cannot be switched on (and are definitely off)
i += put_uint16_t_by_index(packet_drop, i, msg->payload); // Dropped packets (packets that were corrupted on reception on the MAV)
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a sys_status 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 sys_status C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_sys_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_sys_status_t* sys_status)
{
return mavlink_msg_sys_status_pack(system_id, component_id, msg, sys_status->mode, sys_status->nav_mode, sys_status->status, sys_status->load, sys_status->vbat, sys_status->motor_block, sys_status->packet_drop);
}
/**
* @brief Send a sys_status message
* @param chan MAVLink channel to send the message
*
* @param mode System mode, see MAV_MODE ENUM in mavlink/include/mavlink_types.h
* @param nav_mode Navigation mode, see MAV_NAV_MODE ENUM
* @param status System status flag, see MAV_STATUS ENUM
* @param load Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000
* @param vbat Battery voltage, in millivolts (1 = 1 millivolt)
* @param motor_block Motor block status flag, 0: Motors can be switched on (and could be either off or on), 1: Mechanical motor block switch is on, motors cannot be switched on (and are definitely off)
* @param packet_drop Dropped packets (packets that were corrupted on reception on the MAV)
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_sys_status_send(mavlink_channel_t chan, uint8_t mode, uint8_t nav_mode, uint8_t status, uint16_t load, uint16_t vbat, uint8_t motor_block, uint16_t packet_drop)
@ -156,6 +194,12 @@ static inline uint16_t mavlink_msg_sys_status_get_packet_drop(const mavlink_mess
return (uint16_t)r.s;
}
/**
* @brief Decode a sys_status message into a struct
*
* @param msg The message to decode
* @param sys_status C-struct to decode the message contents into
*/
static inline void mavlink_msg_sys_status_decode(const mavlink_message_t* msg, mavlink_sys_status_t* sys_status)
{
sys_status->mode = mavlink_msg_sys_status_get_mode(msg);

View File

@ -11,7 +11,10 @@ typedef struct __mavlink_system_time_t
/**
* @brief Send a system_time message
* @brief Pack a system_time 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 time_usec Timestamp of the master clock in microseconds since UNIX epoch.
* @return length of the message in bytes (excluding serial stream start sign)
@ -21,26 +24,49 @@ static inline uint16_t mavlink_msg_system_time_pack(uint8_t system_id, uint8_t c
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_SYSTEM_TIME;
i += put_uint64_t_by_index(time_usec, i, msg->payload); //Timestamp of the master clock in microseconds since UNIX epoch.
i += put_uint64_t_by_index(time_usec, i, msg->payload); // Timestamp of the master clock in microseconds since UNIX epoch.
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a system_time 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 time_usec Timestamp of the master clock in microseconds since UNIX epoch.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_system_time_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint64_t time_usec)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_SYSTEM_TIME;
i += put_uint64_t_by_index(time_usec, i, msg->payload); //Timestamp of the master clock in microseconds since UNIX epoch.
i += put_uint64_t_by_index(time_usec, i, msg->payload); // Timestamp of the master clock in microseconds since UNIX epoch.
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a system_time 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 system_time C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_system_time_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_system_time_t* system_time)
{
return mavlink_msg_system_time_pack(system_id, component_id, msg, system_time->time_usec);
}
/**
* @brief Send a system_time message
* @param chan MAVLink channel to send the message
*
* @param time_usec Timestamp of the master clock in microseconds since UNIX epoch.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_system_time_send(mavlink_channel_t chan, uint64_t time_usec)
@ -72,6 +98,12 @@ static inline uint64_t mavlink_msg_system_time_get_time_usec(const mavlink_messa
return (uint64_t)r.ll;
}
/**
* @brief Decode a system_time message into a struct
*
* @param msg The message to decode
* @param system_time C-struct to decode the message contents into
*/
static inline void mavlink_msg_system_time_decode(const mavlink_message_t* msg, mavlink_system_time_t* system_time)
{
system_time->time_usec = mavlink_msg_system_time_get_time_usec(msg);

View File

@ -25,7 +25,10 @@ typedef struct __mavlink_waypoint_t
/**
* @brief Send a waypoint message
* @brief Pack a waypoint 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 target_system System ID
* @param target_component Component ID
@ -49,54 +52,105 @@ static inline uint16_t mavlink_msg_waypoint_pack(uint8_t system_id, uint8_t comp
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_WAYPOINT;
i += put_uint8_t_by_index(target_system, i, msg->payload); //System ID
i += put_uint8_t_by_index(target_component, i, msg->payload); //Component ID
i += put_uint16_t_by_index(seq, i, msg->payload); //Sequence
i += put_uint8_t_by_index(frame, i, msg->payload); //The coordinate system of the waypoint. see MAV_FRAME in mavlink_types.h
i += put_uint8_t_by_index(action, i, msg->payload); //The scheduled action for the waypoint. see MAV_ACTION in mavlink_types.h
i += put_float_by_index(orbit, i, msg->payload); //Orbit to circle around the waypoint, in meters. Set to 0 to fly straight through the waypoint
i += put_uint8_t_by_index(orbit_direction, i, msg->payload); //Direction of the orbit circling: 0: clockwise, 1: counter-clockwise
i += put_float_by_index(param1, i, msg->payload); //For waypoints of type 0 and 1: Radius in which the waypoint is accepted as reached, in meters
i += put_float_by_index(param2, i, msg->payload); //For waypoints of type 0 and 1: Time that the MAV should stay inside the orbit before advancing, in milliseconds
i += put_uint8_t_by_index(current, i, msg->payload); //false:0, true:1
i += put_float_by_index(x, i, msg->payload); //local: x position, global: longitude
i += put_float_by_index(y, i, msg->payload); //y position: global: latitude
i += put_float_by_index(z, i, msg->payload); //z position: global: altitude
i += put_float_by_index(yaw, i, msg->payload); //yaw orientation in radians, 0 = NORTH
i += put_uint8_t_by_index(autocontinue, i, msg->payload); //autocontinue to next wp
i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID
i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID
i += put_uint16_t_by_index(seq, i, msg->payload); // Sequence
i += put_uint8_t_by_index(frame, i, msg->payload); // The coordinate system of the waypoint. see MAV_FRAME in mavlink_types.h
i += put_uint8_t_by_index(action, i, msg->payload); // The scheduled action for the waypoint. see MAV_ACTION in mavlink_types.h
i += put_float_by_index(orbit, i, msg->payload); // Orbit to circle around the waypoint, in meters. Set to 0 to fly straight through the waypoint
i += put_uint8_t_by_index(orbit_direction, i, msg->payload); // Direction of the orbit circling: 0: clockwise, 1: counter-clockwise
i += put_float_by_index(param1, i, msg->payload); // For waypoints of type 0 and 1: Radius in which the waypoint is accepted as reached, in meters
i += put_float_by_index(param2, i, msg->payload); // For waypoints of type 0 and 1: Time that the MAV should stay inside the orbit before advancing, in milliseconds
i += put_uint8_t_by_index(current, i, msg->payload); // false:0, true:1
i += put_float_by_index(x, i, msg->payload); // local: x position, global: longitude
i += put_float_by_index(y, i, msg->payload); // y position: global: latitude
i += put_float_by_index(z, i, msg->payload); // z position: global: altitude
i += put_float_by_index(yaw, i, msg->payload); // yaw orientation in radians, 0 = NORTH
i += put_uint8_t_by_index(autocontinue, i, msg->payload); // autocontinue to next wp
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a waypoint 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 target_system System ID
* @param target_component Component ID
* @param seq Sequence
* @param frame The coordinate system of the waypoint. see MAV_FRAME in mavlink_types.h
* @param action The scheduled action for the waypoint. see MAV_ACTION in mavlink_types.h
* @param orbit Orbit to circle around the waypoint, in meters. Set to 0 to fly straight through the waypoint
* @param orbit_direction Direction of the orbit circling: 0: clockwise, 1: counter-clockwise
* @param param1 For waypoints of type 0 and 1: Radius in which the waypoint is accepted as reached, in meters
* @param param2 For waypoints of type 0 and 1: Time that the MAV should stay inside the orbit before advancing, in milliseconds
* @param current false:0, true:1
* @param x local: x position, global: longitude
* @param y y position: global: latitude
* @param z z position: global: altitude
* @param yaw yaw orientation in radians, 0 = NORTH
* @param autocontinue autocontinue to next wp
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_waypoint_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, uint16_t seq, uint8_t frame, uint8_t action, float orbit, uint8_t orbit_direction, float param1, float param2, uint8_t current, float x, float y, float z, float yaw, uint8_t autocontinue)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_WAYPOINT;
i += put_uint8_t_by_index(target_system, i, msg->payload); //System ID
i += put_uint8_t_by_index(target_component, i, msg->payload); //Component ID
i += put_uint16_t_by_index(seq, i, msg->payload); //Sequence
i += put_uint8_t_by_index(frame, i, msg->payload); //The coordinate system of the waypoint. see MAV_FRAME in mavlink_types.h
i += put_uint8_t_by_index(action, i, msg->payload); //The scheduled action for the waypoint. see MAV_ACTION in mavlink_types.h
i += put_float_by_index(orbit, i, msg->payload); //Orbit to circle around the waypoint, in meters. Set to 0 to fly straight through the waypoint
i += put_uint8_t_by_index(orbit_direction, i, msg->payload); //Direction of the orbit circling: 0: clockwise, 1: counter-clockwise
i += put_float_by_index(param1, i, msg->payload); //For waypoints of type 0 and 1: Radius in which the waypoint is accepted as reached, in meters
i += put_float_by_index(param2, i, msg->payload); //For waypoints of type 0 and 1: Time that the MAV should stay inside the orbit before advancing, in milliseconds
i += put_uint8_t_by_index(current, i, msg->payload); //false:0, true:1
i += put_float_by_index(x, i, msg->payload); //local: x position, global: longitude
i += put_float_by_index(y, i, msg->payload); //y position: global: latitude
i += put_float_by_index(z, i, msg->payload); //z position: global: altitude
i += put_float_by_index(yaw, i, msg->payload); //yaw orientation in radians, 0 = NORTH
i += put_uint8_t_by_index(autocontinue, i, msg->payload); //autocontinue to next wp
i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID
i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID
i += put_uint16_t_by_index(seq, i, msg->payload); // Sequence
i += put_uint8_t_by_index(frame, i, msg->payload); // The coordinate system of the waypoint. see MAV_FRAME in mavlink_types.h
i += put_uint8_t_by_index(action, i, msg->payload); // The scheduled action for the waypoint. see MAV_ACTION in mavlink_types.h
i += put_float_by_index(orbit, i, msg->payload); // Orbit to circle around the waypoint, in meters. Set to 0 to fly straight through the waypoint
i += put_uint8_t_by_index(orbit_direction, i, msg->payload); // Direction of the orbit circling: 0: clockwise, 1: counter-clockwise
i += put_float_by_index(param1, i, msg->payload); // For waypoints of type 0 and 1: Radius in which the waypoint is accepted as reached, in meters
i += put_float_by_index(param2, i, msg->payload); // For waypoints of type 0 and 1: Time that the MAV should stay inside the orbit before advancing, in milliseconds
i += put_uint8_t_by_index(current, i, msg->payload); // false:0, true:1
i += put_float_by_index(x, i, msg->payload); // local: x position, global: longitude
i += put_float_by_index(y, i, msg->payload); // y position: global: latitude
i += put_float_by_index(z, i, msg->payload); // z position: global: altitude
i += put_float_by_index(yaw, i, msg->payload); // yaw orientation in radians, 0 = NORTH
i += put_uint8_t_by_index(autocontinue, i, msg->payload); // autocontinue to next wp
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a waypoint 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 waypoint C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_waypoint_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_waypoint_t* waypoint)
{
return mavlink_msg_waypoint_pack(system_id, component_id, msg, waypoint->target_system, waypoint->target_component, waypoint->seq, waypoint->frame, waypoint->action, waypoint->orbit, waypoint->orbit_direction, waypoint->param1, waypoint->param2, waypoint->current, waypoint->x, waypoint->y, waypoint->z, waypoint->yaw, waypoint->autocontinue);
}
/**
* @brief Send a waypoint message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID
* @param target_component Component ID
* @param seq Sequence
* @param frame The coordinate system of the waypoint. see MAV_FRAME in mavlink_types.h
* @param action The scheduled action for the waypoint. see MAV_ACTION in mavlink_types.h
* @param orbit Orbit to circle around the waypoint, in meters. Set to 0 to fly straight through the waypoint
* @param orbit_direction Direction of the orbit circling: 0: clockwise, 1: counter-clockwise
* @param param1 For waypoints of type 0 and 1: Radius in which the waypoint is accepted as reached, in meters
* @param param2 For waypoints of type 0 and 1: Time that the MAV should stay inside the orbit before advancing, in milliseconds
* @param current false:0, true:1
* @param x local: x position, global: longitude
* @param y y position: global: latitude
* @param z z position: global: altitude
* @param yaw yaw orientation in radians, 0 = NORTH
* @param autocontinue autocontinue to next wp
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_waypoint_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t seq, uint8_t frame, uint8_t action, float orbit, uint8_t orbit_direction, float param1, float param2, uint8_t current, float x, float y, float z, float yaw, uint8_t autocontinue)
@ -297,6 +351,12 @@ static inline uint8_t mavlink_msg_waypoint_get_autocontinue(const mavlink_messag
return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(float)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
}
/**
* @brief Decode a waypoint message into a struct
*
* @param msg The message to decode
* @param waypoint C-struct to decode the message contents into
*/
static inline void mavlink_msg_waypoint_decode(const mavlink_message_t* msg, mavlink_waypoint_t* waypoint)
{
waypoint->target_system = mavlink_msg_waypoint_get_target_system(msg);

View File

@ -13,7 +13,10 @@ typedef struct __mavlink_waypoint_ack_t
/**
* @brief Send a waypoint_ack message
* @brief Pack a waypoint_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 target_system System ID
* @param target_component Component ID
@ -25,30 +28,57 @@ static inline uint16_t mavlink_msg_waypoint_ack_pack(uint8_t system_id, uint8_t
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_WAYPOINT_ACK;
i += put_uint8_t_by_index(target_system, i, msg->payload); //System ID
i += put_uint8_t_by_index(target_component, i, msg->payload); //Component ID
i += put_uint8_t_by_index(type, i, msg->payload); //0: OK, 1: Error
i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID
i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID
i += put_uint8_t_by_index(type, i, msg->payload); // 0: OK, 1: Error
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a waypoint_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 target_system System ID
* @param target_component Component ID
* @param type 0: OK, 1: Error
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_waypoint_ack_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, uint8_t type)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_WAYPOINT_ACK;
i += put_uint8_t_by_index(target_system, i, msg->payload); //System ID
i += put_uint8_t_by_index(target_component, i, msg->payload); //Component ID
i += put_uint8_t_by_index(type, i, msg->payload); //0: OK, 1: Error
i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID
i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID
i += put_uint8_t_by_index(type, i, msg->payload); // 0: OK, 1: Error
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a waypoint_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 waypoint_ack C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_waypoint_ack_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_waypoint_ack_t* waypoint_ack)
{
return mavlink_msg_waypoint_ack_pack(system_id, component_id, msg, waypoint_ack->target_system, waypoint_ack->target_component, waypoint_ack->type);
}
/**
* @brief Send a waypoint_ack message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID
* @param target_component Component ID
* @param type 0: OK, 1: Error
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_waypoint_ack_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t type)
@ -91,6 +121,12 @@ static inline uint8_t mavlink_msg_waypoint_ack_get_type(const mavlink_message_t*
return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0];
}
/**
* @brief Decode a waypoint_ack message into a struct
*
* @param msg The message to decode
* @param waypoint_ack C-struct to decode the message contents into
*/
static inline void mavlink_msg_waypoint_ack_decode(const mavlink_message_t* msg, mavlink_waypoint_ack_t* waypoint_ack)
{
waypoint_ack->target_system = mavlink_msg_waypoint_ack_get_target_system(msg);

View File

@ -12,7 +12,10 @@ typedef struct __mavlink_waypoint_clear_all_t
/**
* @brief Send a waypoint_clear_all message
* @brief Pack a waypoint_clear_all 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 target_system System ID
* @param target_component Component ID
@ -23,28 +26,53 @@ static inline uint16_t mavlink_msg_waypoint_clear_all_pack(uint8_t system_id, ui
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_WAYPOINT_CLEAR_ALL;
i += put_uint8_t_by_index(target_system, i, msg->payload); //System ID
i += put_uint8_t_by_index(target_component, i, msg->payload); //Component ID
i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID
i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a waypoint_clear_all 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 target_system System ID
* @param target_component Component ID
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_waypoint_clear_all_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)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_WAYPOINT_CLEAR_ALL;
i += put_uint8_t_by_index(target_system, i, msg->payload); //System ID
i += put_uint8_t_by_index(target_component, i, msg->payload); //Component ID
i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID
i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a waypoint_clear_all 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 waypoint_clear_all C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_waypoint_clear_all_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_waypoint_clear_all_t* waypoint_clear_all)
{
return mavlink_msg_waypoint_clear_all_pack(system_id, component_id, msg, waypoint_clear_all->target_system, waypoint_clear_all->target_component);
}
/**
* @brief Send a waypoint_clear_all message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID
* @param target_component Component ID
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_waypoint_clear_all_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component)
@ -77,6 +105,12 @@ static inline uint8_t mavlink_msg_waypoint_clear_all_get_target_component(const
return (uint8_t)(msg->payload+sizeof(uint8_t))[0];
}
/**
* @brief Decode a waypoint_clear_all message into a struct
*
* @param msg The message to decode
* @param waypoint_clear_all C-struct to decode the message contents into
*/
static inline void mavlink_msg_waypoint_clear_all_decode(const mavlink_message_t* msg, mavlink_waypoint_clear_all_t* waypoint_clear_all)
{
waypoint_clear_all->target_system = mavlink_msg_waypoint_clear_all_get_target_system(msg);

View File

@ -13,7 +13,10 @@ typedef struct __mavlink_waypoint_count_t
/**
* @brief Send a waypoint_count message
* @brief Pack a waypoint_count 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 target_system System ID
* @param target_component Component ID
@ -25,30 +28,57 @@ static inline uint16_t mavlink_msg_waypoint_count_pack(uint8_t system_id, uint8_
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_WAYPOINT_COUNT;
i += put_uint8_t_by_index(target_system, i, msg->payload); //System ID
i += put_uint8_t_by_index(target_component, i, msg->payload); //Component ID
i += put_uint16_t_by_index(count, i, msg->payload); //Number of Waypoints in the Sequence
i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID
i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID
i += put_uint16_t_by_index(count, i, msg->payload); // Number of Waypoints in the Sequence
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a waypoint_count 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 target_system System ID
* @param target_component Component ID
* @param count Number of Waypoints in the Sequence
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_waypoint_count_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, uint16_t count)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_WAYPOINT_COUNT;
i += put_uint8_t_by_index(target_system, i, msg->payload); //System ID
i += put_uint8_t_by_index(target_component, i, msg->payload); //Component ID
i += put_uint16_t_by_index(count, i, msg->payload); //Number of Waypoints in the Sequence
i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID
i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID
i += put_uint16_t_by_index(count, i, msg->payload); // Number of Waypoints in the Sequence
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a waypoint_count 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 waypoint_count C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_waypoint_count_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_waypoint_count_t* waypoint_count)
{
return mavlink_msg_waypoint_count_pack(system_id, component_id, msg, waypoint_count->target_system, waypoint_count->target_component, waypoint_count->count);
}
/**
* @brief Send a waypoint_count message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID
* @param target_component Component ID
* @param count Number of Waypoints in the Sequence
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_waypoint_count_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t count)
@ -94,6 +124,12 @@ static inline uint16_t mavlink_msg_waypoint_count_get_count(const mavlink_messag
return (uint16_t)r.s;
}
/**
* @brief Decode a waypoint_count message into a struct
*
* @param msg The message to decode
* @param waypoint_count C-struct to decode the message contents into
*/
static inline void mavlink_msg_waypoint_count_decode(const mavlink_message_t* msg, mavlink_waypoint_count_t* waypoint_count)
{
waypoint_count->target_system = mavlink_msg_waypoint_count_get_target_system(msg);

View File

@ -11,7 +11,10 @@ typedef struct __mavlink_waypoint_current_t
/**
* @brief Send a waypoint_current message
* @brief Pack a waypoint_current 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 seq Sequence
* @return length of the message in bytes (excluding serial stream start sign)
@ -21,26 +24,49 @@ static inline uint16_t mavlink_msg_waypoint_current_pack(uint8_t system_id, uint
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_WAYPOINT_CURRENT;
i += put_uint16_t_by_index(seq, i, msg->payload); //Sequence
i += put_uint16_t_by_index(seq, i, msg->payload); // Sequence
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a waypoint_current 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 seq Sequence
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_waypoint_current_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint16_t seq)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_WAYPOINT_CURRENT;
i += put_uint16_t_by_index(seq, i, msg->payload); //Sequence
i += put_uint16_t_by_index(seq, i, msg->payload); // Sequence
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a waypoint_current 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 waypoint_current C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_waypoint_current_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_waypoint_current_t* waypoint_current)
{
return mavlink_msg_waypoint_current_pack(system_id, component_id, msg, waypoint_current->seq);
}
/**
* @brief Send a waypoint_current message
* @param chan MAVLink channel to send the message
*
* @param seq Sequence
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_waypoint_current_send(mavlink_channel_t chan, uint16_t seq)
@ -66,6 +92,12 @@ static inline uint16_t mavlink_msg_waypoint_current_get_seq(const mavlink_messag
return (uint16_t)r.s;
}
/**
* @brief Decode a waypoint_current message into a struct
*
* @param msg The message to decode
* @param waypoint_current C-struct to decode the message contents into
*/
static inline void mavlink_msg_waypoint_current_decode(const mavlink_message_t* msg, mavlink_waypoint_current_t* waypoint_current)
{
waypoint_current->seq = mavlink_msg_waypoint_current_get_seq(msg);

View File

@ -11,7 +11,10 @@ typedef struct __mavlink_waypoint_reached_t
/**
* @brief Send a waypoint_reached message
* @brief Pack a waypoint_reached 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 seq Sequence
* @return length of the message in bytes (excluding serial stream start sign)
@ -21,26 +24,49 @@ static inline uint16_t mavlink_msg_waypoint_reached_pack(uint8_t system_id, uint
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_WAYPOINT_REACHED;
i += put_uint16_t_by_index(seq, i, msg->payload); //Sequence
i += put_uint16_t_by_index(seq, i, msg->payload); // Sequence
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a waypoint_reached 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 seq Sequence
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_waypoint_reached_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint16_t seq)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_WAYPOINT_REACHED;
i += put_uint16_t_by_index(seq, i, msg->payload); //Sequence
i += put_uint16_t_by_index(seq, i, msg->payload); // Sequence
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a waypoint_reached 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 waypoint_reached C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_waypoint_reached_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_waypoint_reached_t* waypoint_reached)
{
return mavlink_msg_waypoint_reached_pack(system_id, component_id, msg, waypoint_reached->seq);
}
/**
* @brief Send a waypoint_reached message
* @param chan MAVLink channel to send the message
*
* @param seq Sequence
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_waypoint_reached_send(mavlink_channel_t chan, uint16_t seq)
@ -66,6 +92,12 @@ static inline uint16_t mavlink_msg_waypoint_reached_get_seq(const mavlink_messag
return (uint16_t)r.s;
}
/**
* @brief Decode a waypoint_reached message into a struct
*
* @param msg The message to decode
* @param waypoint_reached C-struct to decode the message contents into
*/
static inline void mavlink_msg_waypoint_reached_decode(const mavlink_message_t* msg, mavlink_waypoint_reached_t* waypoint_reached)
{
waypoint_reached->seq = mavlink_msg_waypoint_reached_get_seq(msg);

View File

@ -13,7 +13,10 @@ typedef struct __mavlink_waypoint_request_t
/**
* @brief Send a waypoint_request message
* @brief Pack a waypoint_request 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 target_system System ID
* @param target_component Component ID
@ -25,30 +28,57 @@ static inline uint16_t mavlink_msg_waypoint_request_pack(uint8_t system_id, uint
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_WAYPOINT_REQUEST;
i += put_uint8_t_by_index(target_system, i, msg->payload); //System ID
i += put_uint8_t_by_index(target_component, i, msg->payload); //Component ID
i += put_uint16_t_by_index(seq, i, msg->payload); //Sequence
i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID
i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID
i += put_uint16_t_by_index(seq, i, msg->payload); // Sequence
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a waypoint_request 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 target_system System ID
* @param target_component Component ID
* @param seq Sequence
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_waypoint_request_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, uint16_t seq)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_WAYPOINT_REQUEST;
i += put_uint8_t_by_index(target_system, i, msg->payload); //System ID
i += put_uint8_t_by_index(target_component, i, msg->payload); //Component ID
i += put_uint16_t_by_index(seq, i, msg->payload); //Sequence
i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID
i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID
i += put_uint16_t_by_index(seq, i, msg->payload); // Sequence
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a waypoint_request 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 waypoint_request C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_waypoint_request_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_waypoint_request_t* waypoint_request)
{
return mavlink_msg_waypoint_request_pack(system_id, component_id, msg, waypoint_request->target_system, waypoint_request->target_component, waypoint_request->seq);
}
/**
* @brief Send a waypoint_request message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID
* @param target_component Component ID
* @param seq Sequence
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_waypoint_request_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t seq)
@ -94,6 +124,12 @@ static inline uint16_t mavlink_msg_waypoint_request_get_seq(const mavlink_messag
return (uint16_t)r.s;
}
/**
* @brief Decode a waypoint_request message into a struct
*
* @param msg The message to decode
* @param waypoint_request C-struct to decode the message contents into
*/
static inline void mavlink_msg_waypoint_request_decode(const mavlink_message_t* msg, mavlink_waypoint_request_t* waypoint_request)
{
waypoint_request->target_system = mavlink_msg_waypoint_request_get_target_system(msg);

View File

@ -12,7 +12,10 @@ typedef struct __mavlink_waypoint_request_list_t
/**
* @brief Send a waypoint_request_list message
* @brief Pack a waypoint_request_list 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 target_system System ID
* @param target_component Component ID
@ -23,28 +26,53 @@ static inline uint16_t mavlink_msg_waypoint_request_list_pack(uint8_t system_id,
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_WAYPOINT_REQUEST_LIST;
i += put_uint8_t_by_index(target_system, i, msg->payload); //System ID
i += put_uint8_t_by_index(target_component, i, msg->payload); //Component ID
i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID
i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a waypoint_request_list 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 target_system System ID
* @param target_component Component ID
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_waypoint_request_list_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)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_WAYPOINT_REQUEST_LIST;
i += put_uint8_t_by_index(target_system, i, msg->payload); //System ID
i += put_uint8_t_by_index(target_component, i, msg->payload); //Component ID
i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID
i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a waypoint_request_list 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 waypoint_request_list C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_waypoint_request_list_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_waypoint_request_list_t* waypoint_request_list)
{
return mavlink_msg_waypoint_request_list_pack(system_id, component_id, msg, waypoint_request_list->target_system, waypoint_request_list->target_component);
}
/**
* @brief Send a waypoint_request_list message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID
* @param target_component Component ID
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_waypoint_request_list_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component)
@ -77,6 +105,12 @@ static inline uint8_t mavlink_msg_waypoint_request_list_get_target_component(con
return (uint8_t)(msg->payload+sizeof(uint8_t))[0];
}
/**
* @brief Decode a waypoint_request_list message into a struct
*
* @param msg The message to decode
* @param waypoint_request_list C-struct to decode the message contents into
*/
static inline void mavlink_msg_waypoint_request_list_decode(const mavlink_message_t* msg, mavlink_waypoint_request_list_t* waypoint_request_list)
{
waypoint_request_list->target_system = mavlink_msg_waypoint_request_list_get_target_system(msg);

View File

@ -13,7 +13,10 @@ typedef struct __mavlink_waypoint_set_current_t
/**
* @brief Send a waypoint_set_current message
* @brief Pack a waypoint_set_current 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 target_system System ID
* @param target_component Component ID
@ -25,30 +28,57 @@ static inline uint16_t mavlink_msg_waypoint_set_current_pack(uint8_t system_id,
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_WAYPOINT_SET_CURRENT;
i += put_uint8_t_by_index(target_system, i, msg->payload); //System ID
i += put_uint8_t_by_index(target_component, i, msg->payload); //Component ID
i += put_uint16_t_by_index(seq, i, msg->payload); //Sequence
i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID
i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID
i += put_uint16_t_by_index(seq, i, msg->payload); // Sequence
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a waypoint_set_current 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 target_system System ID
* @param target_component Component ID
* @param seq Sequence
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_waypoint_set_current_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, uint16_t seq)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_WAYPOINT_SET_CURRENT;
i += put_uint8_t_by_index(target_system, i, msg->payload); //System ID
i += put_uint8_t_by_index(target_component, i, msg->payload); //Component ID
i += put_uint16_t_by_index(seq, i, msg->payload); //Sequence
i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID
i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID
i += put_uint16_t_by_index(seq, i, msg->payload); // Sequence
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a waypoint_set_current 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 waypoint_set_current C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_waypoint_set_current_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_waypoint_set_current_t* waypoint_set_current)
{
return mavlink_msg_waypoint_set_current_pack(system_id, component_id, msg, waypoint_set_current->target_system, waypoint_set_current->target_component, waypoint_set_current->seq);
}
/**
* @brief Send a waypoint_set_current message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID
* @param target_component Component ID
* @param seq Sequence
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_waypoint_set_current_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t seq)
@ -94,6 +124,12 @@ static inline uint16_t mavlink_msg_waypoint_set_current_get_seq(const mavlink_me
return (uint16_t)r.s;
}
/**
* @brief Decode a waypoint_set_current message into a struct
*
* @param msg The message to decode
* @param waypoint_set_current C-struct to decode the message contents into
*/
static inline void mavlink_msg_waypoint_set_current_decode(const mavlink_message_t* msg, mavlink_waypoint_set_current_t* waypoint_set_current)
{
waypoint_set_current->target_system = mavlink_msg_waypoint_set_current_get_target_system(msg);

View File

@ -20,7 +20,10 @@ typedef struct __mavlink_waypoint_set_global_reference_t
/**
* @brief Send a waypoint_set_global_reference message
* @brief Pack a waypoint_set_global_reference 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 target_system System ID
* @param target_component Component ID
@ -39,44 +42,85 @@ static inline uint16_t mavlink_msg_waypoint_set_global_reference_pack(uint8_t sy
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_WAYPOINT_SET_GLOBAL_REFERENCE;
i += put_uint8_t_by_index(target_system, i, msg->payload); //System ID
i += put_uint8_t_by_index(target_component, i, msg->payload); //Component ID
i += put_float_by_index(global_x, i, msg->payload); //global x position
i += put_float_by_index(global_y, i, msg->payload); //global y position
i += put_float_by_index(global_z, i, msg->payload); //global z position
i += put_float_by_index(global_yaw, i, msg->payload); //global yaw orientation in radians, 0 = NORTH
i += put_float_by_index(local_x, i, msg->payload); //local x position that matches the global x position
i += put_float_by_index(local_y, i, msg->payload); //local y position that matches the global y position
i += put_float_by_index(local_z, i, msg->payload); //local z position that matches the global z position
i += put_float_by_index(local_yaw, i, msg->payload); //local yaw that matches the global yaw orientation
i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID
i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID
i += put_float_by_index(global_x, i, msg->payload); // global x position
i += put_float_by_index(global_y, i, msg->payload); // global y position
i += put_float_by_index(global_z, i, msg->payload); // global z position
i += put_float_by_index(global_yaw, i, msg->payload); // global yaw orientation in radians, 0 = NORTH
i += put_float_by_index(local_x, i, msg->payload); // local x position that matches the global x position
i += put_float_by_index(local_y, i, msg->payload); // local y position that matches the global y position
i += put_float_by_index(local_z, i, msg->payload); // local z position that matches the global z position
i += put_float_by_index(local_yaw, i, msg->payload); // local yaw that matches the global yaw orientation
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a waypoint_set_global_reference 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 target_system System ID
* @param target_component Component ID
* @param global_x global x position
* @param global_y global y position
* @param global_z global z position
* @param global_yaw global yaw orientation in radians, 0 = NORTH
* @param local_x local x position that matches the global x position
* @param local_y local y position that matches the global y position
* @param local_z local z position that matches the global z position
* @param local_yaw local yaw that matches the global yaw orientation
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_waypoint_set_global_reference_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, float global_x, float global_y, float global_z, float global_yaw, float local_x, float local_y, float local_z, float local_yaw)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_WAYPOINT_SET_GLOBAL_REFERENCE;
i += put_uint8_t_by_index(target_system, i, msg->payload); //System ID
i += put_uint8_t_by_index(target_component, i, msg->payload); //Component ID
i += put_float_by_index(global_x, i, msg->payload); //global x position
i += put_float_by_index(global_y, i, msg->payload); //global y position
i += put_float_by_index(global_z, i, msg->payload); //global z position
i += put_float_by_index(global_yaw, i, msg->payload); //global yaw orientation in radians, 0 = NORTH
i += put_float_by_index(local_x, i, msg->payload); //local x position that matches the global x position
i += put_float_by_index(local_y, i, msg->payload); //local y position that matches the global y position
i += put_float_by_index(local_z, i, msg->payload); //local z position that matches the global z position
i += put_float_by_index(local_yaw, i, msg->payload); //local yaw that matches the global yaw orientation
i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID
i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID
i += put_float_by_index(global_x, i, msg->payload); // global x position
i += put_float_by_index(global_y, i, msg->payload); // global y position
i += put_float_by_index(global_z, i, msg->payload); // global z position
i += put_float_by_index(global_yaw, i, msg->payload); // global yaw orientation in radians, 0 = NORTH
i += put_float_by_index(local_x, i, msg->payload); // local x position that matches the global x position
i += put_float_by_index(local_y, i, msg->payload); // local y position that matches the global y position
i += put_float_by_index(local_z, i, msg->payload); // local z position that matches the global z position
i += put_float_by_index(local_yaw, i, msg->payload); // local yaw that matches the global yaw orientation
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a waypoint_set_global_reference 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 waypoint_set_global_reference C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_waypoint_set_global_reference_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_waypoint_set_global_reference_t* waypoint_set_global_reference)
{
return mavlink_msg_waypoint_set_global_reference_pack(system_id, component_id, msg, waypoint_set_global_reference->target_system, waypoint_set_global_reference->target_component, waypoint_set_global_reference->global_x, waypoint_set_global_reference->global_y, waypoint_set_global_reference->global_z, waypoint_set_global_reference->global_yaw, waypoint_set_global_reference->local_x, waypoint_set_global_reference->local_y, waypoint_set_global_reference->local_z, waypoint_set_global_reference->local_yaw);
}
/**
* @brief Send a waypoint_set_global_reference message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID
* @param target_component Component ID
* @param global_x global x position
* @param global_y global y position
* @param global_z global z position
* @param global_yaw global yaw orientation in radians, 0 = NORTH
* @param local_x local x position that matches the global x position
* @param local_y local y position that matches the global y position
* @param local_z local z position that matches the global z position
* @param local_yaw local yaw that matches the global yaw orientation
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_waypoint_set_global_reference_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, float global_x, float global_y, float global_z, float global_yaw, float local_x, float local_y, float local_z, float local_yaw)
@ -229,6 +273,12 @@ static inline float mavlink_msg_waypoint_set_global_reference_get_local_yaw(cons
return (float)r.f;
}
/**
* @brief Decode a waypoint_set_global_reference message into a struct
*
* @param msg The message to decode
* @param waypoint_set_global_reference C-struct to decode the message contents into
*/
static inline void mavlink_msg_waypoint_set_global_reference_decode(const mavlink_message_t* msg, mavlink_waypoint_set_global_reference_t* waypoint_set_global_reference)
{
waypoint_set_global_reference->target_system = mavlink_msg_waypoint_set_global_reference_get_target_system(msg);

View File

@ -42,6 +42,10 @@ enum MAV_ACTION {
MAV_ACTION_SET_ORIGIN = 28,
MAV_ACITON_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_NB ///< Number of MAV actions
};
@ -108,6 +112,7 @@ enum MAV_COMPONENT {
MAV_COMP_ID_BLOBTRACKER,
MAV_COMP_ID_PATHPLANNER,
MAV_COMP_ID_AIRSLAM,
MAV_COMP_ID_MAPPER,
MAV_COMP_ID_IMU = 200
};
@ -132,6 +137,12 @@ enum MAV_DATA_STREAM{
enum DATA_TYPES {
DATA_TYPE_JPEG_IMAGE = 0,
DATA_TYPE_RAW_IMAGE = 1,
DATA_TYPE_KINECT
};
#define MAVLINK_STX 0x55 ///< Packet start sign
#define MAVLINK_STX_LEN 1 ///< Length of start sign
#define MAVLINK_MAX_PAYLOAD_LEN 255 ///< Maximum payload length

View File

@ -1,7 +1,7 @@
/** @file
* @brief MAVLink comm protocol.
* @see http://pixhawk.ethz.ch/software/mavlink
* Generated on Tuesday, December 7 2010, 13:34 UTC
* Generated on Friday, January 7 2011, 10:04 UTC
*/
#ifndef MAVLINK_H
#define MAVLINK_H

View File

@ -19,7 +19,10 @@ typedef struct __mavlink_attitude_control_t
/**
* @brief Send a attitude_control message
* @brief Pack a attitude_control 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 target The system to be controlled
* @param roll roll
@ -37,42 +40,81 @@ static inline uint16_t mavlink_msg_attitude_control_pack(uint8_t system_id, uint
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_ATTITUDE_CONTROL;
i += put_uint8_t_by_index(target, i, msg->payload); //The system to be controlled
i += put_float_by_index(roll, i, msg->payload); //roll
i += put_float_by_index(pitch, i, msg->payload); //pitch
i += put_float_by_index(yaw, i, msg->payload); //yaw
i += put_float_by_index(thrust, i, msg->payload); //thrust
i += put_uint8_t_by_index(roll_manual, i, msg->payload); //roll control enabled auto:0, manual:1
i += put_uint8_t_by_index(pitch_manual, i, msg->payload); //pitch auto:0, manual:1
i += put_uint8_t_by_index(yaw_manual, i, msg->payload); //yaw auto:0, manual:1
i += put_uint8_t_by_index(thrust_manual, i, msg->payload); //thrust auto:0, manual:1
i += put_uint8_t_by_index(target, i, msg->payload); // The system to be controlled
i += put_float_by_index(roll, i, msg->payload); // roll
i += put_float_by_index(pitch, i, msg->payload); // pitch
i += put_float_by_index(yaw, i, msg->payload); // yaw
i += put_float_by_index(thrust, i, msg->payload); // thrust
i += put_uint8_t_by_index(roll_manual, i, msg->payload); // roll control enabled auto:0, manual:1
i += put_uint8_t_by_index(pitch_manual, i, msg->payload); // pitch auto:0, manual:1
i += put_uint8_t_by_index(yaw_manual, i, msg->payload); // yaw auto:0, manual:1
i += put_uint8_t_by_index(thrust_manual, i, msg->payload); // thrust auto:0, manual:1
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a attitude_control 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 target The system to be controlled
* @param roll roll
* @param pitch pitch
* @param yaw yaw
* @param thrust thrust
* @param roll_manual roll control enabled auto:0, manual:1
* @param pitch_manual pitch auto:0, manual:1
* @param yaw_manual yaw auto:0, manual:1
* @param thrust_manual thrust auto:0, manual:1
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_attitude_control_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target, float roll, float pitch, float yaw, float thrust, uint8_t roll_manual, uint8_t pitch_manual, uint8_t yaw_manual, uint8_t thrust_manual)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_ATTITUDE_CONTROL;
i += put_uint8_t_by_index(target, i, msg->payload); //The system to be controlled
i += put_float_by_index(roll, i, msg->payload); //roll
i += put_float_by_index(pitch, i, msg->payload); //pitch
i += put_float_by_index(yaw, i, msg->payload); //yaw
i += put_float_by_index(thrust, i, msg->payload); //thrust
i += put_uint8_t_by_index(roll_manual, i, msg->payload); //roll control enabled auto:0, manual:1
i += put_uint8_t_by_index(pitch_manual, i, msg->payload); //pitch auto:0, manual:1
i += put_uint8_t_by_index(yaw_manual, i, msg->payload); //yaw auto:0, manual:1
i += put_uint8_t_by_index(thrust_manual, i, msg->payload); //thrust auto:0, manual:1
i += put_uint8_t_by_index(target, i, msg->payload); // The system to be controlled
i += put_float_by_index(roll, i, msg->payload); // roll
i += put_float_by_index(pitch, i, msg->payload); // pitch
i += put_float_by_index(yaw, i, msg->payload); // yaw
i += put_float_by_index(thrust, i, msg->payload); // thrust
i += put_uint8_t_by_index(roll_manual, i, msg->payload); // roll control enabled auto:0, manual:1
i += put_uint8_t_by_index(pitch_manual, i, msg->payload); // pitch auto:0, manual:1
i += put_uint8_t_by_index(yaw_manual, i, msg->payload); // yaw auto:0, manual:1
i += put_uint8_t_by_index(thrust_manual, i, msg->payload); // thrust auto:0, manual:1
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a attitude_control 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 attitude_control C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_attitude_control_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_attitude_control_t* attitude_control)
{
return mavlink_msg_attitude_control_pack(system_id, component_id, msg, attitude_control->target, attitude_control->roll, attitude_control->pitch, attitude_control->yaw, attitude_control->thrust, attitude_control->roll_manual, attitude_control->pitch_manual, attitude_control->yaw_manual, attitude_control->thrust_manual);
}
/**
* @brief Send a attitude_control message
* @param chan MAVLink channel to send the message
*
* @param target The system to be controlled
* @param roll roll
* @param pitch pitch
* @param yaw yaw
* @param thrust thrust
* @param roll_manual roll control enabled auto:0, manual:1
* @param pitch_manual pitch auto:0, manual:1
* @param yaw_manual yaw auto:0, manual:1
* @param thrust_manual thrust auto:0, manual:1
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_attitude_control_send(mavlink_channel_t chan, uint8_t target, float roll, float pitch, float yaw, float thrust, uint8_t roll_manual, uint8_t pitch_manual, uint8_t yaw_manual, uint8_t thrust_manual)
@ -195,6 +237,12 @@ static inline uint8_t mavlink_msg_attitude_control_get_thrust_manual(const mavli
return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[0];
}
/**
* @brief Decode a attitude_control message into a struct
*
* @param msg The message to decode
* @param attitude_control C-struct to decode the message contents into
*/
static inline void mavlink_msg_attitude_control_decode(const mavlink_message_t* msg, mavlink_attitude_control_t* attitude_control)
{
attitude_control->target = mavlink_msg_attitude_control_get_target(msg);

View File

@ -16,7 +16,10 @@ typedef struct __mavlink_aux_status_t
/**
* @brief Send a aux_status message
* @brief Pack a aux_status 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 load Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000
* @param i2c0_err_count Number of I2C errors since startup
@ -31,36 +34,69 @@ static inline uint16_t mavlink_msg_aux_status_pack(uint8_t system_id, uint8_t co
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_AUX_STATUS;
i += put_uint16_t_by_index(load, i, msg->payload); //Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000
i += put_uint16_t_by_index(i2c0_err_count, i, msg->payload); //Number of I2C errors since startup
i += put_uint16_t_by_index(i2c1_err_count, i, msg->payload); //Number of I2C errors since startup
i += put_uint16_t_by_index(spi0_err_count, i, msg->payload); //Number of I2C errors since startup
i += put_uint16_t_by_index(spi1_err_count, i, msg->payload); //Number of I2C errors since startup
i += put_uint16_t_by_index(uart_total_err_count, i, msg->payload); //Number of I2C errors since startup
i += put_uint16_t_by_index(load, i, msg->payload); // Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000
i += put_uint16_t_by_index(i2c0_err_count, i, msg->payload); // Number of I2C errors since startup
i += put_uint16_t_by_index(i2c1_err_count, i, msg->payload); // Number of I2C errors since startup
i += put_uint16_t_by_index(spi0_err_count, i, msg->payload); // Number of I2C errors since startup
i += put_uint16_t_by_index(spi1_err_count, i, msg->payload); // Number of I2C errors since startup
i += put_uint16_t_by_index(uart_total_err_count, i, msg->payload); // Number of I2C errors since startup
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a aux_status 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 load Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000
* @param i2c0_err_count Number of I2C errors since startup
* @param i2c1_err_count Number of I2C errors since startup
* @param spi0_err_count Number of I2C errors since startup
* @param spi1_err_count Number of I2C errors since startup
* @param uart_total_err_count Number of I2C errors since startup
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_aux_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint16_t load, uint16_t i2c0_err_count, uint16_t i2c1_err_count, uint16_t spi0_err_count, uint16_t spi1_err_count, uint16_t uart_total_err_count)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_AUX_STATUS;
i += put_uint16_t_by_index(load, i, msg->payload); //Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000
i += put_uint16_t_by_index(i2c0_err_count, i, msg->payload); //Number of I2C errors since startup
i += put_uint16_t_by_index(i2c1_err_count, i, msg->payload); //Number of I2C errors since startup
i += put_uint16_t_by_index(spi0_err_count, i, msg->payload); //Number of I2C errors since startup
i += put_uint16_t_by_index(spi1_err_count, i, msg->payload); //Number of I2C errors since startup
i += put_uint16_t_by_index(uart_total_err_count, i, msg->payload); //Number of I2C errors since startup
i += put_uint16_t_by_index(load, i, msg->payload); // Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000
i += put_uint16_t_by_index(i2c0_err_count, i, msg->payload); // Number of I2C errors since startup
i += put_uint16_t_by_index(i2c1_err_count, i, msg->payload); // Number of I2C errors since startup
i += put_uint16_t_by_index(spi0_err_count, i, msg->payload); // Number of I2C errors since startup
i += put_uint16_t_by_index(spi1_err_count, i, msg->payload); // Number of I2C errors since startup
i += put_uint16_t_by_index(uart_total_err_count, i, msg->payload); // Number of I2C errors since startup
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a aux_status 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 aux_status C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_aux_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_aux_status_t* aux_status)
{
return mavlink_msg_aux_status_pack(system_id, component_id, msg, aux_status->load, aux_status->i2c0_err_count, aux_status->i2c1_err_count, aux_status->spi0_err_count, aux_status->spi1_err_count, aux_status->uart_total_err_count);
}
/**
* @brief Send a aux_status message
* @param chan MAVLink channel to send the message
*
* @param load Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000
* @param i2c0_err_count Number of I2C errors since startup
* @param i2c1_err_count Number of I2C errors since startup
* @param spi0_err_count Number of I2C errors since startup
* @param spi1_err_count Number of I2C errors since startup
* @param uart_total_err_count Number of I2C errors since startup
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_aux_status_send(mavlink_channel_t chan, uint16_t load, uint16_t i2c0_err_count, uint16_t i2c1_err_count, uint16_t spi0_err_count, uint16_t spi1_err_count, uint16_t uart_total_err_count)
@ -151,6 +187,12 @@ static inline uint16_t mavlink_msg_aux_status_get_uart_total_err_count(const mav
return (uint16_t)r.s;
}
/**
* @brief Decode a aux_status message into a struct
*
* @param msg The message to decode
* @param aux_status C-struct to decode the message contents into
*/
static inline void mavlink_msg_aux_status_decode(const mavlink_message_t* msg, mavlink_aux_status_t* aux_status)
{
aux_status->load = mavlink_msg_aux_status_get_load(msg);

View File

@ -17,7 +17,10 @@ typedef struct __mavlink_control_status_t
/**
* @brief Send a control_status message
* @brief Pack a control_status 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 position_fix Position fix: 0: lost, 2: 2D position fix, 3: 3D position fix
* @param vision_fix Vision position fix: 0: lost, 1: 2D local position hold, 2: 2D global position fix, 3: 3D global position fix
@ -33,38 +36,73 @@ static inline uint16_t mavlink_msg_control_status_pack(uint8_t system_id, uint8_
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_CONTROL_STATUS;
i += put_uint8_t_by_index(position_fix, i, msg->payload); //Position fix: 0: lost, 2: 2D position fix, 3: 3D position fix
i += put_uint8_t_by_index(vision_fix, i, msg->payload); //Vision position fix: 0: lost, 1: 2D local position hold, 2: 2D global position fix, 3: 3D global position fix
i += put_uint8_t_by_index(gps_fix, i, msg->payload); //GPS position fix: 0: no reception, 1: Minimum 1 satellite, but no position fix, 2: 2D position fix, 3: 3D position fix
i += put_uint8_t_by_index(control_att, i, msg->payload); //0: Attitude control disabled, 1: enabled
i += put_uint8_t_by_index(control_pos_xy, i, msg->payload); //0: X, Y position control disabled, 1: enabled
i += put_uint8_t_by_index(control_pos_z, i, msg->payload); //0: Z position control disabled, 1: enabled
i += put_uint8_t_by_index(control_pos_yaw, i, msg->payload); //0: Yaw angle control disabled, 1: enabled
i += put_uint8_t_by_index(position_fix, i, msg->payload); // Position fix: 0: lost, 2: 2D position fix, 3: 3D position fix
i += put_uint8_t_by_index(vision_fix, i, msg->payload); // Vision position fix: 0: lost, 1: 2D local position hold, 2: 2D global position fix, 3: 3D global position fix
i += put_uint8_t_by_index(gps_fix, i, msg->payload); // GPS position fix: 0: no reception, 1: Minimum 1 satellite, but no position fix, 2: 2D position fix, 3: 3D position fix
i += put_uint8_t_by_index(control_att, i, msg->payload); // 0: Attitude control disabled, 1: enabled
i += put_uint8_t_by_index(control_pos_xy, i, msg->payload); // 0: X, Y position control disabled, 1: enabled
i += put_uint8_t_by_index(control_pos_z, i, msg->payload); // 0: Z position control disabled, 1: enabled
i += put_uint8_t_by_index(control_pos_yaw, i, msg->payload); // 0: Yaw angle control disabled, 1: enabled
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a control_status 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 position_fix Position fix: 0: lost, 2: 2D position fix, 3: 3D position fix
* @param vision_fix Vision position fix: 0: lost, 1: 2D local position hold, 2: 2D global position fix, 3: 3D global position fix
* @param gps_fix GPS position fix: 0: no reception, 1: Minimum 1 satellite, but no position fix, 2: 2D position fix, 3: 3D position fix
* @param control_att 0: Attitude control disabled, 1: enabled
* @param control_pos_xy 0: X, Y position control disabled, 1: enabled
* @param control_pos_z 0: Z position control disabled, 1: enabled
* @param control_pos_yaw 0: Yaw angle control disabled, 1: enabled
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_control_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t position_fix, uint8_t vision_fix, uint8_t gps_fix, uint8_t control_att, uint8_t control_pos_xy, uint8_t control_pos_z, uint8_t control_pos_yaw)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_CONTROL_STATUS;
i += put_uint8_t_by_index(position_fix, i, msg->payload); //Position fix: 0: lost, 2: 2D position fix, 3: 3D position fix
i += put_uint8_t_by_index(vision_fix, i, msg->payload); //Vision position fix: 0: lost, 1: 2D local position hold, 2: 2D global position fix, 3: 3D global position fix
i += put_uint8_t_by_index(gps_fix, i, msg->payload); //GPS position fix: 0: no reception, 1: Minimum 1 satellite, but no position fix, 2: 2D position fix, 3: 3D position fix
i += put_uint8_t_by_index(control_att, i, msg->payload); //0: Attitude control disabled, 1: enabled
i += put_uint8_t_by_index(control_pos_xy, i, msg->payload); //0: X, Y position control disabled, 1: enabled
i += put_uint8_t_by_index(control_pos_z, i, msg->payload); //0: Z position control disabled, 1: enabled
i += put_uint8_t_by_index(control_pos_yaw, i, msg->payload); //0: Yaw angle control disabled, 1: enabled
i += put_uint8_t_by_index(position_fix, i, msg->payload); // Position fix: 0: lost, 2: 2D position fix, 3: 3D position fix
i += put_uint8_t_by_index(vision_fix, i, msg->payload); // Vision position fix: 0: lost, 1: 2D local position hold, 2: 2D global position fix, 3: 3D global position fix
i += put_uint8_t_by_index(gps_fix, i, msg->payload); // GPS position fix: 0: no reception, 1: Minimum 1 satellite, but no position fix, 2: 2D position fix, 3: 3D position fix
i += put_uint8_t_by_index(control_att, i, msg->payload); // 0: Attitude control disabled, 1: enabled
i += put_uint8_t_by_index(control_pos_xy, i, msg->payload); // 0: X, Y position control disabled, 1: enabled
i += put_uint8_t_by_index(control_pos_z, i, msg->payload); // 0: Z position control disabled, 1: enabled
i += put_uint8_t_by_index(control_pos_yaw, i, msg->payload); // 0: Yaw angle control disabled, 1: enabled
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a control_status 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 control_status C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_control_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_control_status_t* control_status)
{
return mavlink_msg_control_status_pack(system_id, component_id, msg, control_status->position_fix, control_status->vision_fix, control_status->gps_fix, control_status->control_att, control_status->control_pos_xy, control_status->control_pos_z, control_status->control_pos_yaw);
}
/**
* @brief Send a control_status message
* @param chan MAVLink channel to send the message
*
* @param position_fix Position fix: 0: lost, 2: 2D position fix, 3: 3D position fix
* @param vision_fix Vision position fix: 0: lost, 1: 2D local position hold, 2: 2D global position fix, 3: 3D global position fix
* @param gps_fix GPS position fix: 0: no reception, 1: Minimum 1 satellite, but no position fix, 2: 2D position fix, 3: 3D position fix
* @param control_att 0: Attitude control disabled, 1: enabled
* @param control_pos_xy 0: X, Y position control disabled, 1: enabled
* @param control_pos_z 0: Z position control disabled, 1: enabled
* @param control_pos_yaw 0: Yaw angle control disabled, 1: enabled
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_control_status_send(mavlink_channel_t chan, uint8_t position_fix, uint8_t vision_fix, uint8_t gps_fix, uint8_t control_att, uint8_t control_pos_xy, uint8_t control_pos_z, uint8_t control_pos_yaw)
@ -147,6 +185,12 @@ static inline uint8_t mavlink_msg_control_status_get_control_pos_yaw(const mavli
return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[0];
}
/**
* @brief Decode a control_status message into a struct
*
* @param msg The message to decode
* @param control_status C-struct to decode the message contents into
*/
static inline void mavlink_msg_control_status_decode(const mavlink_message_t* msg, mavlink_control_status_t* control_status)
{
control_status->position_fix = mavlink_msg_control_status_get_position_fix(msg);

View File

@ -0,0 +1,174 @@
// MESSAGE DATA_TRANSMISSION_HANDSHAKE PACKING
#define MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE 170
typedef struct __mavlink_data_transmission_handshake_t
{
uint8_t type; ///< type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h)
uint32_t size; ///< total data size in bytes (set on ACK only)
uint8_t packets; ///< number of packets beeing sent (set on ACK only)
uint8_t payload; ///< payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only)
uint8_t jpg_quality; ///< JPEG quality out of [1,100]
} mavlink_data_transmission_handshake_t;
/**
* @brief Pack a data_transmission_handshake 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 type type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h)
* @param size total data size in bytes (set on ACK only)
* @param packets number of packets beeing sent (set on ACK only)
* @param payload payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only)
* @param jpg_quality JPEG quality out of [1,100]
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_data_transmission_handshake_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t type, uint32_t size, uint8_t packets, uint8_t payload, uint8_t jpg_quality)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE;
i += put_uint8_t_by_index(type, i, msg->payload); // type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h)
i += put_uint32_t_by_index(size, i, msg->payload); // total data size in bytes (set on ACK only)
i += put_uint8_t_by_index(packets, i, msg->payload); // number of packets beeing sent (set on ACK only)
i += put_uint8_t_by_index(payload, i, msg->payload); // payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only)
i += put_uint8_t_by_index(jpg_quality, i, msg->payload); // JPEG quality out of [1,100]
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a data_transmission_handshake 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 type type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h)
* @param size total data size in bytes (set on ACK only)
* @param packets number of packets beeing sent (set on ACK only)
* @param payload payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only)
* @param jpg_quality JPEG quality out of [1,100]
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_data_transmission_handshake_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t type, uint32_t size, uint8_t packets, uint8_t payload, uint8_t jpg_quality)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE;
i += put_uint8_t_by_index(type, i, msg->payload); // type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h)
i += put_uint32_t_by_index(size, i, msg->payload); // total data size in bytes (set on ACK only)
i += put_uint8_t_by_index(packets, i, msg->payload); // number of packets beeing sent (set on ACK only)
i += put_uint8_t_by_index(payload, i, msg->payload); // payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only)
i += put_uint8_t_by_index(jpg_quality, i, msg->payload); // JPEG quality out of [1,100]
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a data_transmission_handshake 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 data_transmission_handshake C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_data_transmission_handshake_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_data_transmission_handshake_t* data_transmission_handshake)
{
return mavlink_msg_data_transmission_handshake_pack(system_id, component_id, msg, data_transmission_handshake->type, data_transmission_handshake->size, data_transmission_handshake->packets, data_transmission_handshake->payload, data_transmission_handshake->jpg_quality);
}
/**
* @brief Send a data_transmission_handshake message
* @param chan MAVLink channel to send the message
*
* @param type type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h)
* @param size total data size in bytes (set on ACK only)
* @param packets number of packets beeing sent (set on ACK only)
* @param payload payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only)
* @param jpg_quality JPEG quality out of [1,100]
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_data_transmission_handshake_send(mavlink_channel_t chan, uint8_t type, uint32_t size, uint8_t packets, uint8_t payload, uint8_t jpg_quality)
{
mavlink_message_t msg;
mavlink_msg_data_transmission_handshake_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, type, size, packets, payload, jpg_quality);
mavlink_send_uart(chan, &msg);
}
#endif
// MESSAGE DATA_TRANSMISSION_HANDSHAKE UNPACKING
/**
* @brief Get field type from data_transmission_handshake message
*
* @return type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h)
*/
static inline uint8_t mavlink_msg_data_transmission_handshake_get_type(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload)[0];
}
/**
* @brief Get field size from data_transmission_handshake message
*
* @return total data size in bytes (set on ACK only)
*/
static inline uint32_t mavlink_msg_data_transmission_handshake_get_size(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(uint8_t))[0];
r.b[2] = (msg->payload+sizeof(uint8_t))[1];
r.b[1] = (msg->payload+sizeof(uint8_t))[2];
r.b[0] = (msg->payload+sizeof(uint8_t))[3];
return (uint32_t)r.i;
}
/**
* @brief Get field packets from data_transmission_handshake message
*
* @return number of packets beeing sent (set on ACK only)
*/
static inline uint8_t mavlink_msg_data_transmission_handshake_get_packets(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint32_t))[0];
}
/**
* @brief Get field payload from data_transmission_handshake message
*
* @return payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only)
*/
static inline uint8_t mavlink_msg_data_transmission_handshake_get_payload(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint8_t))[0];
}
/**
* @brief Get field jpg_quality from data_transmission_handshake message
*
* @return JPEG quality out of [1,100]
*/
static inline uint8_t mavlink_msg_data_transmission_handshake_get_jpg_quality(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint8_t)+sizeof(uint8_t))[0];
}
/**
* @brief Decode a data_transmission_handshake message into a struct
*
* @param msg The message to decode
* @param data_transmission_handshake C-struct to decode the message contents into
*/
static inline void mavlink_msg_data_transmission_handshake_decode(const mavlink_message_t* msg, mavlink_data_transmission_handshake_t* data_transmission_handshake)
{
data_transmission_handshake->type = mavlink_msg_data_transmission_handshake_get_type(msg);
data_transmission_handshake->size = mavlink_msg_data_transmission_handshake_get_size(msg);
data_transmission_handshake->packets = mavlink_msg_data_transmission_handshake_get_packets(msg);
data_transmission_handshake->payload = mavlink_msg_data_transmission_handshake_get_payload(msg);
data_transmission_handshake->jpg_quality = mavlink_msg_data_transmission_handshake_get_jpg_quality(msg);
}

View File

@ -0,0 +1,124 @@
// MESSAGE ENCAPSULATED_DATA PACKING
#define MAVLINK_MSG_ID_ENCAPSULATED_DATA 171
typedef struct __mavlink_encapsulated_data_t
{
uint16_t seqnr; ///< sequence number (starting with 0 on every transmission)
uint8_t data[253]; ///< image data bytes
} mavlink_encapsulated_data_t;
#define MAVLINK_MSG_ENCAPSULATED_DATA_FIELD_DATA_LEN 253
/**
* @brief Pack a encapsulated_data 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 seqnr sequence number (starting with 0 on every transmission)
* @param data image data bytes
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_encapsulated_data_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint16_t seqnr, const uint8_t* data)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_ENCAPSULATED_DATA;
i += put_uint16_t_by_index(seqnr, i, msg->payload); // sequence number (starting with 0 on every transmission)
i += put_array_by_index((const int8_t*)data, sizeof(uint8_t)*253, i, msg->payload); // image data bytes
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a encapsulated_data 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 seqnr sequence number (starting with 0 on every transmission)
* @param data image data bytes
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_encapsulated_data_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint16_t seqnr, const uint8_t* data)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_ENCAPSULATED_DATA;
i += put_uint16_t_by_index(seqnr, i, msg->payload); // sequence number (starting with 0 on every transmission)
i += put_array_by_index((const int8_t*)data, sizeof(uint8_t)*253, i, msg->payload); // image data bytes
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a encapsulated_data 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 encapsulated_data C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_encapsulated_data_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_encapsulated_data_t* encapsulated_data)
{
return mavlink_msg_encapsulated_data_pack(system_id, component_id, msg, encapsulated_data->seqnr, encapsulated_data->data);
}
/**
* @brief Send a encapsulated_data message
* @param chan MAVLink channel to send the message
*
* @param seqnr sequence number (starting with 0 on every transmission)
* @param data image data bytes
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_encapsulated_data_send(mavlink_channel_t chan, uint16_t seqnr, const uint8_t* data)
{
mavlink_message_t msg;
mavlink_msg_encapsulated_data_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, seqnr, data);
mavlink_send_uart(chan, &msg);
}
#endif
// MESSAGE ENCAPSULATED_DATA UNPACKING
/**
* @brief Get field seqnr from encapsulated_data message
*
* @return sequence number (starting with 0 on every transmission)
*/
static inline uint16_t mavlink_msg_encapsulated_data_get_seqnr(const mavlink_message_t* msg)
{
generic_16bit r;
r.b[1] = (msg->payload)[0];
r.b[0] = (msg->payload)[1];
return (uint16_t)r.s;
}
/**
* @brief Get field data from encapsulated_data message
*
* @return image data bytes
*/
static inline uint16_t mavlink_msg_encapsulated_data_get_data(const mavlink_message_t* msg, uint8_t* r_data)
{
memcpy(r_data, msg->payload+sizeof(uint16_t), sizeof(uint8_t)*253);
return sizeof(uint8_t)*253;
}
/**
* @brief Decode a encapsulated_data message into a struct
*
* @param msg The message to decode
* @param encapsulated_data C-struct to decode the message contents into
*/
static inline void mavlink_msg_encapsulated_data_decode(const mavlink_message_t* msg, mavlink_encapsulated_data_t* encapsulated_data)
{
encapsulated_data->seqnr = mavlink_msg_encapsulated_data_get_seqnr(msg);
mavlink_msg_encapsulated_data_get_data(msg, encapsulated_data->data);
}

View File

@ -0,0 +1,76 @@
// MESSAGE ENCAPSULATED_IMAGE PACKING
#define MAVLINK_MSG_ID_ENCAPSULATED_IMAGE 171
typedef struct __mavlink_encapsulated_image_t
{
uint8_t seqnr; ///< sequence number (starting with 0 on every transmission)
uint8_t data[254]; ///< image data bytes
} mavlink_encapsulated_image_t;
#define MAVLINK_MSG_ENCAPSULATED_IMAGE_FIELD_DATA_LEN 254
/**
* @brief Send a encapsulated_image message
*
* @param seqnr sequence number (starting with 0 on every transmission)
* @param data image data bytes
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_encapsulated_image_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t seqnr, const uint8_t* data)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_ENCAPSULATED_IMAGE;
i += put_uint8_t_by_index(seqnr, i, msg->payload); //sequence number (starting with 0 on every transmission)
i += put_array_by_index((int8_t*)data, sizeof(uint8_t)*254, i, msg->payload); //image data bytes
return mavlink_finalize_message(msg, system_id, component_id, i);
}
static inline uint16_t mavlink_msg_encapsulated_image_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_encapsulated_image_t* encapsulated_image)
{
return mavlink_msg_encapsulated_image_pack(system_id, component_id, msg, encapsulated_image->seqnr, encapsulated_image->data);
}
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_encapsulated_image_send(mavlink_channel_t chan, uint8_t seqnr, const uint8_t* data)
{
mavlink_message_t msg;
mavlink_msg_encapsulated_image_pack(mavlink_system.sysid, mavlink_system.compid, &msg, seqnr, data);
mavlink_send_uart(chan, &msg);
}
#endif
// MESSAGE ENCAPSULATED_IMAGE UNPACKING
/**
* @brief Get field seqnr from encapsulated_image message
*
* @return sequence number (starting with 0 on every transmission)
*/
static inline uint8_t mavlink_msg_encapsulated_image_get_seqnr(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload)[0];
}
/**
* @brief Get field data from encapsulated_image message
*
* @return image data bytes
*/
static inline uint16_t mavlink_msg_encapsulated_image_get_data(const mavlink_message_t* msg, uint8_t* r_data)
{
memcpy(r_data, msg->payload+sizeof(uint8_t), sizeof(uint8_t)*254);
return sizeof(uint8_t)*254;
}
static inline void mavlink_msg_encapsulated_image_decode(const mavlink_message_t* msg, mavlink_encapsulated_image_t* encapsulated_image)
{
encapsulated_image->seqnr = mavlink_msg_encapsulated_image_get_seqnr(msg);
mavlink_msg_encapsulated_image_get_data(msg, encapsulated_image->data);
}

View File

@ -0,0 +1,104 @@
// MESSAGE GET_IMAGE_ACK PACKING
#define MAVLINK_MSG_ID_GET_IMAGE_ACK 170
typedef struct __mavlink_get_image_ack_t
{
uint16_t size; ///< image size in bytes (65000 byte max)
uint8_t packets; ///< number of packets beeing sent
uint8_t payload; ///< image payload size (normally 254 byte)
uint8_t quality; ///< JPEG quality out of [0,100]
} mavlink_get_image_ack_t;
/**
* @brief Send a get_image_ack message
*
* @param size image size in bytes (65000 byte max)
* @param packets number of packets beeing sent
* @param payload image payload size (normally 254 byte)
* @param quality JPEG quality out of [0,100]
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_get_image_ack_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint16_t size, uint8_t packets, uint8_t payload, uint8_t quality)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_GET_IMAGE_ACK;
i += put_uint16_t_by_index(size, i, msg->payload); //image size in bytes (65000 byte max)
i += put_uint8_t_by_index(packets, i, msg->payload); //number of packets beeing sent
i += put_uint8_t_by_index(payload, i, msg->payload); //image payload size (normally 254 byte)
i += put_uint8_t_by_index(quality, i, msg->payload); //JPEG quality out of [0,100]
return mavlink_finalize_message(msg, system_id, component_id, i);
}
static inline uint16_t mavlink_msg_get_image_ack_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_get_image_ack_t* get_image_ack)
{
return mavlink_msg_get_image_ack_pack(system_id, component_id, msg, get_image_ack->size, get_image_ack->packets, get_image_ack->payload, get_image_ack->quality);
}
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_get_image_ack_send(mavlink_channel_t chan, uint16_t size, uint8_t packets, uint8_t payload, uint8_t quality)
{
mavlink_message_t msg;
mavlink_msg_get_image_ack_pack(mavlink_system.sysid, mavlink_system.compid, &msg, size, packets, payload, quality);
mavlink_send_uart(chan, &msg);
}
#endif
// MESSAGE GET_IMAGE_ACK UNPACKING
/**
* @brief Get field size from get_image_ack message
*
* @return image size in bytes (65000 byte max)
*/
static inline uint16_t mavlink_msg_get_image_ack_get_size(const mavlink_message_t* msg)
{
generic_16bit r;
r.b[1] = (msg->payload)[0];
r.b[0] = (msg->payload)[1];
return (uint16_t)r.s;
}
/**
* @brief Get field packets from get_image_ack message
*
* @return number of packets beeing sent
*/
static inline uint8_t mavlink_msg_get_image_ack_get_packets(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload+sizeof(uint16_t))[0];
}
/**
* @brief Get field payload from get_image_ack message
*
* @return image payload size (normally 254 byte)
*/
static inline uint8_t mavlink_msg_get_image_ack_get_payload(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload+sizeof(uint16_t)+sizeof(uint8_t))[0];
}
/**
* @brief Get field quality from get_image_ack message
*
* @return JPEG quality out of [0,100]
*/
static inline uint8_t mavlink_msg_get_image_ack_get_quality(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint8_t))[0];
}
static inline void mavlink_msg_get_image_ack_decode(const mavlink_message_t* msg, mavlink_get_image_ack_t* get_image_ack)
{
get_image_ack->size = mavlink_msg_get_image_ack_get_size(msg);
get_image_ack->packets = mavlink_msg_get_image_ack_get_packets(msg);
get_image_ack->payload = mavlink_msg_get_image_ack_get_payload(msg);
get_image_ack->quality = mavlink_msg_get_image_ack_get_quality(msg);
}

View File

@ -19,13 +19,21 @@ typedef struct __mavlink_image_available_t
float gain; ///< Camera gain
float roll; ///< Roll angle in rad
float pitch; ///< Pitch angle in rad
float yaw; ///< Yaw angle in rad
float local_z; ///< Local frame Z coordinate (height over ground)
float lat; ///< GPS X coordinate
float lon; ///< GPS Y coordinate
float alt; ///< Global frame altitude
} mavlink_image_available_t;
/**
* @brief Send a image_available message
* @brief Pack a image_available 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 cam_id Camera id
* @param cam_no Camera # (starts with 0)
@ -42,67 +50,143 @@ typedef struct __mavlink_image_available_t
* @param gain Camera gain
* @param roll Roll angle in rad
* @param pitch Pitch angle in rad
* @param yaw Yaw angle in rad
* @param local_z Local frame Z coordinate (height over ground)
* @param lat GPS X coordinate
* @param lon GPS Y coordinate
* @param alt Global frame altitude
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_image_available_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint64_t cam_id, uint8_t cam_no, uint64_t timestamp, uint64_t valid_until, uint32_t img_seq, uint32_t img_buf_index, uint16_t width, uint16_t height, uint16_t depth, uint8_t channels, uint32_t key, uint32_t exposure, float gain, float roll, float pitch)
static inline uint16_t mavlink_msg_image_available_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint64_t cam_id, uint8_t cam_no, uint64_t timestamp, uint64_t valid_until, uint32_t img_seq, uint32_t img_buf_index, uint16_t width, uint16_t height, uint16_t depth, uint8_t channels, uint32_t key, uint32_t exposure, float gain, float roll, float pitch, float yaw, float local_z, float lat, float lon, float alt)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_IMAGE_AVAILABLE;
i += put_uint64_t_by_index(cam_id, i, msg->payload); //Camera id
i += put_uint8_t_by_index(cam_no, i, msg->payload); //Camera # (starts with 0)
i += put_uint64_t_by_index(timestamp, i, msg->payload); //Timestamp
i += put_uint64_t_by_index(valid_until, i, msg->payload); //Until which timestamp this buffer will stay valid
i += put_uint32_t_by_index(img_seq, i, msg->payload); //The image sequence number
i += put_uint32_t_by_index(img_buf_index, i, msg->payload); //Position of the image in the buffer, starts with 0
i += put_uint16_t_by_index(width, i, msg->payload); //Image width
i += put_uint16_t_by_index(height, i, msg->payload); //Image height
i += put_uint16_t_by_index(depth, i, msg->payload); //Image depth
i += put_uint8_t_by_index(channels, i, msg->payload); //Image channels
i += put_uint32_t_by_index(key, i, msg->payload); //Shared memory area key
i += put_uint32_t_by_index(exposure, i, msg->payload); //Exposure time, in microseconds
i += put_float_by_index(gain, i, msg->payload); //Camera gain
i += put_float_by_index(roll, i, msg->payload); //Roll angle in rad
i += put_float_by_index(pitch, i, msg->payload); //Pitch angle in rad
i += put_uint64_t_by_index(cam_id, i, msg->payload); // Camera id
i += put_uint8_t_by_index(cam_no, i, msg->payload); // Camera # (starts with 0)
i += put_uint64_t_by_index(timestamp, i, msg->payload); // Timestamp
i += put_uint64_t_by_index(valid_until, i, msg->payload); // Until which timestamp this buffer will stay valid
i += put_uint32_t_by_index(img_seq, i, msg->payload); // The image sequence number
i += put_uint32_t_by_index(img_buf_index, i, msg->payload); // Position of the image in the buffer, starts with 0
i += put_uint16_t_by_index(width, i, msg->payload); // Image width
i += put_uint16_t_by_index(height, i, msg->payload); // Image height
i += put_uint16_t_by_index(depth, i, msg->payload); // Image depth
i += put_uint8_t_by_index(channels, i, msg->payload); // Image channels
i += put_uint32_t_by_index(key, i, msg->payload); // Shared memory area key
i += put_uint32_t_by_index(exposure, i, msg->payload); // Exposure time, in microseconds
i += put_float_by_index(gain, i, msg->payload); // Camera gain
i += put_float_by_index(roll, i, msg->payload); // Roll angle in rad
i += put_float_by_index(pitch, i, msg->payload); // Pitch angle in rad
i += put_float_by_index(yaw, i, msg->payload); // Yaw angle in rad
i += put_float_by_index(local_z, i, msg->payload); // Local frame Z coordinate (height over ground)
i += put_float_by_index(lat, i, msg->payload); // GPS X coordinate
i += put_float_by_index(lon, i, msg->payload); // GPS Y coordinate
i += put_float_by_index(alt, i, msg->payload); // Global frame altitude
return mavlink_finalize_message(msg, system_id, component_id, i);
}
static inline uint16_t mavlink_msg_image_available_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint64_t cam_id, uint8_t cam_no, uint64_t timestamp, uint64_t valid_until, uint32_t img_seq, uint32_t img_buf_index, uint16_t width, uint16_t height, uint16_t depth, uint8_t channels, uint32_t key, uint32_t exposure, float gain, float roll, float pitch)
/**
* @brief Pack a image_available 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 cam_id Camera id
* @param cam_no Camera # (starts with 0)
* @param timestamp Timestamp
* @param valid_until Until which timestamp this buffer will stay valid
* @param img_seq The image sequence number
* @param img_buf_index Position of the image in the buffer, starts with 0
* @param width Image width
* @param height Image height
* @param depth Image depth
* @param channels Image channels
* @param key Shared memory area key
* @param exposure Exposure time, in microseconds
* @param gain Camera gain
* @param roll Roll angle in rad
* @param pitch Pitch angle in rad
* @param yaw Yaw angle in rad
* @param local_z Local frame Z coordinate (height over ground)
* @param lat GPS X coordinate
* @param lon GPS Y coordinate
* @param alt Global frame altitude
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_image_available_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint64_t cam_id, uint8_t cam_no, uint64_t timestamp, uint64_t valid_until, uint32_t img_seq, uint32_t img_buf_index, uint16_t width, uint16_t height, uint16_t depth, uint8_t channels, uint32_t key, uint32_t exposure, float gain, float roll, float pitch, float yaw, float local_z, float lat, float lon, float alt)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_IMAGE_AVAILABLE;
i += put_uint64_t_by_index(cam_id, i, msg->payload); //Camera id
i += put_uint8_t_by_index(cam_no, i, msg->payload); //Camera # (starts with 0)
i += put_uint64_t_by_index(timestamp, i, msg->payload); //Timestamp
i += put_uint64_t_by_index(valid_until, i, msg->payload); //Until which timestamp this buffer will stay valid
i += put_uint32_t_by_index(img_seq, i, msg->payload); //The image sequence number
i += put_uint32_t_by_index(img_buf_index, i, msg->payload); //Position of the image in the buffer, starts with 0
i += put_uint16_t_by_index(width, i, msg->payload); //Image width
i += put_uint16_t_by_index(height, i, msg->payload); //Image height
i += put_uint16_t_by_index(depth, i, msg->payload); //Image depth
i += put_uint8_t_by_index(channels, i, msg->payload); //Image channels
i += put_uint32_t_by_index(key, i, msg->payload); //Shared memory area key
i += put_uint32_t_by_index(exposure, i, msg->payload); //Exposure time, in microseconds
i += put_float_by_index(gain, i, msg->payload); //Camera gain
i += put_float_by_index(roll, i, msg->payload); //Roll angle in rad
i += put_float_by_index(pitch, i, msg->payload); //Pitch angle in rad
i += put_uint64_t_by_index(cam_id, i, msg->payload); // Camera id
i += put_uint8_t_by_index(cam_no, i, msg->payload); // Camera # (starts with 0)
i += put_uint64_t_by_index(timestamp, i, msg->payload); // Timestamp
i += put_uint64_t_by_index(valid_until, i, msg->payload); // Until which timestamp this buffer will stay valid
i += put_uint32_t_by_index(img_seq, i, msg->payload); // The image sequence number
i += put_uint32_t_by_index(img_buf_index, i, msg->payload); // Position of the image in the buffer, starts with 0
i += put_uint16_t_by_index(width, i, msg->payload); // Image width
i += put_uint16_t_by_index(height, i, msg->payload); // Image height
i += put_uint16_t_by_index(depth, i, msg->payload); // Image depth
i += put_uint8_t_by_index(channels, i, msg->payload); // Image channels
i += put_uint32_t_by_index(key, i, msg->payload); // Shared memory area key
i += put_uint32_t_by_index(exposure, i, msg->payload); // Exposure time, in microseconds
i += put_float_by_index(gain, i, msg->payload); // Camera gain
i += put_float_by_index(roll, i, msg->payload); // Roll angle in rad
i += put_float_by_index(pitch, i, msg->payload); // Pitch angle in rad
i += put_float_by_index(yaw, i, msg->payload); // Yaw angle in rad
i += put_float_by_index(local_z, i, msg->payload); // Local frame Z coordinate (height over ground)
i += put_float_by_index(lat, i, msg->payload); // GPS X coordinate
i += put_float_by_index(lon, i, msg->payload); // GPS Y coordinate
i += put_float_by_index(alt, i, msg->payload); // Global frame altitude
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a image_available 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 image_available C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_image_available_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_image_available_t* image_available)
{
return mavlink_msg_image_available_pack(system_id, component_id, msg, image_available->cam_id, image_available->cam_no, image_available->timestamp, image_available->valid_until, image_available->img_seq, image_available->img_buf_index, image_available->width, image_available->height, image_available->depth, image_available->channels, image_available->key, image_available->exposure, image_available->gain, image_available->roll, image_available->pitch);
return mavlink_msg_image_available_pack(system_id, component_id, msg, image_available->cam_id, image_available->cam_no, image_available->timestamp, image_available->valid_until, image_available->img_seq, image_available->img_buf_index, image_available->width, image_available->height, image_available->depth, image_available->channels, image_available->key, image_available->exposure, image_available->gain, image_available->roll, image_available->pitch, image_available->yaw, image_available->local_z, image_available->lat, image_available->lon, image_available->alt);
}
/**
* @brief Send a image_available message
* @param chan MAVLink channel to send the message
*
* @param cam_id Camera id
* @param cam_no Camera # (starts with 0)
* @param timestamp Timestamp
* @param valid_until Until which timestamp this buffer will stay valid
* @param img_seq The image sequence number
* @param img_buf_index Position of the image in the buffer, starts with 0
* @param width Image width
* @param height Image height
* @param depth Image depth
* @param channels Image channels
* @param key Shared memory area key
* @param exposure Exposure time, in microseconds
* @param gain Camera gain
* @param roll Roll angle in rad
* @param pitch Pitch angle in rad
* @param yaw Yaw angle in rad
* @param local_z Local frame Z coordinate (height over ground)
* @param lat GPS X coordinate
* @param lon GPS Y coordinate
* @param alt Global frame altitude
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_image_available_send(mavlink_channel_t chan, uint64_t cam_id, uint8_t cam_no, uint64_t timestamp, uint64_t valid_until, uint32_t img_seq, uint32_t img_buf_index, uint16_t width, uint16_t height, uint16_t depth, uint8_t channels, uint32_t key, uint32_t exposure, float gain, float roll, float pitch)
static inline void mavlink_msg_image_available_send(mavlink_channel_t chan, uint64_t cam_id, uint8_t cam_no, uint64_t timestamp, uint64_t valid_until, uint32_t img_seq, uint32_t img_buf_index, uint16_t width, uint16_t height, uint16_t depth, uint8_t channels, uint32_t key, uint32_t exposure, float gain, float roll, float pitch, float yaw, float local_z, float lat, float lon, float alt)
{
mavlink_message_t msg;
mavlink_msg_image_available_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, cam_id, cam_no, timestamp, valid_until, img_seq, img_buf_index, width, height, depth, channels, key, exposure, gain, roll, pitch);
mavlink_msg_image_available_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, cam_id, cam_no, timestamp, valid_until, img_seq, img_buf_index, width, height, depth, channels, key, exposure, gain, roll, pitch, yaw, local_z, lat, lon, alt);
mavlink_send_uart(chan, &msg);
}
@ -330,6 +414,87 @@ static inline float mavlink_msg_image_available_get_pitch(const mavlink_message_
return (float)r.f;
}
/**
* @brief Get field yaw from image_available message
*
* @return Yaw angle in rad
*/
static inline float mavlink_msg_image_available_get_yaw(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float))[3];
return (float)r.f;
}
/**
* @brief Get field local_z from image_available message
*
* @return Local frame Z coordinate (height over ground)
*/
static inline float mavlink_msg_image_available_get_local_z(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
return (float)r.f;
}
/**
* @brief Get field lat from image_available message
*
* @return GPS X coordinate
*/
static inline float mavlink_msg_image_available_get_lat(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
return (float)r.f;
}
/**
* @brief Get field lon from image_available message
*
* @return GPS Y coordinate
*/
static inline float mavlink_msg_image_available_get_lon(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
return (float)r.f;
}
/**
* @brief Get field alt from image_available message
*
* @return Global frame altitude
*/
static inline float mavlink_msg_image_available_get_alt(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
return (float)r.f;
}
/**
* @brief Decode a image_available message into a struct
*
* @param msg The message to decode
* @param image_available C-struct to decode the message contents into
*/
static inline void mavlink_msg_image_available_decode(const mavlink_message_t* msg, mavlink_image_available_t* image_available)
{
image_available->cam_id = mavlink_msg_image_available_get_cam_id(msg);
@ -347,4 +512,9 @@ static inline void mavlink_msg_image_available_decode(const mavlink_message_t* m
image_available->gain = mavlink_msg_image_available_get_gain(msg);
image_available->roll = mavlink_msg_image_available_get_roll(msg);
image_available->pitch = mavlink_msg_image_available_get_pitch(msg);
image_available->yaw = mavlink_msg_image_available_get_yaw(msg);
image_available->local_z = mavlink_msg_image_available_get_local_z(msg);
image_available->lat = mavlink_msg_image_available_get_lat(msg);
image_available->lon = mavlink_msg_image_available_get_lon(msg);
image_available->alt = mavlink_msg_image_available_get_alt(msg);
}

View File

@ -11,7 +11,10 @@ typedef struct __mavlink_image_trigger_control_t
/**
* @brief Send a image_trigger_control message
* @brief Pack a image_trigger_control 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 enable 0 to disable, 1 to enable
* @return length of the message in bytes (excluding serial stream start sign)
@ -21,26 +24,49 @@ static inline uint16_t mavlink_msg_image_trigger_control_pack(uint8_t system_id,
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL;
i += put_uint8_t_by_index(enable, i, msg->payload); //0 to disable, 1 to enable
i += put_uint8_t_by_index(enable, i, msg->payload); // 0 to disable, 1 to enable
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a image_trigger_control 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 enable 0 to disable, 1 to enable
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_image_trigger_control_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t enable)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL;
i += put_uint8_t_by_index(enable, i, msg->payload); //0 to disable, 1 to enable
i += put_uint8_t_by_index(enable, i, msg->payload); // 0 to disable, 1 to enable
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a image_trigger_control 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 image_trigger_control C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_image_trigger_control_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_image_trigger_control_t* image_trigger_control)
{
return mavlink_msg_image_trigger_control_pack(system_id, component_id, msg, image_trigger_control->enable);
}
/**
* @brief Send a image_trigger_control message
* @param chan MAVLink channel to send the message
*
* @param enable 0 to disable, 1 to enable
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_image_trigger_control_send(mavlink_channel_t chan, uint8_t enable)
@ -63,6 +89,12 @@ static inline uint8_t mavlink_msg_image_trigger_control_get_enable(const mavlink
return (uint8_t)(msg->payload)[0];
}
/**
* @brief Decode a image_trigger_control message into a struct
*
* @param msg The message to decode
* @param image_trigger_control C-struct to decode the message contents into
*/
static inline void mavlink_msg_image_trigger_control_decode(const mavlink_message_t* msg, mavlink_image_trigger_control_t* image_trigger_control)
{
image_trigger_control->enable = mavlink_msg_image_trigger_control_get_enable(msg);

View File

@ -8,57 +8,119 @@ typedef struct __mavlink_image_triggered_t
uint32_t seq; ///< IMU seq
float roll; ///< Roll angle in rad
float pitch; ///< Pitch angle in rad
float yaw; ///< Yaw angle in rad
float local_z; ///< Local frame Z coordinate (height over ground)
float lat; ///< GPS X coordinate
float lon; ///< GPS Y coordinate
float alt; ///< Global frame altitude
} mavlink_image_triggered_t;
/**
* @brief Send a image_triggered message
* @brief Pack a image_triggered 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 timestamp Timestamp
* @param seq IMU seq
* @param roll Roll angle in rad
* @param pitch Pitch angle in rad
* @param yaw Yaw angle in rad
* @param local_z Local frame Z coordinate (height over ground)
* @param lat GPS X coordinate
* @param lon GPS Y coordinate
* @param alt Global frame altitude
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_image_triggered_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint64_t timestamp, uint32_t seq, float roll, float pitch)
static inline uint16_t mavlink_msg_image_triggered_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint64_t timestamp, uint32_t seq, float roll, float pitch, float yaw, float local_z, float lat, float lon, float alt)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_IMAGE_TRIGGERED;
i += put_uint64_t_by_index(timestamp, i, msg->payload); //Timestamp
i += put_uint32_t_by_index(seq, i, msg->payload); //IMU seq
i += put_float_by_index(roll, i, msg->payload); //Roll angle in rad
i += put_float_by_index(pitch, i, msg->payload); //Pitch angle in rad
i += put_uint64_t_by_index(timestamp, i, msg->payload); // Timestamp
i += put_uint32_t_by_index(seq, i, msg->payload); // IMU seq
i += put_float_by_index(roll, i, msg->payload); // Roll angle in rad
i += put_float_by_index(pitch, i, msg->payload); // Pitch angle in rad
i += put_float_by_index(yaw, i, msg->payload); // Yaw angle in rad
i += put_float_by_index(local_z, i, msg->payload); // Local frame Z coordinate (height over ground)
i += put_float_by_index(lat, i, msg->payload); // GPS X coordinate
i += put_float_by_index(lon, i, msg->payload); // GPS Y coordinate
i += put_float_by_index(alt, i, msg->payload); // Global frame altitude
return mavlink_finalize_message(msg, system_id, component_id, i);
}
static inline uint16_t mavlink_msg_image_triggered_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint64_t timestamp, uint32_t seq, float roll, float pitch)
/**
* @brief Pack a image_triggered 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 timestamp Timestamp
* @param seq IMU seq
* @param roll Roll angle in rad
* @param pitch Pitch angle in rad
* @param yaw Yaw angle in rad
* @param local_z Local frame Z coordinate (height over ground)
* @param lat GPS X coordinate
* @param lon GPS Y coordinate
* @param alt Global frame altitude
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_image_triggered_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint64_t timestamp, uint32_t seq, float roll, float pitch, float yaw, float local_z, float lat, float lon, float alt)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_IMAGE_TRIGGERED;
i += put_uint64_t_by_index(timestamp, i, msg->payload); //Timestamp
i += put_uint32_t_by_index(seq, i, msg->payload); //IMU seq
i += put_float_by_index(roll, i, msg->payload); //Roll angle in rad
i += put_float_by_index(pitch, i, msg->payload); //Pitch angle in rad
i += put_uint64_t_by_index(timestamp, i, msg->payload); // Timestamp
i += put_uint32_t_by_index(seq, i, msg->payload); // IMU seq
i += put_float_by_index(roll, i, msg->payload); // Roll angle in rad
i += put_float_by_index(pitch, i, msg->payload); // Pitch angle in rad
i += put_float_by_index(yaw, i, msg->payload); // Yaw angle in rad
i += put_float_by_index(local_z, i, msg->payload); // Local frame Z coordinate (height over ground)
i += put_float_by_index(lat, i, msg->payload); // GPS X coordinate
i += put_float_by_index(lon, i, msg->payload); // GPS Y coordinate
i += put_float_by_index(alt, i, msg->payload); // Global frame altitude
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a image_triggered 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 image_triggered C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_image_triggered_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_image_triggered_t* image_triggered)
{
return mavlink_msg_image_triggered_pack(system_id, component_id, msg, image_triggered->timestamp, image_triggered->seq, image_triggered->roll, image_triggered->pitch);
return mavlink_msg_image_triggered_pack(system_id, component_id, msg, image_triggered->timestamp, image_triggered->seq, image_triggered->roll, image_triggered->pitch, image_triggered->yaw, image_triggered->local_z, image_triggered->lat, image_triggered->lon, image_triggered->alt);
}
/**
* @brief Send a image_triggered message
* @param chan MAVLink channel to send the message
*
* @param timestamp Timestamp
* @param seq IMU seq
* @param roll Roll angle in rad
* @param pitch Pitch angle in rad
* @param yaw Yaw angle in rad
* @param local_z Local frame Z coordinate (height over ground)
* @param lat GPS X coordinate
* @param lon GPS Y coordinate
* @param alt Global frame altitude
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_image_triggered_send(mavlink_channel_t chan, uint64_t timestamp, uint32_t seq, float roll, float pitch)
static inline void mavlink_msg_image_triggered_send(mavlink_channel_t chan, uint64_t timestamp, uint32_t seq, float roll, float pitch, float yaw, float local_z, float lat, float lon, float alt)
{
mavlink_message_t msg;
mavlink_msg_image_triggered_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, timestamp, seq, roll, pitch);
mavlink_msg_image_triggered_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, timestamp, seq, roll, pitch, yaw, local_z, lat, lon, alt);
mavlink_send_uart(chan, &msg);
}
@ -129,10 +191,96 @@ static inline float mavlink_msg_image_triggered_get_pitch(const mavlink_message_
return (float)r.f;
}
/**
* @brief Get field yaw from image_triggered message
*
* @return Yaw angle in rad
*/
static inline float mavlink_msg_image_triggered_get_yaw(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float))[3];
return (float)r.f;
}
/**
* @brief Get field local_z from image_triggered message
*
* @return Local frame Z coordinate (height over ground)
*/
static inline float mavlink_msg_image_triggered_get_local_z(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float))[3];
return (float)r.f;
}
/**
* @brief Get field lat from image_triggered message
*
* @return GPS X coordinate
*/
static inline float mavlink_msg_image_triggered_get_lat(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
return (float)r.f;
}
/**
* @brief Get field lon from image_triggered message
*
* @return GPS Y coordinate
*/
static inline float mavlink_msg_image_triggered_get_lon(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
return (float)r.f;
}
/**
* @brief Get field alt from image_triggered message
*
* @return Global frame altitude
*/
static inline float mavlink_msg_image_triggered_get_alt(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
return (float)r.f;
}
/**
* @brief Decode a image_triggered message into a struct
*
* @param msg The message to decode
* @param image_triggered C-struct to decode the message contents into
*/
static inline void mavlink_msg_image_triggered_decode(const mavlink_message_t* msg, mavlink_image_triggered_t* image_triggered)
{
image_triggered->timestamp = mavlink_msg_image_triggered_get_timestamp(msg);
image_triggered->seq = mavlink_msg_image_triggered_get_seq(msg);
image_triggered->roll = mavlink_msg_image_triggered_get_roll(msg);
image_triggered->pitch = mavlink_msg_image_triggered_get_pitch(msg);
image_triggered->yaw = mavlink_msg_image_triggered_get_yaw(msg);
image_triggered->local_z = mavlink_msg_image_triggered_get_local_z(msg);
image_triggered->lat = mavlink_msg_image_triggered_get_lat(msg);
image_triggered->lon = mavlink_msg_image_triggered_get_lon(msg);
image_triggered->alt = mavlink_msg_image_triggered_get_alt(msg);
}

View File

@ -17,7 +17,10 @@ typedef struct __mavlink_marker_t
/**
* @brief Send a marker message
* @brief Pack a marker 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 id ID
* @param x x position
@ -33,38 +36,73 @@ static inline uint16_t mavlink_msg_marker_pack(uint8_t system_id, uint8_t compon
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_MARKER;
i += put_uint16_t_by_index(id, i, msg->payload); //ID
i += put_float_by_index(x, i, msg->payload); //x position
i += put_float_by_index(y, i, msg->payload); //y position
i += put_float_by_index(z, i, msg->payload); //z position
i += put_float_by_index(roll, i, msg->payload); //roll orientation
i += put_float_by_index(pitch, i, msg->payload); //pitch orientation
i += put_float_by_index(yaw, i, msg->payload); //yaw orientation
i += put_uint16_t_by_index(id, i, msg->payload); // ID
i += put_float_by_index(x, i, msg->payload); // x position
i += put_float_by_index(y, i, msg->payload); // y position
i += put_float_by_index(z, i, msg->payload); // z position
i += put_float_by_index(roll, i, msg->payload); // roll orientation
i += put_float_by_index(pitch, i, msg->payload); // pitch orientation
i += put_float_by_index(yaw, i, msg->payload); // yaw orientation
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a marker 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 id ID
* @param x x position
* @param y y position
* @param z z position
* @param roll roll orientation
* @param pitch pitch orientation
* @param yaw yaw orientation
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_marker_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint16_t id, float x, float y, float z, float roll, float pitch, float yaw)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_MARKER;
i += put_uint16_t_by_index(id, i, msg->payload); //ID
i += put_float_by_index(x, i, msg->payload); //x position
i += put_float_by_index(y, i, msg->payload); //y position
i += put_float_by_index(z, i, msg->payload); //z position
i += put_float_by_index(roll, i, msg->payload); //roll orientation
i += put_float_by_index(pitch, i, msg->payload); //pitch orientation
i += put_float_by_index(yaw, i, msg->payload); //yaw orientation
i += put_uint16_t_by_index(id, i, msg->payload); // ID
i += put_float_by_index(x, i, msg->payload); // x position
i += put_float_by_index(y, i, msg->payload); // y position
i += put_float_by_index(z, i, msg->payload); // z position
i += put_float_by_index(roll, i, msg->payload); // roll orientation
i += put_float_by_index(pitch, i, msg->payload); // pitch orientation
i += put_float_by_index(yaw, i, msg->payload); // yaw orientation
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a marker 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 marker C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_marker_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_marker_t* marker)
{
return mavlink_msg_marker_pack(system_id, component_id, msg, marker->id, marker->x, marker->y, marker->z, marker->roll, marker->pitch, marker->yaw);
}
/**
* @brief Send a marker message
* @param chan MAVLink channel to send the message
*
* @param id ID
* @param x x position
* @param y y position
* @param z z position
* @param roll roll orientation
* @param pitch pitch orientation
* @param yaw yaw orientation
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_marker_send(mavlink_channel_t chan, uint16_t id, float x, float y, float z, float roll, float pitch, float yaw)
@ -180,6 +218,12 @@ static inline float mavlink_msg_marker_get_yaw(const mavlink_message_t* msg)
return (float)r.f;
}
/**
* @brief Decode a marker message into a struct
*
* @param msg The message to decode
* @param marker C-struct to decode the message contents into
*/
static inline void mavlink_msg_marker_decode(const mavlink_message_t* msg, mavlink_marker_t* marker)
{
marker->id = mavlink_msg_marker_get_id(msg);

View File

@ -15,7 +15,10 @@ typedef struct __mavlink_pattern_detected_t
/**
* @brief Send a pattern_detected message
* @brief Pack a pattern_detected 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 type 0: Pattern, 1: Letter
* @param confidence Confidence of detection
@ -28,32 +31,61 @@ static inline uint16_t mavlink_msg_pattern_detected_pack(uint8_t system_id, uint
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_PATTERN_DETECTED;
i += put_uint8_t_by_index(type, i, msg->payload); //0: Pattern, 1: Letter
i += put_float_by_index(confidence, i, msg->payload); //Confidence of detection
i += put_array_by_index(file, 100, i, msg->payload); //Pattern file name
i += put_uint8_t_by_index(detected, i, msg->payload); //Accepted as true detection, 0 no, 1 yes
i += put_uint8_t_by_index(type, i, msg->payload); // 0: Pattern, 1: Letter
i += put_float_by_index(confidence, i, msg->payload); // Confidence of detection
i += put_array_by_index(file, 100, i, msg->payload); // Pattern file name
i += put_uint8_t_by_index(detected, i, msg->payload); // Accepted as true detection, 0 no, 1 yes
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a pattern_detected 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 type 0: Pattern, 1: Letter
* @param confidence Confidence of detection
* @param file Pattern file name
* @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 int8_t* file, uint8_t detected)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_PATTERN_DETECTED;
i += put_uint8_t_by_index(type, i, msg->payload); //0: Pattern, 1: Letter
i += put_float_by_index(confidence, i, msg->payload); //Confidence of detection
i += put_array_by_index(file, 100, i, msg->payload); //Pattern file name
i += put_uint8_t_by_index(detected, i, msg->payload); //Accepted as true detection, 0 no, 1 yes
i += put_uint8_t_by_index(type, i, msg->payload); // 0: Pattern, 1: Letter
i += put_float_by_index(confidence, i, msg->payload); // Confidence of detection
i += put_array_by_index(file, 100, i, msg->payload); // Pattern file name
i += put_uint8_t_by_index(detected, i, msg->payload); // Accepted as true detection, 0 no, 1 yes
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a pattern_detected 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 pattern_detected C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_pattern_detected_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_pattern_detected_t* pattern_detected)
{
return mavlink_msg_pattern_detected_pack(system_id, component_id, msg, pattern_detected->type, pattern_detected->confidence, pattern_detected->file, pattern_detected->detected);
}
/**
* @brief Send a pattern_detected message
* @param chan MAVLink channel to send the message
*
* @param type 0: Pattern, 1: Letter
* @param confidence Confidence of detection
* @param file Pattern file name
* @param detected Accepted as true detection, 0 no, 1 yes
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_pattern_detected_send(mavlink_channel_t chan, uint8_t type, float confidence, const int8_t* file, uint8_t detected)
@ -113,6 +145,12 @@ static inline uint8_t mavlink_msg_pattern_detected_get_detected(const mavlink_me
return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(float)+100)[0];
}
/**
* @brief Decode a pattern_detected message into a struct
*
* @param msg The message to decode
* @param pattern_detected C-struct to decode the message contents into
*/
static inline void mavlink_msg_pattern_detected_decode(const mavlink_message_t* msg, mavlink_pattern_detected_t* pattern_detected)
{
pattern_detected->type = mavlink_msg_pattern_detected_get_type(msg);

View File

@ -19,7 +19,10 @@ typedef struct __mavlink_point_of_interest_t
/**
* @brief Send a point_of_interest message
* @brief Pack a point_of_interest 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 type 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug
* @param color 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta
@ -36,40 +39,77 @@ static inline uint16_t mavlink_msg_point_of_interest_pack(uint8_t system_id, uin
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_POINT_OF_INTEREST;
i += put_uint8_t_by_index(type, i, msg->payload); //0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug
i += put_uint8_t_by_index(color, i, msg->payload); //0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta
i += put_uint8_t_by_index(coordinate_system, i, msg->payload); //0: global, 1:local
i += put_uint16_t_by_index(timeout, i, msg->payload); //0: no timeout, >1: timeout in seconds
i += put_float_by_index(x, i, msg->payload); //X Position
i += put_float_by_index(y, i, msg->payload); //Y Position
i += put_float_by_index(z, i, msg->payload); //Z Position
i += put_array_by_index(name, 25, i, msg->payload); //POI name
i += put_uint8_t_by_index(type, i, msg->payload); // 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug
i += put_uint8_t_by_index(color, i, msg->payload); // 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta
i += put_uint8_t_by_index(coordinate_system, i, msg->payload); // 0: global, 1:local
i += put_uint16_t_by_index(timeout, i, msg->payload); // 0: no timeout, >1: timeout in seconds
i += put_float_by_index(x, i, msg->payload); // X Position
i += put_float_by_index(y, i, msg->payload); // Y Position
i += put_float_by_index(z, i, msg->payload); // Z Position
i += put_array_by_index(name, 25, i, msg->payload); // POI name
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a point_of_interest 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 type 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug
* @param color 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta
* @param coordinate_system 0: global, 1:local
* @param timeout 0: no timeout, >1: timeout in seconds
* @param x X Position
* @param y Y Position
* @param z Z Position
* @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 int8_t* name)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_POINT_OF_INTEREST;
i += put_uint8_t_by_index(type, i, msg->payload); //0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug
i += put_uint8_t_by_index(color, i, msg->payload); //0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta
i += put_uint8_t_by_index(coordinate_system, i, msg->payload); //0: global, 1:local
i += put_uint16_t_by_index(timeout, i, msg->payload); //0: no timeout, >1: timeout in seconds
i += put_float_by_index(x, i, msg->payload); //X Position
i += put_float_by_index(y, i, msg->payload); //Y Position
i += put_float_by_index(z, i, msg->payload); //Z Position
i += put_array_by_index(name, 25, i, msg->payload); //POI name
i += put_uint8_t_by_index(type, i, msg->payload); // 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug
i += put_uint8_t_by_index(color, i, msg->payload); // 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta
i += put_uint8_t_by_index(coordinate_system, i, msg->payload); // 0: global, 1:local
i += put_uint16_t_by_index(timeout, i, msg->payload); // 0: no timeout, >1: timeout in seconds
i += put_float_by_index(x, i, msg->payload); // X Position
i += put_float_by_index(y, i, msg->payload); // Y Position
i += put_float_by_index(z, i, msg->payload); // Z Position
i += put_array_by_index(name, 25, i, msg->payload); // POI name
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a point_of_interest 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 point_of_interest C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_point_of_interest_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_point_of_interest_t* point_of_interest)
{
return mavlink_msg_point_of_interest_pack(system_id, component_id, msg, point_of_interest->type, point_of_interest->color, point_of_interest->coordinate_system, point_of_interest->timeout, point_of_interest->x, point_of_interest->y, point_of_interest->z, point_of_interest->name);
}
/**
* @brief Send a point_of_interest message
* @param chan MAVLink channel to send the message
*
* @param type 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug
* @param color 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta
* @param coordinate_system 0: global, 1:local
* @param timeout 0: no timeout, >1: timeout in seconds
* @param x X Position
* @param y Y Position
* @param z Z Position
* @param name POI name
*/
#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 int8_t* name)
@ -182,6 +222,12 @@ static inline uint16_t mavlink_msg_point_of_interest_get_name(const mavlink_mess
return 25;
}
/**
* @brief Decode a point_of_interest message into a struct
*
* @param msg The message to decode
* @param point_of_interest C-struct to decode the message contents into
*/
static inline void mavlink_msg_point_of_interest_decode(const mavlink_message_t* msg, mavlink_point_of_interest_t* point_of_interest)
{
point_of_interest->type = mavlink_msg_point_of_interest_get_type(msg);

View File

@ -22,7 +22,10 @@ typedef struct __mavlink_point_of_interest_connection_t
/**
* @brief Send a point_of_interest_connection message
* @brief Pack a point_of_interest_connection 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 type 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug
* @param color 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta
@ -42,46 +45,89 @@ static inline uint16_t mavlink_msg_point_of_interest_connection_pack(uint8_t sys
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION;
i += put_uint8_t_by_index(type, i, msg->payload); //0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug
i += put_uint8_t_by_index(color, i, msg->payload); //0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta
i += put_uint8_t_by_index(coordinate_system, i, msg->payload); //0: global, 1:local
i += put_uint16_t_by_index(timeout, i, msg->payload); //0: no timeout, >1: timeout in seconds
i += put_float_by_index(xp1, i, msg->payload); //X1 Position
i += put_float_by_index(yp1, i, msg->payload); //Y1 Position
i += put_float_by_index(zp1, i, msg->payload); //Z1 Position
i += put_float_by_index(xp2, i, msg->payload); //X2 Position
i += put_float_by_index(yp2, i, msg->payload); //Y2 Position
i += put_float_by_index(zp2, i, msg->payload); //Z2 Position
i += put_array_by_index(name, 25, i, msg->payload); //POI connection name
i += put_uint8_t_by_index(type, i, msg->payload); // 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug
i += put_uint8_t_by_index(color, i, msg->payload); // 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta
i += put_uint8_t_by_index(coordinate_system, i, msg->payload); // 0: global, 1:local
i += put_uint16_t_by_index(timeout, i, msg->payload); // 0: no timeout, >1: timeout in seconds
i += put_float_by_index(xp1, i, msg->payload); // X1 Position
i += put_float_by_index(yp1, i, msg->payload); // Y1 Position
i += put_float_by_index(zp1, i, msg->payload); // Z1 Position
i += put_float_by_index(xp2, i, msg->payload); // X2 Position
i += put_float_by_index(yp2, i, msg->payload); // Y2 Position
i += put_float_by_index(zp2, i, msg->payload); // Z2 Position
i += put_array_by_index(name, 25, i, msg->payload); // POI connection name
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a point_of_interest_connection 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 type 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug
* @param color 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta
* @param coordinate_system 0: global, 1:local
* @param timeout 0: no timeout, >1: timeout in seconds
* @param xp1 X1 Position
* @param yp1 Y1 Position
* @param zp1 Z1 Position
* @param xp2 X2 Position
* @param yp2 Y2 Position
* @param zp2 Z2 Position
* @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 int8_t* name)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION;
i += put_uint8_t_by_index(type, i, msg->payload); //0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug
i += put_uint8_t_by_index(color, i, msg->payload); //0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta
i += put_uint8_t_by_index(coordinate_system, i, msg->payload); //0: global, 1:local
i += put_uint16_t_by_index(timeout, i, msg->payload); //0: no timeout, >1: timeout in seconds
i += put_float_by_index(xp1, i, msg->payload); //X1 Position
i += put_float_by_index(yp1, i, msg->payload); //Y1 Position
i += put_float_by_index(zp1, i, msg->payload); //Z1 Position
i += put_float_by_index(xp2, i, msg->payload); //X2 Position
i += put_float_by_index(yp2, i, msg->payload); //Y2 Position
i += put_float_by_index(zp2, i, msg->payload); //Z2 Position
i += put_array_by_index(name, 25, i, msg->payload); //POI connection name
i += put_uint8_t_by_index(type, i, msg->payload); // 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug
i += put_uint8_t_by_index(color, i, msg->payload); // 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta
i += put_uint8_t_by_index(coordinate_system, i, msg->payload); // 0: global, 1:local
i += put_uint16_t_by_index(timeout, i, msg->payload); // 0: no timeout, >1: timeout in seconds
i += put_float_by_index(xp1, i, msg->payload); // X1 Position
i += put_float_by_index(yp1, i, msg->payload); // Y1 Position
i += put_float_by_index(zp1, i, msg->payload); // Z1 Position
i += put_float_by_index(xp2, i, msg->payload); // X2 Position
i += put_float_by_index(yp2, i, msg->payload); // Y2 Position
i += put_float_by_index(zp2, i, msg->payload); // Z2 Position
i += put_array_by_index(name, 25, i, msg->payload); // POI connection name
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a point_of_interest_connection 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 point_of_interest_connection C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_point_of_interest_connection_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_point_of_interest_connection_t* point_of_interest_connection)
{
return mavlink_msg_point_of_interest_connection_pack(system_id, component_id, msg, point_of_interest_connection->type, point_of_interest_connection->color, point_of_interest_connection->coordinate_system, point_of_interest_connection->timeout, point_of_interest_connection->xp1, point_of_interest_connection->yp1, point_of_interest_connection->zp1, point_of_interest_connection->xp2, point_of_interest_connection->yp2, point_of_interest_connection->zp2, point_of_interest_connection->name);
}
/**
* @brief Send a point_of_interest_connection message
* @param chan MAVLink channel to send the message
*
* @param type 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug
* @param color 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta
* @param coordinate_system 0: global, 1:local
* @param timeout 0: no timeout, >1: timeout in seconds
* @param xp1 X1 Position
* @param yp1 Y1 Position
* @param zp1 Z1 Position
* @param xp2 X2 Position
* @param yp2 Y2 Position
* @param zp2 Z2 Position
* @param name POI connection name
*/
#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 int8_t* name)
@ -239,6 +285,12 @@ static inline uint16_t mavlink_msg_point_of_interest_connection_get_name(const m
return 25;
}
/**
* @brief Decode a point_of_interest_connection message into a struct
*
* @param msg The message to decode
* @param point_of_interest_connection C-struct to decode the message contents into
*/
static inline void mavlink_msg_point_of_interest_connection_decode(const mavlink_message_t* msg, mavlink_point_of_interest_connection_t* point_of_interest_connection)
{
point_of_interest_connection->type = mavlink_msg_point_of_interest_connection_get_type(msg);

View File

@ -16,7 +16,10 @@ typedef struct __mavlink_position_control_offset_set_t
/**
* @brief Send a position_control_offset_set message
* @brief Pack a position_control_offset_set 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 target_system System ID
* @param target_component Component ID
@ -31,36 +34,69 @@ static inline uint16_t mavlink_msg_position_control_offset_set_pack(uint8_t syst
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_POSITION_CONTROL_OFFSET_SET;
i += put_uint8_t_by_index(target_system, i, msg->payload); //System ID
i += put_uint8_t_by_index(target_component, i, msg->payload); //Component ID
i += put_float_by_index(x, i, msg->payload); //x position offset
i += put_float_by_index(y, i, msg->payload); //y position offset
i += put_float_by_index(z, i, msg->payload); //z position offset
i += put_float_by_index(yaw, i, msg->payload); //yaw orientation offset in radians, 0 = NORTH
i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID
i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID
i += put_float_by_index(x, i, msg->payload); // x position offset
i += put_float_by_index(y, i, msg->payload); // y position offset
i += put_float_by_index(z, i, msg->payload); // z position offset
i += put_float_by_index(yaw, i, msg->payload); // yaw orientation offset in radians, 0 = NORTH
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a position_control_offset_set 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 target_system System ID
* @param target_component Component ID
* @param x x position offset
* @param y y position offset
* @param z z position offset
* @param yaw yaw orientation offset in radians, 0 = NORTH
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_position_control_offset_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, float x, float y, float z, float yaw)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_POSITION_CONTROL_OFFSET_SET;
i += put_uint8_t_by_index(target_system, i, msg->payload); //System ID
i += put_uint8_t_by_index(target_component, i, msg->payload); //Component ID
i += put_float_by_index(x, i, msg->payload); //x position offset
i += put_float_by_index(y, i, msg->payload); //y position offset
i += put_float_by_index(z, i, msg->payload); //z position offset
i += put_float_by_index(yaw, i, msg->payload); //yaw orientation offset in radians, 0 = NORTH
i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID
i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID
i += put_float_by_index(x, i, msg->payload); // x position offset
i += put_float_by_index(y, i, msg->payload); // y position offset
i += put_float_by_index(z, i, msg->payload); // z position offset
i += put_float_by_index(yaw, i, msg->payload); // yaw orientation offset in radians, 0 = NORTH
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a position_control_offset_set 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 position_control_offset_set C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_position_control_offset_set_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_position_control_offset_set_t* position_control_offset_set)
{
return mavlink_msg_position_control_offset_set_pack(system_id, component_id, msg, position_control_offset_set->target_system, position_control_offset_set->target_component, position_control_offset_set->x, position_control_offset_set->y, position_control_offset_set->z, position_control_offset_set->yaw);
}
/**
* @brief Send a position_control_offset_set message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID
* @param target_component Component ID
* @param x x position offset
* @param y y position offset
* @param z z position offset
* @param yaw yaw orientation offset in radians, 0 = NORTH
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_position_control_offset_set_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, float x, float y, float z, float yaw)
@ -153,6 +189,12 @@ static inline float mavlink_msg_position_control_offset_set_get_yaw(const mavlin
return (float)r.f;
}
/**
* @brief Decode a position_control_offset_set message into a struct
*
* @param msg The message to decode
* @param position_control_offset_set C-struct to decode the message contents into
*/
static inline void mavlink_msg_position_control_offset_set_decode(const mavlink_message_t* msg, mavlink_position_control_offset_set_t* position_control_offset_set)
{
position_control_offset_set->target_system = mavlink_msg_position_control_offset_set_get_target_system(msg);

View File

@ -15,7 +15,10 @@ typedef struct __mavlink_position_control_setpoint_t
/**
* @brief Send a position_control_setpoint message
* @brief Pack a position_control_setpoint 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 id ID of waypoint, 0 for plain position
* @param x x position
@ -29,34 +32,65 @@ static inline uint16_t mavlink_msg_position_control_setpoint_pack(uint8_t system
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT;
i += put_uint16_t_by_index(id, i, msg->payload); //ID of waypoint, 0 for plain position
i += put_float_by_index(x, i, msg->payload); //x position
i += put_float_by_index(y, i, msg->payload); //y position
i += put_float_by_index(z, i, msg->payload); //z position
i += put_float_by_index(yaw, i, msg->payload); //yaw orientation in radians, 0 = NORTH
i += put_uint16_t_by_index(id, i, msg->payload); // ID of waypoint, 0 for plain position
i += put_float_by_index(x, i, msg->payload); // x position
i += put_float_by_index(y, i, msg->payload); // y position
i += put_float_by_index(z, i, msg->payload); // z position
i += put_float_by_index(yaw, i, msg->payload); // yaw orientation in radians, 0 = NORTH
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a position_control_setpoint 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 id ID of waypoint, 0 for plain position
* @param x x position
* @param y y position
* @param z z position
* @param yaw yaw orientation in radians, 0 = NORTH
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_position_control_setpoint_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint16_t id, float x, float y, float z, float yaw)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT;
i += put_uint16_t_by_index(id, i, msg->payload); //ID of waypoint, 0 for plain position
i += put_float_by_index(x, i, msg->payload); //x position
i += put_float_by_index(y, i, msg->payload); //y position
i += put_float_by_index(z, i, msg->payload); //z position
i += put_float_by_index(yaw, i, msg->payload); //yaw orientation in radians, 0 = NORTH
i += put_uint16_t_by_index(id, i, msg->payload); // ID of waypoint, 0 for plain position
i += put_float_by_index(x, i, msg->payload); // x position
i += put_float_by_index(y, i, msg->payload); // y position
i += put_float_by_index(z, i, msg->payload); // z position
i += put_float_by_index(yaw, i, msg->payload); // yaw orientation in radians, 0 = NORTH
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a position_control_setpoint 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 position_control_setpoint C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_position_control_setpoint_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_position_control_setpoint_t* position_control_setpoint)
{
return mavlink_msg_position_control_setpoint_pack(system_id, component_id, msg, position_control_setpoint->id, position_control_setpoint->x, position_control_setpoint->y, position_control_setpoint->z, position_control_setpoint->yaw);
}
/**
* @brief Send a position_control_setpoint message
* @param chan MAVLink channel to send the message
*
* @param id ID of waypoint, 0 for plain position
* @param x x position
* @param y y position
* @param z z position
* @param yaw yaw orientation in radians, 0 = NORTH
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_position_control_setpoint_send(mavlink_channel_t chan, uint16_t id, float x, float y, float z, float yaw)
@ -142,6 +176,12 @@ static inline float mavlink_msg_position_control_setpoint_get_yaw(const mavlink_
return (float)r.f;
}
/**
* @brief Decode a position_control_setpoint message into a struct
*
* @param msg The message to decode
* @param position_control_setpoint C-struct to decode the message contents into
*/
static inline void mavlink_msg_position_control_setpoint_decode(const mavlink_message_t* msg, mavlink_position_control_setpoint_t* position_control_setpoint)
{
position_control_setpoint->id = mavlink_msg_position_control_setpoint_get_id(msg);

View File

@ -17,7 +17,10 @@ typedef struct __mavlink_position_control_setpoint_set_t
/**
* @brief Send a position_control_setpoint_set message
* @brief Pack a position_control_setpoint_set 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 target_system System ID
* @param target_component Component ID
@ -33,38 +36,73 @@ static inline uint16_t mavlink_msg_position_control_setpoint_set_pack(uint8_t sy
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT_SET;
i += put_uint8_t_by_index(target_system, i, msg->payload); //System ID
i += put_uint8_t_by_index(target_component, i, msg->payload); //Component ID
i += put_uint16_t_by_index(id, i, msg->payload); //ID of waypoint, 0 for plain position
i += put_float_by_index(x, i, msg->payload); //x position
i += put_float_by_index(y, i, msg->payload); //y position
i += put_float_by_index(z, i, msg->payload); //z position
i += put_float_by_index(yaw, i, msg->payload); //yaw orientation in radians, 0 = NORTH
i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID
i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID
i += put_uint16_t_by_index(id, i, msg->payload); // ID of waypoint, 0 for plain position
i += put_float_by_index(x, i, msg->payload); // x position
i += put_float_by_index(y, i, msg->payload); // y position
i += put_float_by_index(z, i, msg->payload); // z position
i += put_float_by_index(yaw, i, msg->payload); // yaw orientation in radians, 0 = NORTH
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a position_control_setpoint_set 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 target_system System ID
* @param target_component Component ID
* @param id ID of waypoint, 0 for plain position
* @param x x position
* @param y y position
* @param z z position
* @param yaw yaw orientation in radians, 0 = NORTH
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_position_control_setpoint_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, uint16_t id, float x, float y, float z, float yaw)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT_SET;
i += put_uint8_t_by_index(target_system, i, msg->payload); //System ID
i += put_uint8_t_by_index(target_component, i, msg->payload); //Component ID
i += put_uint16_t_by_index(id, i, msg->payload); //ID of waypoint, 0 for plain position
i += put_float_by_index(x, i, msg->payload); //x position
i += put_float_by_index(y, i, msg->payload); //y position
i += put_float_by_index(z, i, msg->payload); //z position
i += put_float_by_index(yaw, i, msg->payload); //yaw orientation in radians, 0 = NORTH
i += put_uint8_t_by_index(target_system, i, msg->payload); // System ID
i += put_uint8_t_by_index(target_component, i, msg->payload); // Component ID
i += put_uint16_t_by_index(id, i, msg->payload); // ID of waypoint, 0 for plain position
i += put_float_by_index(x, i, msg->payload); // x position
i += put_float_by_index(y, i, msg->payload); // y position
i += put_float_by_index(z, i, msg->payload); // z position
i += put_float_by_index(yaw, i, msg->payload); // yaw orientation in radians, 0 = NORTH
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a position_control_setpoint_set 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 position_control_setpoint_set C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_position_control_setpoint_set_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_position_control_setpoint_set_t* position_control_setpoint_set)
{
return mavlink_msg_position_control_setpoint_set_pack(system_id, component_id, msg, position_control_setpoint_set->target_system, position_control_setpoint_set->target_component, position_control_setpoint_set->id, position_control_setpoint_set->x, position_control_setpoint_set->y, position_control_setpoint_set->z, position_control_setpoint_set->yaw);
}
/**
* @brief Send a position_control_setpoint_set message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID
* @param target_component Component ID
* @param id ID of waypoint, 0 for plain position
* @param x x position
* @param y y position
* @param z z position
* @param yaw yaw orientation in radians, 0 = NORTH
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_position_control_setpoint_set_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t id, float x, float y, float z, float yaw)
@ -170,6 +208,12 @@ static inline float mavlink_msg_position_control_setpoint_set_get_yaw(const mavl
return (float)r.f;
}
/**
* @brief Decode a position_control_setpoint_set message into a struct
*
* @param msg The message to decode
* @param position_control_setpoint_set C-struct to decode the message contents into
*/
static inline void mavlink_msg_position_control_setpoint_set_decode(const mavlink_message_t* msg, mavlink_position_control_setpoint_set_t* position_control_setpoint_set)
{
position_control_setpoint_set->target_system = mavlink_msg_position_control_setpoint_set_get_target_system(msg);

View File

@ -17,7 +17,10 @@ typedef struct __mavlink_raw_aux_t
/**
* @brief Send a raw_aux message
* @brief Pack a raw_aux 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 adc1 ADC1 (J405 ADC3, LPC2148 AD0.6)
* @param adc2 ADC2 (J405 ADC5, LPC2148 AD0.2)
@ -33,38 +36,73 @@ static inline uint16_t mavlink_msg_raw_aux_pack(uint8_t system_id, uint8_t compo
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_RAW_AUX;
i += put_uint16_t_by_index(adc1, i, msg->payload); //ADC1 (J405 ADC3, LPC2148 AD0.6)
i += put_uint16_t_by_index(adc2, i, msg->payload); //ADC2 (J405 ADC5, LPC2148 AD0.2)
i += put_uint16_t_by_index(adc3, i, msg->payload); //ADC3 (J405 ADC6, LPC2148 AD0.1)
i += put_uint16_t_by_index(adc4, i, msg->payload); //ADC4 (J405 ADC7, LPC2148 AD1.3)
i += put_uint16_t_by_index(vbat, i, msg->payload); //Battery voltage
i += put_int16_t_by_index(temp, i, msg->payload); //Temperature (degrees celcius)
i += put_int32_t_by_index(baro, i, msg->payload); //Barometric pressure (hecto Pascal)
i += put_uint16_t_by_index(adc1, i, msg->payload); // ADC1 (J405 ADC3, LPC2148 AD0.6)
i += put_uint16_t_by_index(adc2, i, msg->payload); // ADC2 (J405 ADC5, LPC2148 AD0.2)
i += put_uint16_t_by_index(adc3, i, msg->payload); // ADC3 (J405 ADC6, LPC2148 AD0.1)
i += put_uint16_t_by_index(adc4, i, msg->payload); // ADC4 (J405 ADC7, LPC2148 AD1.3)
i += put_uint16_t_by_index(vbat, i, msg->payload); // Battery voltage
i += put_int16_t_by_index(temp, i, msg->payload); // Temperature (degrees celcius)
i += put_int32_t_by_index(baro, i, msg->payload); // Barometric pressure (hecto Pascal)
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a raw_aux 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 adc1 ADC1 (J405 ADC3, LPC2148 AD0.6)
* @param adc2 ADC2 (J405 ADC5, LPC2148 AD0.2)
* @param adc3 ADC3 (J405 ADC6, LPC2148 AD0.1)
* @param adc4 ADC4 (J405 ADC7, LPC2148 AD1.3)
* @param vbat Battery voltage
* @param temp Temperature (degrees celcius)
* @param baro Barometric pressure (hecto Pascal)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_raw_aux_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint16_t adc1, uint16_t adc2, uint16_t adc3, uint16_t adc4, uint16_t vbat, int16_t temp, int32_t baro)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_RAW_AUX;
i += put_uint16_t_by_index(adc1, i, msg->payload); //ADC1 (J405 ADC3, LPC2148 AD0.6)
i += put_uint16_t_by_index(adc2, i, msg->payload); //ADC2 (J405 ADC5, LPC2148 AD0.2)
i += put_uint16_t_by_index(adc3, i, msg->payload); //ADC3 (J405 ADC6, LPC2148 AD0.1)
i += put_uint16_t_by_index(adc4, i, msg->payload); //ADC4 (J405 ADC7, LPC2148 AD1.3)
i += put_uint16_t_by_index(vbat, i, msg->payload); //Battery voltage
i += put_int16_t_by_index(temp, i, msg->payload); //Temperature (degrees celcius)
i += put_int32_t_by_index(baro, i, msg->payload); //Barometric pressure (hecto Pascal)
i += put_uint16_t_by_index(adc1, i, msg->payload); // ADC1 (J405 ADC3, LPC2148 AD0.6)
i += put_uint16_t_by_index(adc2, i, msg->payload); // ADC2 (J405 ADC5, LPC2148 AD0.2)
i += put_uint16_t_by_index(adc3, i, msg->payload); // ADC3 (J405 ADC6, LPC2148 AD0.1)
i += put_uint16_t_by_index(adc4, i, msg->payload); // ADC4 (J405 ADC7, LPC2148 AD1.3)
i += put_uint16_t_by_index(vbat, i, msg->payload); // Battery voltage
i += put_int16_t_by_index(temp, i, msg->payload); // Temperature (degrees celcius)
i += put_int32_t_by_index(baro, i, msg->payload); // Barometric pressure (hecto Pascal)
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a raw_aux 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 raw_aux C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_raw_aux_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_raw_aux_t* raw_aux)
{
return mavlink_msg_raw_aux_pack(system_id, component_id, msg, raw_aux->adc1, raw_aux->adc2, raw_aux->adc3, raw_aux->adc4, raw_aux->vbat, raw_aux->temp, raw_aux->baro);
}
/**
* @brief Send a raw_aux message
* @param chan MAVLink channel to send the message
*
* @param adc1 ADC1 (J405 ADC3, LPC2148 AD0.6)
* @param adc2 ADC2 (J405 ADC5, LPC2148 AD0.2)
* @param adc3 ADC3 (J405 ADC6, LPC2148 AD0.1)
* @param adc4 ADC4 (J405 ADC7, LPC2148 AD1.3)
* @param vbat Battery voltage
* @param temp Temperature (degrees celcius)
* @param baro Barometric pressure (hecto Pascal)
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_raw_aux_send(mavlink_channel_t chan, uint16_t adc1, uint16_t adc2, uint16_t adc3, uint16_t adc4, uint16_t vbat, int16_t temp, int32_t baro)
@ -170,6 +208,12 @@ static inline int32_t mavlink_msg_raw_aux_get_baro(const mavlink_message_t* msg)
return (int32_t)r.i;
}
/**
* @brief Decode a raw_aux message into a struct
*
* @param msg The message to decode
* @param raw_aux C-struct to decode the message contents into
*/
static inline void mavlink_msg_raw_aux_decode(const mavlink_message_t* msg, mavlink_raw_aux_t* raw_aux)
{
raw_aux->adc1 = mavlink_msg_raw_aux_get_adc1(msg);

View File

@ -16,7 +16,10 @@ typedef struct __mavlink_set_cam_shutter_t
/**
* @brief Send a set_cam_shutter message
* @brief Pack a set_cam_shutter 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 cam_no Camera id
* @param cam_mode Camera mode: 0 = auto, 1 = manual
@ -31,36 +34,69 @@ static inline uint16_t mavlink_msg_set_cam_shutter_pack(uint8_t system_id, uint8
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_SET_CAM_SHUTTER;
i += put_uint8_t_by_index(cam_no, i, msg->payload); //Camera id
i += put_uint8_t_by_index(cam_mode, i, msg->payload); //Camera mode: 0 = auto, 1 = manual
i += put_uint8_t_by_index(trigger_pin, i, msg->payload); //Trigger pin, 0-3 for PtGrey FireFly
i += put_uint16_t_by_index(interval, i, msg->payload); //Shutter interval, in microseconds
i += put_uint16_t_by_index(exposure, i, msg->payload); //Exposure time, in microseconds
i += put_float_by_index(gain, i, msg->payload); //Camera gain
i += put_uint8_t_by_index(cam_no, i, msg->payload); // Camera id
i += put_uint8_t_by_index(cam_mode, i, msg->payload); // Camera mode: 0 = auto, 1 = manual
i += put_uint8_t_by_index(trigger_pin, i, msg->payload); // Trigger pin, 0-3 for PtGrey FireFly
i += put_uint16_t_by_index(interval, i, msg->payload); // Shutter interval, in microseconds
i += put_uint16_t_by_index(exposure, i, msg->payload); // Exposure time, in microseconds
i += put_float_by_index(gain, i, msg->payload); // Camera gain
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a set_cam_shutter 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 cam_no Camera id
* @param cam_mode Camera mode: 0 = auto, 1 = manual
* @param trigger_pin Trigger pin, 0-3 for PtGrey FireFly
* @param interval Shutter interval, in microseconds
* @param exposure Exposure time, in microseconds
* @param gain Camera gain
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_set_cam_shutter_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t cam_no, uint8_t cam_mode, uint8_t trigger_pin, uint16_t interval, uint16_t exposure, float gain)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_SET_CAM_SHUTTER;
i += put_uint8_t_by_index(cam_no, i, msg->payload); //Camera id
i += put_uint8_t_by_index(cam_mode, i, msg->payload); //Camera mode: 0 = auto, 1 = manual
i += put_uint8_t_by_index(trigger_pin, i, msg->payload); //Trigger pin, 0-3 for PtGrey FireFly
i += put_uint16_t_by_index(interval, i, msg->payload); //Shutter interval, in microseconds
i += put_uint16_t_by_index(exposure, i, msg->payload); //Exposure time, in microseconds
i += put_float_by_index(gain, i, msg->payload); //Camera gain
i += put_uint8_t_by_index(cam_no, i, msg->payload); // Camera id
i += put_uint8_t_by_index(cam_mode, i, msg->payload); // Camera mode: 0 = auto, 1 = manual
i += put_uint8_t_by_index(trigger_pin, i, msg->payload); // Trigger pin, 0-3 for PtGrey FireFly
i += put_uint16_t_by_index(interval, i, msg->payload); // Shutter interval, in microseconds
i += put_uint16_t_by_index(exposure, i, msg->payload); // Exposure time, in microseconds
i += put_float_by_index(gain, i, msg->payload); // Camera gain
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a set_cam_shutter 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 set_cam_shutter C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_set_cam_shutter_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_cam_shutter_t* set_cam_shutter)
{
return mavlink_msg_set_cam_shutter_pack(system_id, component_id, msg, set_cam_shutter->cam_no, set_cam_shutter->cam_mode, set_cam_shutter->trigger_pin, set_cam_shutter->interval, set_cam_shutter->exposure, set_cam_shutter->gain);
}
/**
* @brief Send a set_cam_shutter message
* @param chan MAVLink channel to send the message
*
* @param cam_no Camera id
* @param cam_mode Camera mode: 0 = auto, 1 = manual
* @param trigger_pin Trigger pin, 0-3 for PtGrey FireFly
* @param interval Shutter interval, in microseconds
* @param exposure Exposure time, in microseconds
* @param gain Camera gain
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_set_cam_shutter_send(mavlink_channel_t chan, uint8_t cam_no, uint8_t cam_mode, uint8_t trigger_pin, uint16_t interval, uint16_t exposure, float gain)
@ -144,6 +180,12 @@ static inline float mavlink_msg_set_cam_shutter_get_gain(const mavlink_message_t
return (float)r.f;
}
/**
* @brief Decode a set_cam_shutter message into a struct
*
* @param msg The message to decode
* @param set_cam_shutter C-struct to decode the message contents into
*/
static inline void mavlink_msg_set_cam_shutter_decode(const mavlink_message_t* msg, mavlink_set_cam_shutter_t* set_cam_shutter)
{
set_cam_shutter->cam_no = mavlink_msg_set_cam_shutter_get_cam_no(msg);

View File

@ -17,7 +17,10 @@ typedef struct __mavlink_vicon_position_estimate_t
/**
* @brief Send a vicon_position_estimate message
* @brief Pack a vicon_position_estimate 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 usec Timestamp (milliseconds)
* @param x Global X position
@ -33,38 +36,73 @@ static inline uint16_t mavlink_msg_vicon_position_estimate_pack(uint8_t system_i
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE;
i += put_uint64_t_by_index(usec, i, msg->payload); //Timestamp (milliseconds)
i += put_float_by_index(x, i, msg->payload); //Global X position
i += put_float_by_index(y, i, msg->payload); //Global Y position
i += put_float_by_index(z, i, msg->payload); //Global Z position
i += put_float_by_index(roll, i, msg->payload); //Roll angle in rad
i += put_float_by_index(pitch, i, msg->payload); //Pitch angle in rad
i += put_float_by_index(yaw, i, msg->payload); //Yaw angle in rad
i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (milliseconds)
i += put_float_by_index(x, i, msg->payload); // Global X position
i += put_float_by_index(y, i, msg->payload); // Global Y position
i += put_float_by_index(z, i, msg->payload); // Global Z position
i += put_float_by_index(roll, i, msg->payload); // Roll angle in rad
i += put_float_by_index(pitch, i, msg->payload); // Pitch angle in rad
i += put_float_by_index(yaw, i, msg->payload); // Yaw angle in rad
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a vicon_position_estimate 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 usec Timestamp (milliseconds)
* @param x Global X position
* @param y Global Y position
* @param z Global Z position
* @param roll Roll angle in rad
* @param pitch Pitch angle in rad
* @param yaw Yaw angle in rad
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_vicon_position_estimate_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE;
i += put_uint64_t_by_index(usec, i, msg->payload); //Timestamp (milliseconds)
i += put_float_by_index(x, i, msg->payload); //Global X position
i += put_float_by_index(y, i, msg->payload); //Global Y position
i += put_float_by_index(z, i, msg->payload); //Global Z position
i += put_float_by_index(roll, i, msg->payload); //Roll angle in rad
i += put_float_by_index(pitch, i, msg->payload); //Pitch angle in rad
i += put_float_by_index(yaw, i, msg->payload); //Yaw angle in rad
i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (milliseconds)
i += put_float_by_index(x, i, msg->payload); // Global X position
i += put_float_by_index(y, i, msg->payload); // Global Y position
i += put_float_by_index(z, i, msg->payload); // Global Z position
i += put_float_by_index(roll, i, msg->payload); // Roll angle in rad
i += put_float_by_index(pitch, i, msg->payload); // Pitch angle in rad
i += put_float_by_index(yaw, i, msg->payload); // Yaw angle in rad
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a vicon_position_estimate 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 vicon_position_estimate C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_vicon_position_estimate_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_vicon_position_estimate_t* vicon_position_estimate)
{
return mavlink_msg_vicon_position_estimate_pack(system_id, component_id, msg, vicon_position_estimate->usec, vicon_position_estimate->x, vicon_position_estimate->y, vicon_position_estimate->z, vicon_position_estimate->roll, vicon_position_estimate->pitch, vicon_position_estimate->yaw);
}
/**
* @brief Send a vicon_position_estimate message
* @param chan MAVLink channel to send the message
*
* @param usec Timestamp (milliseconds)
* @param x Global X position
* @param y Global Y position
* @param z Global Z position
* @param roll Roll angle in rad
* @param pitch Pitch angle in rad
* @param yaw Yaw angle in rad
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_vicon_position_estimate_send(mavlink_channel_t chan, uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw)
@ -186,6 +224,12 @@ static inline float mavlink_msg_vicon_position_estimate_get_yaw(const mavlink_me
return (float)r.f;
}
/**
* @brief Decode a vicon_position_estimate message into a struct
*
* @param msg The message to decode
* @param vicon_position_estimate C-struct to decode the message contents into
*/
static inline void mavlink_msg_vicon_position_estimate_decode(const mavlink_message_t* msg, mavlink_vicon_position_estimate_t* vicon_position_estimate)
{
vicon_position_estimate->usec = mavlink_msg_vicon_position_estimate_get_usec(msg);

View File

@ -17,7 +17,10 @@ typedef struct __mavlink_vision_position_estimate_t
/**
* @brief Send a vision_position_estimate message
* @brief Pack a vision_position_estimate 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 usec Timestamp (milliseconds)
* @param x Global X position
@ -33,38 +36,73 @@ static inline uint16_t mavlink_msg_vision_position_estimate_pack(uint8_t system_
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE;
i += put_uint64_t_by_index(usec, i, msg->payload); //Timestamp (milliseconds)
i += put_float_by_index(x, i, msg->payload); //Global X position
i += put_float_by_index(y, i, msg->payload); //Global Y position
i += put_float_by_index(z, i, msg->payload); //Global Z position
i += put_float_by_index(roll, i, msg->payload); //Roll angle in rad
i += put_float_by_index(pitch, i, msg->payload); //Pitch angle in rad
i += put_float_by_index(yaw, i, msg->payload); //Yaw angle in rad
i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (milliseconds)
i += put_float_by_index(x, i, msg->payload); // Global X position
i += put_float_by_index(y, i, msg->payload); // Global Y position
i += put_float_by_index(z, i, msg->payload); // Global Z position
i += put_float_by_index(roll, i, msg->payload); // Roll angle in rad
i += put_float_by_index(pitch, i, msg->payload); // Pitch angle in rad
i += put_float_by_index(yaw, i, msg->payload); // Yaw angle in rad
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a vision_position_estimate 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 usec Timestamp (milliseconds)
* @param x Global X position
* @param y Global Y position
* @param z Global Z position
* @param roll Roll angle in rad
* @param pitch Pitch angle in rad
* @param yaw Yaw angle in rad
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_vision_position_estimate_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE;
i += put_uint64_t_by_index(usec, i, msg->payload); //Timestamp (milliseconds)
i += put_float_by_index(x, i, msg->payload); //Global X position
i += put_float_by_index(y, i, msg->payload); //Global Y position
i += put_float_by_index(z, i, msg->payload); //Global Z position
i += put_float_by_index(roll, i, msg->payload); //Roll angle in rad
i += put_float_by_index(pitch, i, msg->payload); //Pitch angle in rad
i += put_float_by_index(yaw, i, msg->payload); //Yaw angle in rad
i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (milliseconds)
i += put_float_by_index(x, i, msg->payload); // Global X position
i += put_float_by_index(y, i, msg->payload); // Global Y position
i += put_float_by_index(z, i, msg->payload); // Global Z position
i += put_float_by_index(roll, i, msg->payload); // Roll angle in rad
i += put_float_by_index(pitch, i, msg->payload); // Pitch angle in rad
i += put_float_by_index(yaw, i, msg->payload); // Yaw angle in rad
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a vision_position_estimate 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 vision_position_estimate C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_vision_position_estimate_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_vision_position_estimate_t* vision_position_estimate)
{
return mavlink_msg_vision_position_estimate_pack(system_id, component_id, msg, vision_position_estimate->usec, vision_position_estimate->x, vision_position_estimate->y, vision_position_estimate->z, vision_position_estimate->roll, vision_position_estimate->pitch, vision_position_estimate->yaw);
}
/**
* @brief Send a vision_position_estimate message
* @param chan MAVLink channel to send the message
*
* @param usec Timestamp (milliseconds)
* @param x Global X position
* @param y Global Y position
* @param z Global Z position
* @param roll Roll angle in rad
* @param pitch Pitch angle in rad
* @param yaw Yaw angle in rad
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_vision_position_estimate_send(mavlink_channel_t chan, uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw)
@ -186,6 +224,12 @@ static inline float mavlink_msg_vision_position_estimate_get_yaw(const mavlink_m
return (float)r.f;
}
/**
* @brief Decode a vision_position_estimate message into a struct
*
* @param msg The message to decode
* @param vision_position_estimate C-struct to decode the message contents into
*/
static inline void mavlink_msg_vision_position_estimate_decode(const mavlink_message_t* msg, mavlink_vision_position_estimate_t* vision_position_estimate)
{
vision_position_estimate->usec = mavlink_msg_vision_position_estimate_get_usec(msg);

View File

@ -14,7 +14,10 @@ typedef struct __mavlink_watchdog_command_t
/**
* @brief Send a watchdog_command message
* @brief Pack a watchdog_command 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 target_system_id Target system ID
* @param watchdog_id Watchdog ID
@ -27,32 +30,61 @@ static inline uint16_t mavlink_msg_watchdog_command_pack(uint8_t system_id, uint
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_WATCHDOG_COMMAND;
i += put_uint8_t_by_index(target_system_id, i, msg->payload); //Target system ID
i += put_uint16_t_by_index(watchdog_id, i, msg->payload); //Watchdog ID
i += put_uint16_t_by_index(process_id, i, msg->payload); //Process ID
i += put_uint8_t_by_index(command_id, i, msg->payload); //Command ID
i += put_uint8_t_by_index(target_system_id, i, msg->payload); // Target system ID
i += put_uint16_t_by_index(watchdog_id, i, msg->payload); // Watchdog ID
i += put_uint16_t_by_index(process_id, i, msg->payload); // Process ID
i += put_uint8_t_by_index(command_id, i, msg->payload); // Command ID
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a watchdog_command 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 target_system_id Target system ID
* @param watchdog_id Watchdog ID
* @param process_id Process ID
* @param command_id Command ID
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_watchdog_command_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target_system_id, uint16_t watchdog_id, uint16_t process_id, uint8_t command_id)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_WATCHDOG_COMMAND;
i += put_uint8_t_by_index(target_system_id, i, msg->payload); //Target system ID
i += put_uint16_t_by_index(watchdog_id, i, msg->payload); //Watchdog ID
i += put_uint16_t_by_index(process_id, i, msg->payload); //Process ID
i += put_uint8_t_by_index(command_id, i, msg->payload); //Command ID
i += put_uint8_t_by_index(target_system_id, i, msg->payload); // Target system ID
i += put_uint16_t_by_index(watchdog_id, i, msg->payload); // Watchdog ID
i += put_uint16_t_by_index(process_id, i, msg->payload); // Process ID
i += put_uint8_t_by_index(command_id, i, msg->payload); // Command ID
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a watchdog_command 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 watchdog_command C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_watchdog_command_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_watchdog_command_t* watchdog_command)
{
return mavlink_msg_watchdog_command_pack(system_id, component_id, msg, watchdog_command->target_system_id, watchdog_command->watchdog_id, watchdog_command->process_id, watchdog_command->command_id);
}
/**
* @brief Send a watchdog_command message
* @param chan MAVLink channel to send the message
*
* @param target_system_id Target system ID
* @param watchdog_id Watchdog ID
* @param process_id Process ID
* @param command_id Command ID
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_watchdog_command_send(mavlink_channel_t chan, uint8_t target_system_id, uint16_t watchdog_id, uint16_t process_id, uint8_t command_id)
@ -111,6 +143,12 @@ static inline uint8_t mavlink_msg_watchdog_command_get_command_id(const mavlink_
return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint16_t)+sizeof(uint16_t))[0];
}
/**
* @brief Decode a watchdog_command message into a struct
*
* @param msg The message to decode
* @param watchdog_command C-struct to decode the message contents into
*/
static inline void mavlink_msg_watchdog_command_decode(const mavlink_message_t* msg, mavlink_watchdog_command_t* watchdog_command)
{
watchdog_command->target_system_id = mavlink_msg_watchdog_command_get_target_system_id(msg);

View File

@ -12,7 +12,10 @@ typedef struct __mavlink_watchdog_heartbeat_t
/**
* @brief Send a watchdog_heartbeat message
* @brief Pack a watchdog_heartbeat 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 watchdog_id Watchdog ID
* @param process_count Number of processes
@ -23,28 +26,53 @@ static inline uint16_t mavlink_msg_watchdog_heartbeat_pack(uint8_t system_id, ui
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT;
i += put_uint16_t_by_index(watchdog_id, i, msg->payload); //Watchdog ID
i += put_uint16_t_by_index(process_count, i, msg->payload); //Number of processes
i += put_uint16_t_by_index(watchdog_id, i, msg->payload); // Watchdog ID
i += put_uint16_t_by_index(process_count, i, msg->payload); // Number of processes
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a watchdog_heartbeat 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 watchdog_id Watchdog ID
* @param process_count Number of processes
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_watchdog_heartbeat_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint16_t watchdog_id, uint16_t process_count)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT;
i += put_uint16_t_by_index(watchdog_id, i, msg->payload); //Watchdog ID
i += put_uint16_t_by_index(process_count, i, msg->payload); //Number of processes
i += put_uint16_t_by_index(watchdog_id, i, msg->payload); // Watchdog ID
i += put_uint16_t_by_index(process_count, i, msg->payload); // Number of processes
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a watchdog_heartbeat 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 watchdog_heartbeat C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_watchdog_heartbeat_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_watchdog_heartbeat_t* watchdog_heartbeat)
{
return mavlink_msg_watchdog_heartbeat_pack(system_id, component_id, msg, watchdog_heartbeat->watchdog_id, watchdog_heartbeat->process_count);
}
/**
* @brief Send a watchdog_heartbeat message
* @param chan MAVLink channel to send the message
*
* @param watchdog_id Watchdog ID
* @param process_count Number of processes
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_watchdog_heartbeat_send(mavlink_channel_t chan, uint16_t watchdog_id, uint16_t process_count)
@ -83,6 +111,12 @@ static inline uint16_t mavlink_msg_watchdog_heartbeat_get_process_count(const ma
return (uint16_t)r.s;
}
/**
* @brief Decode a watchdog_heartbeat message into a struct
*
* @param msg The message to decode
* @param watchdog_heartbeat C-struct to decode the message contents into
*/
static inline void mavlink_msg_watchdog_heartbeat_decode(const mavlink_message_t* msg, mavlink_watchdog_heartbeat_t* watchdog_heartbeat)
{
watchdog_heartbeat->watchdog_id = mavlink_msg_watchdog_heartbeat_get_watchdog_id(msg);

View File

@ -17,7 +17,10 @@ typedef struct __mavlink_watchdog_process_info_t
/**
* @brief Send a watchdog_process_info message
* @brief Pack a watchdog_process_info 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 watchdog_id Watchdog ID
* @param process_id Process ID
@ -31,34 +34,65 @@ static inline uint16_t mavlink_msg_watchdog_process_info_pack(uint8_t system_id,
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO;
i += put_uint16_t_by_index(watchdog_id, i, msg->payload); //Watchdog ID
i += put_uint16_t_by_index(process_id, i, msg->payload); //Process ID
i += put_array_by_index(name, 100, i, msg->payload); //Process name
i += put_array_by_index(arguments, 147, i, msg->payload); //Process arguments
i += put_int32_t_by_index(timeout, i, msg->payload); //Timeout (seconds)
i += put_uint16_t_by_index(watchdog_id, i, msg->payload); // Watchdog ID
i += put_uint16_t_by_index(process_id, i, msg->payload); // Process ID
i += put_array_by_index(name, 100, i, msg->payload); // Process name
i += put_array_by_index(arguments, 147, i, msg->payload); // Process arguments
i += put_int32_t_by_index(timeout, i, msg->payload); // Timeout (seconds)
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a watchdog_process_info 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 watchdog_id Watchdog ID
* @param process_id Process ID
* @param name Process name
* @param arguments Process arguments
* @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 int8_t* name, const int8_t* arguments, int32_t timeout)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO;
i += put_uint16_t_by_index(watchdog_id, i, msg->payload); //Watchdog ID
i += put_uint16_t_by_index(process_id, i, msg->payload); //Process ID
i += put_array_by_index(name, 100, i, msg->payload); //Process name
i += put_array_by_index(arguments, 147, i, msg->payload); //Process arguments
i += put_int32_t_by_index(timeout, i, msg->payload); //Timeout (seconds)
i += put_uint16_t_by_index(watchdog_id, i, msg->payload); // Watchdog ID
i += put_uint16_t_by_index(process_id, i, msg->payload); // Process ID
i += put_array_by_index(name, 100, i, msg->payload); // Process name
i += put_array_by_index(arguments, 147, i, msg->payload); // Process arguments
i += put_int32_t_by_index(timeout, i, msg->payload); // Timeout (seconds)
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a watchdog_process_info 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 watchdog_process_info C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_watchdog_process_info_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_watchdog_process_info_t* watchdog_process_info)
{
return mavlink_msg_watchdog_process_info_pack(system_id, component_id, msg, watchdog_process_info->watchdog_id, watchdog_process_info->process_id, watchdog_process_info->name, watchdog_process_info->arguments, watchdog_process_info->timeout);
}
/**
* @brief Send a watchdog_process_info message
* @param chan MAVLink channel to send the message
*
* @param watchdog_id Watchdog ID
* @param process_id Process ID
* @param name Process name
* @param arguments Process arguments
* @param timeout Timeout (seconds)
*/
#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 int8_t* name, const int8_t* arguments, int32_t timeout)
@ -136,6 +170,12 @@ static inline int32_t mavlink_msg_watchdog_process_info_get_timeout(const mavlin
return (int32_t)r.i;
}
/**
* @brief Decode a watchdog_process_info message into a struct
*
* @param msg The message to decode
* @param watchdog_process_info C-struct to decode the message contents into
*/
static inline void mavlink_msg_watchdog_process_info_decode(const mavlink_message_t* msg, mavlink_watchdog_process_info_t* watchdog_process_info)
{
watchdog_process_info->watchdog_id = mavlink_msg_watchdog_process_info_get_watchdog_id(msg);

View File

@ -16,7 +16,10 @@ typedef struct __mavlink_watchdog_process_status_t
/**
* @brief Send a watchdog_process_status message
* @brief Pack a watchdog_process_status 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 watchdog_id Watchdog ID
* @param process_id Process ID
@ -31,36 +34,69 @@ static inline uint16_t mavlink_msg_watchdog_process_status_pack(uint8_t system_i
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS;
i += put_uint16_t_by_index(watchdog_id, i, msg->payload); //Watchdog ID
i += put_uint16_t_by_index(process_id, i, msg->payload); //Process ID
i += put_uint8_t_by_index(state, i, msg->payload); //Is running / finished / suspended / crashed
i += put_uint8_t_by_index(muted, i, msg->payload); //Is muted
i += put_int32_t_by_index(pid, i, msg->payload); //PID
i += put_uint16_t_by_index(crashes, i, msg->payload); //Number of crashes
i += put_uint16_t_by_index(watchdog_id, i, msg->payload); // Watchdog ID
i += put_uint16_t_by_index(process_id, i, msg->payload); // Process ID
i += put_uint8_t_by_index(state, i, msg->payload); // Is running / finished / suspended / crashed
i += put_uint8_t_by_index(muted, i, msg->payload); // Is muted
i += put_int32_t_by_index(pid, i, msg->payload); // PID
i += put_uint16_t_by_index(crashes, i, msg->payload); // Number of crashes
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a watchdog_process_status 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 watchdog_id Watchdog ID
* @param process_id Process ID
* @param state Is running / finished / suspended / crashed
* @param muted Is muted
* @param pid PID
* @param crashes Number of crashes
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_watchdog_process_status_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, uint8_t state, uint8_t muted, int32_t pid, uint16_t crashes)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS;
i += put_uint16_t_by_index(watchdog_id, i, msg->payload); //Watchdog ID
i += put_uint16_t_by_index(process_id, i, msg->payload); //Process ID
i += put_uint8_t_by_index(state, i, msg->payload); //Is running / finished / suspended / crashed
i += put_uint8_t_by_index(muted, i, msg->payload); //Is muted
i += put_int32_t_by_index(pid, i, msg->payload); //PID
i += put_uint16_t_by_index(crashes, i, msg->payload); //Number of crashes
i += put_uint16_t_by_index(watchdog_id, i, msg->payload); // Watchdog ID
i += put_uint16_t_by_index(process_id, i, msg->payload); // Process ID
i += put_uint8_t_by_index(state, i, msg->payload); // Is running / finished / suspended / crashed
i += put_uint8_t_by_index(muted, i, msg->payload); // Is muted
i += put_int32_t_by_index(pid, i, msg->payload); // PID
i += put_uint16_t_by_index(crashes, i, msg->payload); // Number of crashes
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a watchdog_process_status 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 watchdog_process_status C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_watchdog_process_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_watchdog_process_status_t* watchdog_process_status)
{
return mavlink_msg_watchdog_process_status_pack(system_id, component_id, msg, watchdog_process_status->watchdog_id, watchdog_process_status->process_id, watchdog_process_status->state, watchdog_process_status->muted, watchdog_process_status->pid, watchdog_process_status->crashes);
}
/**
* @brief Send a watchdog_process_status message
* @param chan MAVLink channel to send the message
*
* @param watchdog_id Watchdog ID
* @param process_id Process ID
* @param state Is running / finished / suspended / crashed
* @param muted Is muted
* @param pid PID
* @param crashes Number of crashes
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_watchdog_process_status_send(mavlink_channel_t chan, uint16_t watchdog_id, uint16_t process_id, uint8_t state, uint8_t muted, int32_t pid, uint16_t crashes)
@ -147,6 +183,12 @@ static inline uint16_t mavlink_msg_watchdog_process_status_get_crashes(const mav
return (uint16_t)r.s;
}
/**
* @brief Decode a watchdog_process_status message into a struct
*
* @param msg The message to decode
* @param watchdog_process_status C-struct to decode the message contents into
*/
static inline void mavlink_msg_watchdog_process_status_decode(const mavlink_message_t* msg, mavlink_watchdog_process_status_t* watchdog_process_status)
{
watchdog_process_status->watchdog_id = mavlink_msg_watchdog_process_status_get_watchdog_id(msg);

View File

@ -1,7 +1,7 @@
/** @file
* @brief MAVLink comm protocol.
* @see http://pixhawk.ethz.ch/software/mavlink
* Generated on Tuesday, December 7 2010, 13:34 UTC
* Generated on Friday, January 7 2011, 10:04 UTC
*/
#ifndef PIXHAWK_H
#define PIXHAWK_H
@ -17,6 +17,17 @@ extern "C" {
#include "../common/common.h"
// MAVLINK VERSION
#ifndef MAVLINK_VERSION
#define MAVLINK_VERSION 0
#endif
#if (MAVLINK_VERSION == 0)
#undef MAVLINK_VERSION
#define MAVLINK_VERSION 0
#endif
// ENUM DEFINITIONS
/** @brief Slugs parameter interface subsets */
@ -51,6 +62,8 @@ enum SLUGS_PID_INDX_IDS
#include "./mavlink_msg_pattern_detected.h"
#include "./mavlink_msg_point_of_interest.h"
#include "./mavlink_msg_point_of_interest_connection.h"
#include "./mavlink_msg_data_transmission_handshake.h"
#include "./mavlink_msg_encapsulated_data.h"
#ifdef __cplusplus
}
#endif

View File

@ -1,11 +1,12 @@
<?xml version="1.0"?>
<mavlink>
<version>1</version>
<messages>
<message name="HEARTBEAT" id="0">
<description>The heartbeat message shows that a system is present and responding. The type of the MAV and Autopilot hardware allow the receiving system to treat further messages from this system appropriate (e.g. by laying out the user interface based on the autopilot).</description>
<field name="type" type="uint8_t">Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)</field>
<field name="autopilot" type="uint8_t">Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM</field>
<field name="mavlink_version" type="uint8_t_mavlink_version">MAVLink version</field>
</message>
<message name="BOOT" id="1">
@ -403,18 +404,25 @@ NOT the global position estimate of the sytem, but rather a RAW sensor value. Se
<message name="GPS_LOCAL_ORIGIN_SET" id="71">
<description>Once the MAV sets a new GPS-Local correspondence, this message announces </description>
<field name="latitude" type="float">Latitude (WGS84)</field>
<field name="longitude" type="float">Longitude (WGS84)</field>
<field name="altitude" type="float">Altitude(WGS84)</field>
<field name="x" type="float">Local X coordinate in meters</field>
<field name="y" type="float">Local Y coordinate in meters</field>
<field name="z" type="float">Local Z coordinate in meters</field>
<field name="latitude" type="int32_t">Latitude (WGS84), expressed as * 1E7</field>
<field name="longitude" type="int32_t">Longitude (WGS84), expressed as * 1E7</field>
<field name="altitude" type="int32_t">Altitude(WGS84), expressed as * 1000</field>
</message>
<message name="AIRSPEED" id="72">
<description>The calculated airspeed </description>
<field name="airspeed" type="float">meters/second</field>
</message>
<message name="GLOBAL_POSITION_INT" id="73">
<description>The filtered global position (e.g. fused GPS and accelerometers). The position is in GPS-frame (right-handed, Z-up)</description>
<field name="lat" type="int32_t">Latitude / X Position, expressed as * 1E7</field>
<field name="lon" type="int32_t">Longitude / Y Position, expressed as * 1E7</field>
<field name="alt" type="int32_t">Altitude / negative Z Position, expressed as * 1000</field>
<field name="vx" type="int16_t">Ground X Speed, expressed as m/s * 100</field>
<field name="vy" type="int16_t">Ground Y Speed, expressed as m/s * 100</field>
<field name="vz" type="int16_t">Ground Z Speed, expressed as m/s * 100</field>
</message>
<!-- MESSAGE IDs 80 - 250: Space for custom messages in individual projectname_messages.xml files -->

View File

@ -38,6 +38,11 @@
<field name="seq" type="uint32_t">IMU seq</field>
<field name="roll" type="float">Roll angle in rad</field>
<field name="pitch" type="float">Pitch angle in rad</field>
<field name="yaw" type="float">Yaw angle in rad</field>
<field name="local_z" type="float">Local frame Z coordinate (height over ground)</field>
<field name="lat" type="float">GPS X coordinate</field>
<field name="lon" type="float">GPS Y coordinate</field>
<field name="alt" type="float">Global frame altitude</field>
</message>
<message name="IMAGE_TRIGGER_CONTROL" id="102">
@ -60,6 +65,11 @@
<field name="gain" type="float">Camera gain</field>
<field name="roll" type="float">Roll angle in rad</field>
<field name="pitch" type="float">Pitch angle in rad</field>
<field name="yaw" type="float">Yaw angle in rad</field>
<field name="local_z" type="float">Local frame Z coordinate (height over ground)</field>
<field name="lat" type="float">GPS X coordinate</field>
<field name="lon" type="float">GPS Y coordinate</field>
<field name="alt" type="float">Global frame altitude</field>
</message>
<message name="VISION_POSITION_ESTIMATE" id="111">
@ -218,5 +228,18 @@
<field name="name" type="array[25]">POI connection name</field>
</message>
<message name="DATA_TRANSMISSION_HANDSHAKE" id="170">
<field name="type" type="uint8_t">type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h)</field>
<field name="size" type="uint32_t">total data size in bytes (set on ACK only)</field>
<field name="packets" type="uint8_t">number of packets beeing sent (set on ACK only)</field>
<field name="payload" type="uint8_t">payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only)</field>
<field name="jpg_quality" type="uint8_t">JPEG quality out of [1,100]</field>
</message>
<message name="ENCAPSULATED_DATA" id="171">
<field name="seqnr" type="uint16_t">sequence number (starting with 0 on every transmission)</field>
<field name="data" type="uint8_t[253]">image data bytes</field>
</message>
</messages>
</mavlink>

View File

@ -1,4 +1,5 @@
#!/bin/sh
trap exit ERR
rm -rf _tmp
git clone git://github.com/pixhawk/mavlink.git -b dev _tmp
rm -rf _tmp/.git