添加MAVLINK协议库

This commit is contained in:
OPTOC
2025-09-02 10:34:06 +08:00
parent 7960bb80ec
commit 040ce2c62c
360 changed files with 143976 additions and 0 deletions

File diff suppressed because one or more lines are too long

View File

@@ -0,0 +1,34 @@
/** @file
* @brief MAVLink comm protocol built from ardupilotmega.xml
* @see http://mavlink.org
*/
#pragma once
#ifndef MAVLINK_H
#define MAVLINK_H
#define MAVLINK_PRIMARY_XML_IDX 0
#ifndef MAVLINK_STX
#define MAVLINK_STX 253
#endif
#ifndef MAVLINK_ENDIAN
#define MAVLINK_ENDIAN MAVLINK_LITTLE_ENDIAN
#endif
#ifndef MAVLINK_ALIGNED_FIELDS
#define MAVLINK_ALIGNED_FIELDS 1
#endif
#ifndef MAVLINK_CRC_EXTRA
#define MAVLINK_CRC_EXTRA 1
#endif
#ifndef MAVLINK_COMMAND_24BIT
#define MAVLINK_COMMAND_24BIT 1
#endif
#include "version.h"
#include "ardupilotmega.h"
#endif // MAVLINK_H

View File

@@ -0,0 +1,513 @@
#pragma once
// MESSAGE ADAP_TUNING PACKING
#define MAVLINK_MSG_ID_ADAP_TUNING 11010
MAVPACKED(
typedef struct __mavlink_adap_tuning_t {
float desired; /*< [deg/s] Desired rate.*/
float achieved; /*< [deg/s] Achieved rate.*/
float error; /*< Error between model and vehicle.*/
float theta; /*< Theta estimated state predictor.*/
float omega; /*< Omega estimated state predictor.*/
float sigma; /*< Sigma estimated state predictor.*/
float theta_dot; /*< Theta derivative.*/
float omega_dot; /*< Omega derivative.*/
float sigma_dot; /*< Sigma derivative.*/
float f; /*< Projection operator value.*/
float f_dot; /*< Projection operator derivative.*/
float u; /*< u adaptive controlled output command.*/
uint8_t axis; /*< Axis.*/
}) mavlink_adap_tuning_t;
#define MAVLINK_MSG_ID_ADAP_TUNING_LEN 49
#define MAVLINK_MSG_ID_ADAP_TUNING_MIN_LEN 49
#define MAVLINK_MSG_ID_11010_LEN 49
#define MAVLINK_MSG_ID_11010_MIN_LEN 49
#define MAVLINK_MSG_ID_ADAP_TUNING_CRC 46
#define MAVLINK_MSG_ID_11010_CRC 46
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_ADAP_TUNING { \
11010, \
"ADAP_TUNING", \
13, \
{ { "axis", NULL, MAVLINK_TYPE_UINT8_T, 0, 48, offsetof(mavlink_adap_tuning_t, axis) }, \
{ "desired", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_adap_tuning_t, desired) }, \
{ "achieved", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_adap_tuning_t, achieved) }, \
{ "error", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_adap_tuning_t, error) }, \
{ "theta", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_adap_tuning_t, theta) }, \
{ "omega", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_adap_tuning_t, omega) }, \
{ "sigma", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_adap_tuning_t, sigma) }, \
{ "theta_dot", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_adap_tuning_t, theta_dot) }, \
{ "omega_dot", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_adap_tuning_t, omega_dot) }, \
{ "sigma_dot", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_adap_tuning_t, sigma_dot) }, \
{ "f", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_adap_tuning_t, f) }, \
{ "f_dot", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_adap_tuning_t, f_dot) }, \
{ "u", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_adap_tuning_t, u) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_ADAP_TUNING { \
"ADAP_TUNING", \
13, \
{ { "axis", NULL, MAVLINK_TYPE_UINT8_T, 0, 48, offsetof(mavlink_adap_tuning_t, axis) }, \
{ "desired", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_adap_tuning_t, desired) }, \
{ "achieved", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_adap_tuning_t, achieved) }, \
{ "error", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_adap_tuning_t, error) }, \
{ "theta", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_adap_tuning_t, theta) }, \
{ "omega", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_adap_tuning_t, omega) }, \
{ "sigma", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_adap_tuning_t, sigma) }, \
{ "theta_dot", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_adap_tuning_t, theta_dot) }, \
{ "omega_dot", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_adap_tuning_t, omega_dot) }, \
{ "sigma_dot", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_adap_tuning_t, sigma_dot) }, \
{ "f", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_adap_tuning_t, f) }, \
{ "f_dot", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_adap_tuning_t, f_dot) }, \
{ "u", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_adap_tuning_t, u) }, \
} \
}
#endif
/**
* @brief Pack a adap_tuning 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 axis Axis.
* @param desired [deg/s] Desired rate.
* @param achieved [deg/s] Achieved rate.
* @param error Error between model and vehicle.
* @param theta Theta estimated state predictor.
* @param omega Omega estimated state predictor.
* @param sigma Sigma estimated state predictor.
* @param theta_dot Theta derivative.
* @param omega_dot Omega derivative.
* @param sigma_dot Sigma derivative.
* @param f Projection operator value.
* @param f_dot Projection operator derivative.
* @param u u adaptive controlled output command.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_adap_tuning_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t axis, float desired, float achieved, float error, float theta, float omega, float sigma, float theta_dot, float omega_dot, float sigma_dot, float f, float f_dot, float u)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_ADAP_TUNING_LEN];
_mav_put_float(buf, 0, desired);
_mav_put_float(buf, 4, achieved);
_mav_put_float(buf, 8, error);
_mav_put_float(buf, 12, theta);
_mav_put_float(buf, 16, omega);
_mav_put_float(buf, 20, sigma);
_mav_put_float(buf, 24, theta_dot);
_mav_put_float(buf, 28, omega_dot);
_mav_put_float(buf, 32, sigma_dot);
_mav_put_float(buf, 36, f);
_mav_put_float(buf, 40, f_dot);
_mav_put_float(buf, 44, u);
_mav_put_uint8_t(buf, 48, axis);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ADAP_TUNING_LEN);
#else
mavlink_adap_tuning_t packet;
packet.desired = desired;
packet.achieved = achieved;
packet.error = error;
packet.theta = theta;
packet.omega = omega;
packet.sigma = sigma;
packet.theta_dot = theta_dot;
packet.omega_dot = omega_dot;
packet.sigma_dot = sigma_dot;
packet.f = f;
packet.f_dot = f_dot;
packet.u = u;
packet.axis = axis;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ADAP_TUNING_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_ADAP_TUNING;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ADAP_TUNING_MIN_LEN, MAVLINK_MSG_ID_ADAP_TUNING_LEN, MAVLINK_MSG_ID_ADAP_TUNING_CRC);
}
/**
* @brief Pack a adap_tuning message on a channel
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param axis Axis.
* @param desired [deg/s] Desired rate.
* @param achieved [deg/s] Achieved rate.
* @param error Error between model and vehicle.
* @param theta Theta estimated state predictor.
* @param omega Omega estimated state predictor.
* @param sigma Sigma estimated state predictor.
* @param theta_dot Theta derivative.
* @param omega_dot Omega derivative.
* @param sigma_dot Sigma derivative.
* @param f Projection operator value.
* @param f_dot Projection operator derivative.
* @param u u adaptive controlled output command.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_adap_tuning_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint8_t axis,float desired,float achieved,float error,float theta,float omega,float sigma,float theta_dot,float omega_dot,float sigma_dot,float f,float f_dot,float u)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_ADAP_TUNING_LEN];
_mav_put_float(buf, 0, desired);
_mav_put_float(buf, 4, achieved);
_mav_put_float(buf, 8, error);
_mav_put_float(buf, 12, theta);
_mav_put_float(buf, 16, omega);
_mav_put_float(buf, 20, sigma);
_mav_put_float(buf, 24, theta_dot);
_mav_put_float(buf, 28, omega_dot);
_mav_put_float(buf, 32, sigma_dot);
_mav_put_float(buf, 36, f);
_mav_put_float(buf, 40, f_dot);
_mav_put_float(buf, 44, u);
_mav_put_uint8_t(buf, 48, axis);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ADAP_TUNING_LEN);
#else
mavlink_adap_tuning_t packet;
packet.desired = desired;
packet.achieved = achieved;
packet.error = error;
packet.theta = theta;
packet.omega = omega;
packet.sigma = sigma;
packet.theta_dot = theta_dot;
packet.omega_dot = omega_dot;
packet.sigma_dot = sigma_dot;
packet.f = f;
packet.f_dot = f_dot;
packet.u = u;
packet.axis = axis;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ADAP_TUNING_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_ADAP_TUNING;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ADAP_TUNING_MIN_LEN, MAVLINK_MSG_ID_ADAP_TUNING_LEN, MAVLINK_MSG_ID_ADAP_TUNING_CRC);
}
/**
* @brief Encode a adap_tuning struct
*
* @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 adap_tuning C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_adap_tuning_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_adap_tuning_t* adap_tuning)
{
return mavlink_msg_adap_tuning_pack(system_id, component_id, msg, adap_tuning->axis, adap_tuning->desired, adap_tuning->achieved, adap_tuning->error, adap_tuning->theta, adap_tuning->omega, adap_tuning->sigma, adap_tuning->theta_dot, adap_tuning->omega_dot, adap_tuning->sigma_dot, adap_tuning->f, adap_tuning->f_dot, adap_tuning->u);
}
/**
* @brief Encode a adap_tuning struct on a channel
*
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param adap_tuning C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_adap_tuning_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_adap_tuning_t* adap_tuning)
{
return mavlink_msg_adap_tuning_pack_chan(system_id, component_id, chan, msg, adap_tuning->axis, adap_tuning->desired, adap_tuning->achieved, adap_tuning->error, adap_tuning->theta, adap_tuning->omega, adap_tuning->sigma, adap_tuning->theta_dot, adap_tuning->omega_dot, adap_tuning->sigma_dot, adap_tuning->f, adap_tuning->f_dot, adap_tuning->u);
}
/**
* @brief Send a adap_tuning message
* @param chan MAVLink channel to send the message
*
* @param axis Axis.
* @param desired [deg/s] Desired rate.
* @param achieved [deg/s] Achieved rate.
* @param error Error between model and vehicle.
* @param theta Theta estimated state predictor.
* @param omega Omega estimated state predictor.
* @param sigma Sigma estimated state predictor.
* @param theta_dot Theta derivative.
* @param omega_dot Omega derivative.
* @param sigma_dot Sigma derivative.
* @param f Projection operator value.
* @param f_dot Projection operator derivative.
* @param u u adaptive controlled output command.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_adap_tuning_send(mavlink_channel_t chan, uint8_t axis, float desired, float achieved, float error, float theta, float omega, float sigma, float theta_dot, float omega_dot, float sigma_dot, float f, float f_dot, float u)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_ADAP_TUNING_LEN];
_mav_put_float(buf, 0, desired);
_mav_put_float(buf, 4, achieved);
_mav_put_float(buf, 8, error);
_mav_put_float(buf, 12, theta);
_mav_put_float(buf, 16, omega);
_mav_put_float(buf, 20, sigma);
_mav_put_float(buf, 24, theta_dot);
_mav_put_float(buf, 28, omega_dot);
_mav_put_float(buf, 32, sigma_dot);
_mav_put_float(buf, 36, f);
_mav_put_float(buf, 40, f_dot);
_mav_put_float(buf, 44, u);
_mav_put_uint8_t(buf, 48, axis);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADAP_TUNING, buf, MAVLINK_MSG_ID_ADAP_TUNING_MIN_LEN, MAVLINK_MSG_ID_ADAP_TUNING_LEN, MAVLINK_MSG_ID_ADAP_TUNING_CRC);
#else
mavlink_adap_tuning_t packet;
packet.desired = desired;
packet.achieved = achieved;
packet.error = error;
packet.theta = theta;
packet.omega = omega;
packet.sigma = sigma;
packet.theta_dot = theta_dot;
packet.omega_dot = omega_dot;
packet.sigma_dot = sigma_dot;
packet.f = f;
packet.f_dot = f_dot;
packet.u = u;
packet.axis = axis;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADAP_TUNING, (const char *)&packet, MAVLINK_MSG_ID_ADAP_TUNING_MIN_LEN, MAVLINK_MSG_ID_ADAP_TUNING_LEN, MAVLINK_MSG_ID_ADAP_TUNING_CRC);
#endif
}
/**
* @brief Send a adap_tuning message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_adap_tuning_send_struct(mavlink_channel_t chan, const mavlink_adap_tuning_t* adap_tuning)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_adap_tuning_send(chan, adap_tuning->axis, adap_tuning->desired, adap_tuning->achieved, adap_tuning->error, adap_tuning->theta, adap_tuning->omega, adap_tuning->sigma, adap_tuning->theta_dot, adap_tuning->omega_dot, adap_tuning->sigma_dot, adap_tuning->f, adap_tuning->f_dot, adap_tuning->u);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADAP_TUNING, (const char *)adap_tuning, MAVLINK_MSG_ID_ADAP_TUNING_MIN_LEN, MAVLINK_MSG_ID_ADAP_TUNING_LEN, MAVLINK_MSG_ID_ADAP_TUNING_CRC);
#endif
}
#if MAVLINK_MSG_ID_ADAP_TUNING_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_adap_tuning_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t axis, float desired, float achieved, float error, float theta, float omega, float sigma, float theta_dot, float omega_dot, float sigma_dot, float f, float f_dot, float u)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_float(buf, 0, desired);
_mav_put_float(buf, 4, achieved);
_mav_put_float(buf, 8, error);
_mav_put_float(buf, 12, theta);
_mav_put_float(buf, 16, omega);
_mav_put_float(buf, 20, sigma);
_mav_put_float(buf, 24, theta_dot);
_mav_put_float(buf, 28, omega_dot);
_mav_put_float(buf, 32, sigma_dot);
_mav_put_float(buf, 36, f);
_mav_put_float(buf, 40, f_dot);
_mav_put_float(buf, 44, u);
_mav_put_uint8_t(buf, 48, axis);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADAP_TUNING, buf, MAVLINK_MSG_ID_ADAP_TUNING_MIN_LEN, MAVLINK_MSG_ID_ADAP_TUNING_LEN, MAVLINK_MSG_ID_ADAP_TUNING_CRC);
#else
mavlink_adap_tuning_t *packet = (mavlink_adap_tuning_t *)msgbuf;
packet->desired = desired;
packet->achieved = achieved;
packet->error = error;
packet->theta = theta;
packet->omega = omega;
packet->sigma = sigma;
packet->theta_dot = theta_dot;
packet->omega_dot = omega_dot;
packet->sigma_dot = sigma_dot;
packet->f = f;
packet->f_dot = f_dot;
packet->u = u;
packet->axis = axis;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADAP_TUNING, (const char *)packet, MAVLINK_MSG_ID_ADAP_TUNING_MIN_LEN, MAVLINK_MSG_ID_ADAP_TUNING_LEN, MAVLINK_MSG_ID_ADAP_TUNING_CRC);
#endif
}
#endif
#endif
// MESSAGE ADAP_TUNING UNPACKING
/**
* @brief Get field axis from adap_tuning message
*
* @return Axis.
*/
static inline uint8_t mavlink_msg_adap_tuning_get_axis(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 48);
}
/**
* @brief Get field desired from adap_tuning message
*
* @return [deg/s] Desired rate.
*/
static inline float mavlink_msg_adap_tuning_get_desired(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 0);
}
/**
* @brief Get field achieved from adap_tuning message
*
* @return [deg/s] Achieved rate.
*/
static inline float mavlink_msg_adap_tuning_get_achieved(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 4);
}
/**
* @brief Get field error from adap_tuning message
*
* @return Error between model and vehicle.
*/
static inline float mavlink_msg_adap_tuning_get_error(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
/**
* @brief Get field theta from adap_tuning message
*
* @return Theta estimated state predictor.
*/
static inline float mavlink_msg_adap_tuning_get_theta(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
/**
* @brief Get field omega from adap_tuning message
*
* @return Omega estimated state predictor.
*/
static inline float mavlink_msg_adap_tuning_get_omega(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 16);
}
/**
* @brief Get field sigma from adap_tuning message
*
* @return Sigma estimated state predictor.
*/
static inline float mavlink_msg_adap_tuning_get_sigma(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 20);
}
/**
* @brief Get field theta_dot from adap_tuning message
*
* @return Theta derivative.
*/
static inline float mavlink_msg_adap_tuning_get_theta_dot(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 24);
}
/**
* @brief Get field omega_dot from adap_tuning message
*
* @return Omega derivative.
*/
static inline float mavlink_msg_adap_tuning_get_omega_dot(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 28);
}
/**
* @brief Get field sigma_dot from adap_tuning message
*
* @return Sigma derivative.
*/
static inline float mavlink_msg_adap_tuning_get_sigma_dot(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 32);
}
/**
* @brief Get field f from adap_tuning message
*
* @return Projection operator value.
*/
static inline float mavlink_msg_adap_tuning_get_f(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 36);
}
/**
* @brief Get field f_dot from adap_tuning message
*
* @return Projection operator derivative.
*/
static inline float mavlink_msg_adap_tuning_get_f_dot(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 40);
}
/**
* @brief Get field u from adap_tuning message
*
* @return u adaptive controlled output command.
*/
static inline float mavlink_msg_adap_tuning_get_u(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 44);
}
/**
* @brief Decode a adap_tuning message into a struct
*
* @param msg The message to decode
* @param adap_tuning C-struct to decode the message contents into
*/
static inline void mavlink_msg_adap_tuning_decode(const mavlink_message_t* msg, mavlink_adap_tuning_t* adap_tuning)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
adap_tuning->desired = mavlink_msg_adap_tuning_get_desired(msg);
adap_tuning->achieved = mavlink_msg_adap_tuning_get_achieved(msg);
adap_tuning->error = mavlink_msg_adap_tuning_get_error(msg);
adap_tuning->theta = mavlink_msg_adap_tuning_get_theta(msg);
adap_tuning->omega = mavlink_msg_adap_tuning_get_omega(msg);
adap_tuning->sigma = mavlink_msg_adap_tuning_get_sigma(msg);
adap_tuning->theta_dot = mavlink_msg_adap_tuning_get_theta_dot(msg);
adap_tuning->omega_dot = mavlink_msg_adap_tuning_get_omega_dot(msg);
adap_tuning->sigma_dot = mavlink_msg_adap_tuning_get_sigma_dot(msg);
adap_tuning->f = mavlink_msg_adap_tuning_get_f(msg);
adap_tuning->f_dot = mavlink_msg_adap_tuning_get_f_dot(msg);
adap_tuning->u = mavlink_msg_adap_tuning_get_u(msg);
adap_tuning->axis = mavlink_msg_adap_tuning_get_axis(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_ADAP_TUNING_LEN? msg->len : MAVLINK_MSG_ID_ADAP_TUNING_LEN;
memset(adap_tuning, 0, MAVLINK_MSG_ID_ADAP_TUNING_LEN);
memcpy(adap_tuning, _MAV_PAYLOAD(msg), len);
#endif
}

View File

@@ -0,0 +1,363 @@
#pragma once
// MESSAGE AHRS PACKING
#define MAVLINK_MSG_ID_AHRS 163
MAVPACKED(
typedef struct __mavlink_ahrs_t {
float omegaIx; /*< [rad/s] X gyro drift estimate.*/
float omegaIy; /*< [rad/s] Y gyro drift estimate.*/
float omegaIz; /*< [rad/s] Z gyro drift estimate.*/
float accel_weight; /*< Average accel_weight.*/
float renorm_val; /*< Average renormalisation value.*/
float error_rp; /*< Average error_roll_pitch value.*/
float error_yaw; /*< Average error_yaw value.*/
}) mavlink_ahrs_t;
#define MAVLINK_MSG_ID_AHRS_LEN 28
#define MAVLINK_MSG_ID_AHRS_MIN_LEN 28
#define MAVLINK_MSG_ID_163_LEN 28
#define MAVLINK_MSG_ID_163_MIN_LEN 28
#define MAVLINK_MSG_ID_AHRS_CRC 127
#define MAVLINK_MSG_ID_163_CRC 127
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_AHRS { \
163, \
"AHRS", \
7, \
{ { "omegaIx", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_ahrs_t, omegaIx) }, \
{ "omegaIy", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_ahrs_t, omegaIy) }, \
{ "omegaIz", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_ahrs_t, omegaIz) }, \
{ "accel_weight", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_ahrs_t, accel_weight) }, \
{ "renorm_val", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_ahrs_t, renorm_val) }, \
{ "error_rp", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_ahrs_t, error_rp) }, \
{ "error_yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_ahrs_t, error_yaw) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_AHRS { \
"AHRS", \
7, \
{ { "omegaIx", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_ahrs_t, omegaIx) }, \
{ "omegaIy", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_ahrs_t, omegaIy) }, \
{ "omegaIz", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_ahrs_t, omegaIz) }, \
{ "accel_weight", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_ahrs_t, accel_weight) }, \
{ "renorm_val", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_ahrs_t, renorm_val) }, \
{ "error_rp", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_ahrs_t, error_rp) }, \
{ "error_yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_ahrs_t, error_yaw) }, \
} \
}
#endif
/**
* @brief Pack a ahrs 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 omegaIx [rad/s] X gyro drift estimate.
* @param omegaIy [rad/s] Y gyro drift estimate.
* @param omegaIz [rad/s] Z gyro drift estimate.
* @param accel_weight Average accel_weight.
* @param renorm_val Average renormalisation value.
* @param error_rp Average error_roll_pitch value.
* @param error_yaw Average error_yaw value.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_ahrs_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
float omegaIx, float omegaIy, float omegaIz, float accel_weight, float renorm_val, float error_rp, float error_yaw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_AHRS_LEN];
_mav_put_float(buf, 0, omegaIx);
_mav_put_float(buf, 4, omegaIy);
_mav_put_float(buf, 8, omegaIz);
_mav_put_float(buf, 12, accel_weight);
_mav_put_float(buf, 16, renorm_val);
_mav_put_float(buf, 20, error_rp);
_mav_put_float(buf, 24, error_yaw);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AHRS_LEN);
#else
mavlink_ahrs_t packet;
packet.omegaIx = omegaIx;
packet.omegaIy = omegaIy;
packet.omegaIz = omegaIz;
packet.accel_weight = accel_weight;
packet.renorm_val = renorm_val;
packet.error_rp = error_rp;
packet.error_yaw = error_yaw;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AHRS_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_AHRS;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_AHRS_MIN_LEN, MAVLINK_MSG_ID_AHRS_LEN, MAVLINK_MSG_ID_AHRS_CRC);
}
/**
* @brief Pack a ahrs message on a channel
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param omegaIx [rad/s] X gyro drift estimate.
* @param omegaIy [rad/s] Y gyro drift estimate.
* @param omegaIz [rad/s] Z gyro drift estimate.
* @param accel_weight Average accel_weight.
* @param renorm_val Average renormalisation value.
* @param error_rp Average error_roll_pitch value.
* @param error_yaw Average error_yaw value.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_ahrs_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
float omegaIx,float omegaIy,float omegaIz,float accel_weight,float renorm_val,float error_rp,float error_yaw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_AHRS_LEN];
_mav_put_float(buf, 0, omegaIx);
_mav_put_float(buf, 4, omegaIy);
_mav_put_float(buf, 8, omegaIz);
_mav_put_float(buf, 12, accel_weight);
_mav_put_float(buf, 16, renorm_val);
_mav_put_float(buf, 20, error_rp);
_mav_put_float(buf, 24, error_yaw);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AHRS_LEN);
#else
mavlink_ahrs_t packet;
packet.omegaIx = omegaIx;
packet.omegaIy = omegaIy;
packet.omegaIz = omegaIz;
packet.accel_weight = accel_weight;
packet.renorm_val = renorm_val;
packet.error_rp = error_rp;
packet.error_yaw = error_yaw;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AHRS_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_AHRS;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_AHRS_MIN_LEN, MAVLINK_MSG_ID_AHRS_LEN, MAVLINK_MSG_ID_AHRS_CRC);
}
/**
* @brief Encode a ahrs struct
*
* @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 ahrs C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_ahrs_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_ahrs_t* ahrs)
{
return mavlink_msg_ahrs_pack(system_id, component_id, msg, ahrs->omegaIx, ahrs->omegaIy, ahrs->omegaIz, ahrs->accel_weight, ahrs->renorm_val, ahrs->error_rp, ahrs->error_yaw);
}
/**
* @brief Encode a ahrs struct on a channel
*
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param ahrs C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_ahrs_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_ahrs_t* ahrs)
{
return mavlink_msg_ahrs_pack_chan(system_id, component_id, chan, msg, ahrs->omegaIx, ahrs->omegaIy, ahrs->omegaIz, ahrs->accel_weight, ahrs->renorm_val, ahrs->error_rp, ahrs->error_yaw);
}
/**
* @brief Send a ahrs message
* @param chan MAVLink channel to send the message
*
* @param omegaIx [rad/s] X gyro drift estimate.
* @param omegaIy [rad/s] Y gyro drift estimate.
* @param omegaIz [rad/s] Z gyro drift estimate.
* @param accel_weight Average accel_weight.
* @param renorm_val Average renormalisation value.
* @param error_rp Average error_roll_pitch value.
* @param error_yaw Average error_yaw value.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_ahrs_send(mavlink_channel_t chan, float omegaIx, float omegaIy, float omegaIz, float accel_weight, float renorm_val, float error_rp, float error_yaw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_AHRS_LEN];
_mav_put_float(buf, 0, omegaIx);
_mav_put_float(buf, 4, omegaIy);
_mav_put_float(buf, 8, omegaIz);
_mav_put_float(buf, 12, accel_weight);
_mav_put_float(buf, 16, renorm_val);
_mav_put_float(buf, 20, error_rp);
_mav_put_float(buf, 24, error_yaw);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AHRS, buf, MAVLINK_MSG_ID_AHRS_MIN_LEN, MAVLINK_MSG_ID_AHRS_LEN, MAVLINK_MSG_ID_AHRS_CRC);
#else
mavlink_ahrs_t packet;
packet.omegaIx = omegaIx;
packet.omegaIy = omegaIy;
packet.omegaIz = omegaIz;
packet.accel_weight = accel_weight;
packet.renorm_val = renorm_val;
packet.error_rp = error_rp;
packet.error_yaw = error_yaw;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AHRS, (const char *)&packet, MAVLINK_MSG_ID_AHRS_MIN_LEN, MAVLINK_MSG_ID_AHRS_LEN, MAVLINK_MSG_ID_AHRS_CRC);
#endif
}
/**
* @brief Send a ahrs message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_ahrs_send_struct(mavlink_channel_t chan, const mavlink_ahrs_t* ahrs)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_ahrs_send(chan, ahrs->omegaIx, ahrs->omegaIy, ahrs->omegaIz, ahrs->accel_weight, ahrs->renorm_val, ahrs->error_rp, ahrs->error_yaw);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AHRS, (const char *)ahrs, MAVLINK_MSG_ID_AHRS_MIN_LEN, MAVLINK_MSG_ID_AHRS_LEN, MAVLINK_MSG_ID_AHRS_CRC);
#endif
}
#if MAVLINK_MSG_ID_AHRS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_ahrs_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float omegaIx, float omegaIy, float omegaIz, float accel_weight, float renorm_val, float error_rp, float error_yaw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_float(buf, 0, omegaIx);
_mav_put_float(buf, 4, omegaIy);
_mav_put_float(buf, 8, omegaIz);
_mav_put_float(buf, 12, accel_weight);
_mav_put_float(buf, 16, renorm_val);
_mav_put_float(buf, 20, error_rp);
_mav_put_float(buf, 24, error_yaw);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AHRS, buf, MAVLINK_MSG_ID_AHRS_MIN_LEN, MAVLINK_MSG_ID_AHRS_LEN, MAVLINK_MSG_ID_AHRS_CRC);
#else
mavlink_ahrs_t *packet = (mavlink_ahrs_t *)msgbuf;
packet->omegaIx = omegaIx;
packet->omegaIy = omegaIy;
packet->omegaIz = omegaIz;
packet->accel_weight = accel_weight;
packet->renorm_val = renorm_val;
packet->error_rp = error_rp;
packet->error_yaw = error_yaw;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AHRS, (const char *)packet, MAVLINK_MSG_ID_AHRS_MIN_LEN, MAVLINK_MSG_ID_AHRS_LEN, MAVLINK_MSG_ID_AHRS_CRC);
#endif
}
#endif
#endif
// MESSAGE AHRS UNPACKING
/**
* @brief Get field omegaIx from ahrs message
*
* @return [rad/s] X gyro drift estimate.
*/
static inline float mavlink_msg_ahrs_get_omegaIx(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 0);
}
/**
* @brief Get field omegaIy from ahrs message
*
* @return [rad/s] Y gyro drift estimate.
*/
static inline float mavlink_msg_ahrs_get_omegaIy(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 4);
}
/**
* @brief Get field omegaIz from ahrs message
*
* @return [rad/s] Z gyro drift estimate.
*/
static inline float mavlink_msg_ahrs_get_omegaIz(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
/**
* @brief Get field accel_weight from ahrs message
*
* @return Average accel_weight.
*/
static inline float mavlink_msg_ahrs_get_accel_weight(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
/**
* @brief Get field renorm_val from ahrs message
*
* @return Average renormalisation value.
*/
static inline float mavlink_msg_ahrs_get_renorm_val(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 16);
}
/**
* @brief Get field error_rp from ahrs message
*
* @return Average error_roll_pitch value.
*/
static inline float mavlink_msg_ahrs_get_error_rp(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 20);
}
/**
* @brief Get field error_yaw from ahrs message
*
* @return Average error_yaw value.
*/
static inline float mavlink_msg_ahrs_get_error_yaw(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 24);
}
/**
* @brief Decode a ahrs message into a struct
*
* @param msg The message to decode
* @param ahrs C-struct to decode the message contents into
*/
static inline void mavlink_msg_ahrs_decode(const mavlink_message_t* msg, mavlink_ahrs_t* ahrs)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
ahrs->omegaIx = mavlink_msg_ahrs_get_omegaIx(msg);
ahrs->omegaIy = mavlink_msg_ahrs_get_omegaIy(msg);
ahrs->omegaIz = mavlink_msg_ahrs_get_omegaIz(msg);
ahrs->accel_weight = mavlink_msg_ahrs_get_accel_weight(msg);
ahrs->renorm_val = mavlink_msg_ahrs_get_renorm_val(msg);
ahrs->error_rp = mavlink_msg_ahrs_get_error_rp(msg);
ahrs->error_yaw = mavlink_msg_ahrs_get_error_yaw(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_AHRS_LEN? msg->len : MAVLINK_MSG_ID_AHRS_LEN;
memset(ahrs, 0, MAVLINK_MSG_ID_AHRS_LEN);
memcpy(ahrs, _MAV_PAYLOAD(msg), len);
#endif
}

View File

@@ -0,0 +1,338 @@
#pragma once
// MESSAGE AHRS2 PACKING
#define MAVLINK_MSG_ID_AHRS2 178
MAVPACKED(
typedef struct __mavlink_ahrs2_t {
float roll; /*< [rad] Roll angle.*/
float pitch; /*< [rad] Pitch angle.*/
float yaw; /*< [rad] Yaw angle.*/
float altitude; /*< [m] Altitude (MSL).*/
int32_t lat; /*< [degE7] Latitude.*/
int32_t lng; /*< [degE7] Longitude.*/
}) mavlink_ahrs2_t;
#define MAVLINK_MSG_ID_AHRS2_LEN 24
#define MAVLINK_MSG_ID_AHRS2_MIN_LEN 24
#define MAVLINK_MSG_ID_178_LEN 24
#define MAVLINK_MSG_ID_178_MIN_LEN 24
#define MAVLINK_MSG_ID_AHRS2_CRC 47
#define MAVLINK_MSG_ID_178_CRC 47
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_AHRS2 { \
178, \
"AHRS2", \
6, \
{ { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_ahrs2_t, roll) }, \
{ "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_ahrs2_t, pitch) }, \
{ "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_ahrs2_t, yaw) }, \
{ "altitude", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_ahrs2_t, altitude) }, \
{ "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_ahrs2_t, lat) }, \
{ "lng", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_ahrs2_t, lng) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_AHRS2 { \
"AHRS2", \
6, \
{ { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_ahrs2_t, roll) }, \
{ "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_ahrs2_t, pitch) }, \
{ "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_ahrs2_t, yaw) }, \
{ "altitude", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_ahrs2_t, altitude) }, \
{ "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_ahrs2_t, lat) }, \
{ "lng", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_ahrs2_t, lng) }, \
} \
}
#endif
/**
* @brief Pack a ahrs2 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 roll [rad] Roll angle.
* @param pitch [rad] Pitch angle.
* @param yaw [rad] Yaw angle.
* @param altitude [m] Altitude (MSL).
* @param lat [degE7] Latitude.
* @param lng [degE7] Longitude.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_ahrs2_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
float roll, float pitch, float yaw, float altitude, int32_t lat, int32_t lng)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_AHRS2_LEN];
_mav_put_float(buf, 0, roll);
_mav_put_float(buf, 4, pitch);
_mav_put_float(buf, 8, yaw);
_mav_put_float(buf, 12, altitude);
_mav_put_int32_t(buf, 16, lat);
_mav_put_int32_t(buf, 20, lng);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AHRS2_LEN);
#else
mavlink_ahrs2_t packet;
packet.roll = roll;
packet.pitch = pitch;
packet.yaw = yaw;
packet.altitude = altitude;
packet.lat = lat;
packet.lng = lng;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AHRS2_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_AHRS2;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_AHRS2_MIN_LEN, MAVLINK_MSG_ID_AHRS2_LEN, MAVLINK_MSG_ID_AHRS2_CRC);
}
/**
* @brief Pack a ahrs2 message on a channel
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param roll [rad] Roll angle.
* @param pitch [rad] Pitch angle.
* @param yaw [rad] Yaw angle.
* @param altitude [m] Altitude (MSL).
* @param lat [degE7] Latitude.
* @param lng [degE7] Longitude.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_ahrs2_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
float roll,float pitch,float yaw,float altitude,int32_t lat,int32_t lng)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_AHRS2_LEN];
_mav_put_float(buf, 0, roll);
_mav_put_float(buf, 4, pitch);
_mav_put_float(buf, 8, yaw);
_mav_put_float(buf, 12, altitude);
_mav_put_int32_t(buf, 16, lat);
_mav_put_int32_t(buf, 20, lng);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AHRS2_LEN);
#else
mavlink_ahrs2_t packet;
packet.roll = roll;
packet.pitch = pitch;
packet.yaw = yaw;
packet.altitude = altitude;
packet.lat = lat;
packet.lng = lng;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AHRS2_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_AHRS2;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_AHRS2_MIN_LEN, MAVLINK_MSG_ID_AHRS2_LEN, MAVLINK_MSG_ID_AHRS2_CRC);
}
/**
* @brief Encode a ahrs2 struct
*
* @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 ahrs2 C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_ahrs2_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_ahrs2_t* ahrs2)
{
return mavlink_msg_ahrs2_pack(system_id, component_id, msg, ahrs2->roll, ahrs2->pitch, ahrs2->yaw, ahrs2->altitude, ahrs2->lat, ahrs2->lng);
}
/**
* @brief Encode a ahrs2 struct on a channel
*
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param ahrs2 C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_ahrs2_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_ahrs2_t* ahrs2)
{
return mavlink_msg_ahrs2_pack_chan(system_id, component_id, chan, msg, ahrs2->roll, ahrs2->pitch, ahrs2->yaw, ahrs2->altitude, ahrs2->lat, ahrs2->lng);
}
/**
* @brief Send a ahrs2 message
* @param chan MAVLink channel to send the message
*
* @param roll [rad] Roll angle.
* @param pitch [rad] Pitch angle.
* @param yaw [rad] Yaw angle.
* @param altitude [m] Altitude (MSL).
* @param lat [degE7] Latitude.
* @param lng [degE7] Longitude.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_ahrs2_send(mavlink_channel_t chan, float roll, float pitch, float yaw, float altitude, int32_t lat, int32_t lng)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_AHRS2_LEN];
_mav_put_float(buf, 0, roll);
_mav_put_float(buf, 4, pitch);
_mav_put_float(buf, 8, yaw);
_mav_put_float(buf, 12, altitude);
_mav_put_int32_t(buf, 16, lat);
_mav_put_int32_t(buf, 20, lng);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AHRS2, buf, MAVLINK_MSG_ID_AHRS2_MIN_LEN, MAVLINK_MSG_ID_AHRS2_LEN, MAVLINK_MSG_ID_AHRS2_CRC);
#else
mavlink_ahrs2_t packet;
packet.roll = roll;
packet.pitch = pitch;
packet.yaw = yaw;
packet.altitude = altitude;
packet.lat = lat;
packet.lng = lng;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AHRS2, (const char *)&packet, MAVLINK_MSG_ID_AHRS2_MIN_LEN, MAVLINK_MSG_ID_AHRS2_LEN, MAVLINK_MSG_ID_AHRS2_CRC);
#endif
}
/**
* @brief Send a ahrs2 message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_ahrs2_send_struct(mavlink_channel_t chan, const mavlink_ahrs2_t* ahrs2)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_ahrs2_send(chan, ahrs2->roll, ahrs2->pitch, ahrs2->yaw, ahrs2->altitude, ahrs2->lat, ahrs2->lng);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AHRS2, (const char *)ahrs2, MAVLINK_MSG_ID_AHRS2_MIN_LEN, MAVLINK_MSG_ID_AHRS2_LEN, MAVLINK_MSG_ID_AHRS2_CRC);
#endif
}
#if MAVLINK_MSG_ID_AHRS2_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_ahrs2_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float roll, float pitch, float yaw, float altitude, int32_t lat, int32_t lng)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_float(buf, 0, roll);
_mav_put_float(buf, 4, pitch);
_mav_put_float(buf, 8, yaw);
_mav_put_float(buf, 12, altitude);
_mav_put_int32_t(buf, 16, lat);
_mav_put_int32_t(buf, 20, lng);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AHRS2, buf, MAVLINK_MSG_ID_AHRS2_MIN_LEN, MAVLINK_MSG_ID_AHRS2_LEN, MAVLINK_MSG_ID_AHRS2_CRC);
#else
mavlink_ahrs2_t *packet = (mavlink_ahrs2_t *)msgbuf;
packet->roll = roll;
packet->pitch = pitch;
packet->yaw = yaw;
packet->altitude = altitude;
packet->lat = lat;
packet->lng = lng;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AHRS2, (const char *)packet, MAVLINK_MSG_ID_AHRS2_MIN_LEN, MAVLINK_MSG_ID_AHRS2_LEN, MAVLINK_MSG_ID_AHRS2_CRC);
#endif
}
#endif
#endif
// MESSAGE AHRS2 UNPACKING
/**
* @brief Get field roll from ahrs2 message
*
* @return [rad] Roll angle.
*/
static inline float mavlink_msg_ahrs2_get_roll(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 0);
}
/**
* @brief Get field pitch from ahrs2 message
*
* @return [rad] Pitch angle.
*/
static inline float mavlink_msg_ahrs2_get_pitch(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 4);
}
/**
* @brief Get field yaw from ahrs2 message
*
* @return [rad] Yaw angle.
*/
static inline float mavlink_msg_ahrs2_get_yaw(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
/**
* @brief Get field altitude from ahrs2 message
*
* @return [m] Altitude (MSL).
*/
static inline float mavlink_msg_ahrs2_get_altitude(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
/**
* @brief Get field lat from ahrs2 message
*
* @return [degE7] Latitude.
*/
static inline int32_t mavlink_msg_ahrs2_get_lat(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 16);
}
/**
* @brief Get field lng from ahrs2 message
*
* @return [degE7] Longitude.
*/
static inline int32_t mavlink_msg_ahrs2_get_lng(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 20);
}
/**
* @brief Decode a ahrs2 message into a struct
*
* @param msg The message to decode
* @param ahrs2 C-struct to decode the message contents into
*/
static inline void mavlink_msg_ahrs2_decode(const mavlink_message_t* msg, mavlink_ahrs2_t* ahrs2)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
ahrs2->roll = mavlink_msg_ahrs2_get_roll(msg);
ahrs2->pitch = mavlink_msg_ahrs2_get_pitch(msg);
ahrs2->yaw = mavlink_msg_ahrs2_get_yaw(msg);
ahrs2->altitude = mavlink_msg_ahrs2_get_altitude(msg);
ahrs2->lat = mavlink_msg_ahrs2_get_lat(msg);
ahrs2->lng = mavlink_msg_ahrs2_get_lng(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_AHRS2_LEN? msg->len : MAVLINK_MSG_ID_AHRS2_LEN;
memset(ahrs2, 0, MAVLINK_MSG_ID_AHRS2_LEN);
memcpy(ahrs2, _MAV_PAYLOAD(msg), len);
#endif
}

View File

@@ -0,0 +1,438 @@
#pragma once
// MESSAGE AHRS3 PACKING
#define MAVLINK_MSG_ID_AHRS3 182
MAVPACKED(
typedef struct __mavlink_ahrs3_t {
float roll; /*< [rad] Roll angle.*/
float pitch; /*< [rad] Pitch angle.*/
float yaw; /*< [rad] Yaw angle.*/
float altitude; /*< [m] Altitude (MSL).*/
int32_t lat; /*< [degE7] Latitude.*/
int32_t lng; /*< [degE7] Longitude.*/
float v1; /*< Test variable1.*/
float v2; /*< Test variable2.*/
float v3; /*< Test variable3.*/
float v4; /*< Test variable4.*/
}) mavlink_ahrs3_t;
#define MAVLINK_MSG_ID_AHRS3_LEN 40
#define MAVLINK_MSG_ID_AHRS3_MIN_LEN 40
#define MAVLINK_MSG_ID_182_LEN 40
#define MAVLINK_MSG_ID_182_MIN_LEN 40
#define MAVLINK_MSG_ID_AHRS3_CRC 229
#define MAVLINK_MSG_ID_182_CRC 229
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_AHRS3 { \
182, \
"AHRS3", \
10, \
{ { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_ahrs3_t, roll) }, \
{ "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_ahrs3_t, pitch) }, \
{ "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_ahrs3_t, yaw) }, \
{ "altitude", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_ahrs3_t, altitude) }, \
{ "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_ahrs3_t, lat) }, \
{ "lng", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_ahrs3_t, lng) }, \
{ "v1", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_ahrs3_t, v1) }, \
{ "v2", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_ahrs3_t, v2) }, \
{ "v3", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_ahrs3_t, v3) }, \
{ "v4", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_ahrs3_t, v4) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_AHRS3 { \
"AHRS3", \
10, \
{ { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_ahrs3_t, roll) }, \
{ "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_ahrs3_t, pitch) }, \
{ "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_ahrs3_t, yaw) }, \
{ "altitude", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_ahrs3_t, altitude) }, \
{ "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_ahrs3_t, lat) }, \
{ "lng", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_ahrs3_t, lng) }, \
{ "v1", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_ahrs3_t, v1) }, \
{ "v2", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_ahrs3_t, v2) }, \
{ "v3", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_ahrs3_t, v3) }, \
{ "v4", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_ahrs3_t, v4) }, \
} \
}
#endif
/**
* @brief Pack a ahrs3 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 roll [rad] Roll angle.
* @param pitch [rad] Pitch angle.
* @param yaw [rad] Yaw angle.
* @param altitude [m] Altitude (MSL).
* @param lat [degE7] Latitude.
* @param lng [degE7] Longitude.
* @param v1 Test variable1.
* @param v2 Test variable2.
* @param v3 Test variable3.
* @param v4 Test variable4.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_ahrs3_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
float roll, float pitch, float yaw, float altitude, int32_t lat, int32_t lng, float v1, float v2, float v3, float v4)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_AHRS3_LEN];
_mav_put_float(buf, 0, roll);
_mav_put_float(buf, 4, pitch);
_mav_put_float(buf, 8, yaw);
_mav_put_float(buf, 12, altitude);
_mav_put_int32_t(buf, 16, lat);
_mav_put_int32_t(buf, 20, lng);
_mav_put_float(buf, 24, v1);
_mav_put_float(buf, 28, v2);
_mav_put_float(buf, 32, v3);
_mav_put_float(buf, 36, v4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AHRS3_LEN);
#else
mavlink_ahrs3_t packet;
packet.roll = roll;
packet.pitch = pitch;
packet.yaw = yaw;
packet.altitude = altitude;
packet.lat = lat;
packet.lng = lng;
packet.v1 = v1;
packet.v2 = v2;
packet.v3 = v3;
packet.v4 = v4;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AHRS3_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_AHRS3;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_AHRS3_MIN_LEN, MAVLINK_MSG_ID_AHRS3_LEN, MAVLINK_MSG_ID_AHRS3_CRC);
}
/**
* @brief Pack a ahrs3 message on a channel
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param roll [rad] Roll angle.
* @param pitch [rad] Pitch angle.
* @param yaw [rad] Yaw angle.
* @param altitude [m] Altitude (MSL).
* @param lat [degE7] Latitude.
* @param lng [degE7] Longitude.
* @param v1 Test variable1.
* @param v2 Test variable2.
* @param v3 Test variable3.
* @param v4 Test variable4.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_ahrs3_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
float roll,float pitch,float yaw,float altitude,int32_t lat,int32_t lng,float v1,float v2,float v3,float v4)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_AHRS3_LEN];
_mav_put_float(buf, 0, roll);
_mav_put_float(buf, 4, pitch);
_mav_put_float(buf, 8, yaw);
_mav_put_float(buf, 12, altitude);
_mav_put_int32_t(buf, 16, lat);
_mav_put_int32_t(buf, 20, lng);
_mav_put_float(buf, 24, v1);
_mav_put_float(buf, 28, v2);
_mav_put_float(buf, 32, v3);
_mav_put_float(buf, 36, v4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AHRS3_LEN);
#else
mavlink_ahrs3_t packet;
packet.roll = roll;
packet.pitch = pitch;
packet.yaw = yaw;
packet.altitude = altitude;
packet.lat = lat;
packet.lng = lng;
packet.v1 = v1;
packet.v2 = v2;
packet.v3 = v3;
packet.v4 = v4;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AHRS3_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_AHRS3;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_AHRS3_MIN_LEN, MAVLINK_MSG_ID_AHRS3_LEN, MAVLINK_MSG_ID_AHRS3_CRC);
}
/**
* @brief Encode a ahrs3 struct
*
* @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 ahrs3 C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_ahrs3_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_ahrs3_t* ahrs3)
{
return mavlink_msg_ahrs3_pack(system_id, component_id, msg, ahrs3->roll, ahrs3->pitch, ahrs3->yaw, ahrs3->altitude, ahrs3->lat, ahrs3->lng, ahrs3->v1, ahrs3->v2, ahrs3->v3, ahrs3->v4);
}
/**
* @brief Encode a ahrs3 struct on a channel
*
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param ahrs3 C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_ahrs3_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_ahrs3_t* ahrs3)
{
return mavlink_msg_ahrs3_pack_chan(system_id, component_id, chan, msg, ahrs3->roll, ahrs3->pitch, ahrs3->yaw, ahrs3->altitude, ahrs3->lat, ahrs3->lng, ahrs3->v1, ahrs3->v2, ahrs3->v3, ahrs3->v4);
}
/**
* @brief Send a ahrs3 message
* @param chan MAVLink channel to send the message
*
* @param roll [rad] Roll angle.
* @param pitch [rad] Pitch angle.
* @param yaw [rad] Yaw angle.
* @param altitude [m] Altitude (MSL).
* @param lat [degE7] Latitude.
* @param lng [degE7] Longitude.
* @param v1 Test variable1.
* @param v2 Test variable2.
* @param v3 Test variable3.
* @param v4 Test variable4.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_ahrs3_send(mavlink_channel_t chan, float roll, float pitch, float yaw, float altitude, int32_t lat, int32_t lng, float v1, float v2, float v3, float v4)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_AHRS3_LEN];
_mav_put_float(buf, 0, roll);
_mav_put_float(buf, 4, pitch);
_mav_put_float(buf, 8, yaw);
_mav_put_float(buf, 12, altitude);
_mav_put_int32_t(buf, 16, lat);
_mav_put_int32_t(buf, 20, lng);
_mav_put_float(buf, 24, v1);
_mav_put_float(buf, 28, v2);
_mav_put_float(buf, 32, v3);
_mav_put_float(buf, 36, v4);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AHRS3, buf, MAVLINK_MSG_ID_AHRS3_MIN_LEN, MAVLINK_MSG_ID_AHRS3_LEN, MAVLINK_MSG_ID_AHRS3_CRC);
#else
mavlink_ahrs3_t packet;
packet.roll = roll;
packet.pitch = pitch;
packet.yaw = yaw;
packet.altitude = altitude;
packet.lat = lat;
packet.lng = lng;
packet.v1 = v1;
packet.v2 = v2;
packet.v3 = v3;
packet.v4 = v4;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AHRS3, (const char *)&packet, MAVLINK_MSG_ID_AHRS3_MIN_LEN, MAVLINK_MSG_ID_AHRS3_LEN, MAVLINK_MSG_ID_AHRS3_CRC);
#endif
}
/**
* @brief Send a ahrs3 message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_ahrs3_send_struct(mavlink_channel_t chan, const mavlink_ahrs3_t* ahrs3)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_ahrs3_send(chan, ahrs3->roll, ahrs3->pitch, ahrs3->yaw, ahrs3->altitude, ahrs3->lat, ahrs3->lng, ahrs3->v1, ahrs3->v2, ahrs3->v3, ahrs3->v4);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AHRS3, (const char *)ahrs3, MAVLINK_MSG_ID_AHRS3_MIN_LEN, MAVLINK_MSG_ID_AHRS3_LEN, MAVLINK_MSG_ID_AHRS3_CRC);
#endif
}
#if MAVLINK_MSG_ID_AHRS3_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_ahrs3_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float roll, float pitch, float yaw, float altitude, int32_t lat, int32_t lng, float v1, float v2, float v3, float v4)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_float(buf, 0, roll);
_mav_put_float(buf, 4, pitch);
_mav_put_float(buf, 8, yaw);
_mav_put_float(buf, 12, altitude);
_mav_put_int32_t(buf, 16, lat);
_mav_put_int32_t(buf, 20, lng);
_mav_put_float(buf, 24, v1);
_mav_put_float(buf, 28, v2);
_mav_put_float(buf, 32, v3);
_mav_put_float(buf, 36, v4);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AHRS3, buf, MAVLINK_MSG_ID_AHRS3_MIN_LEN, MAVLINK_MSG_ID_AHRS3_LEN, MAVLINK_MSG_ID_AHRS3_CRC);
#else
mavlink_ahrs3_t *packet = (mavlink_ahrs3_t *)msgbuf;
packet->roll = roll;
packet->pitch = pitch;
packet->yaw = yaw;
packet->altitude = altitude;
packet->lat = lat;
packet->lng = lng;
packet->v1 = v1;
packet->v2 = v2;
packet->v3 = v3;
packet->v4 = v4;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AHRS3, (const char *)packet, MAVLINK_MSG_ID_AHRS3_MIN_LEN, MAVLINK_MSG_ID_AHRS3_LEN, MAVLINK_MSG_ID_AHRS3_CRC);
#endif
}
#endif
#endif
// MESSAGE AHRS3 UNPACKING
/**
* @brief Get field roll from ahrs3 message
*
* @return [rad] Roll angle.
*/
static inline float mavlink_msg_ahrs3_get_roll(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 0);
}
/**
* @brief Get field pitch from ahrs3 message
*
* @return [rad] Pitch angle.
*/
static inline float mavlink_msg_ahrs3_get_pitch(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 4);
}
/**
* @brief Get field yaw from ahrs3 message
*
* @return [rad] Yaw angle.
*/
static inline float mavlink_msg_ahrs3_get_yaw(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
/**
* @brief Get field altitude from ahrs3 message
*
* @return [m] Altitude (MSL).
*/
static inline float mavlink_msg_ahrs3_get_altitude(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
/**
* @brief Get field lat from ahrs3 message
*
* @return [degE7] Latitude.
*/
static inline int32_t mavlink_msg_ahrs3_get_lat(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 16);
}
/**
* @brief Get field lng from ahrs3 message
*
* @return [degE7] Longitude.
*/
static inline int32_t mavlink_msg_ahrs3_get_lng(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 20);
}
/**
* @brief Get field v1 from ahrs3 message
*
* @return Test variable1.
*/
static inline float mavlink_msg_ahrs3_get_v1(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 24);
}
/**
* @brief Get field v2 from ahrs3 message
*
* @return Test variable2.
*/
static inline float mavlink_msg_ahrs3_get_v2(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 28);
}
/**
* @brief Get field v3 from ahrs3 message
*
* @return Test variable3.
*/
static inline float mavlink_msg_ahrs3_get_v3(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 32);
}
/**
* @brief Get field v4 from ahrs3 message
*
* @return Test variable4.
*/
static inline float mavlink_msg_ahrs3_get_v4(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 36);
}
/**
* @brief Decode a ahrs3 message into a struct
*
* @param msg The message to decode
* @param ahrs3 C-struct to decode the message contents into
*/
static inline void mavlink_msg_ahrs3_decode(const mavlink_message_t* msg, mavlink_ahrs3_t* ahrs3)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
ahrs3->roll = mavlink_msg_ahrs3_get_roll(msg);
ahrs3->pitch = mavlink_msg_ahrs3_get_pitch(msg);
ahrs3->yaw = mavlink_msg_ahrs3_get_yaw(msg);
ahrs3->altitude = mavlink_msg_ahrs3_get_altitude(msg);
ahrs3->lat = mavlink_msg_ahrs3_get_lat(msg);
ahrs3->lng = mavlink_msg_ahrs3_get_lng(msg);
ahrs3->v1 = mavlink_msg_ahrs3_get_v1(msg);
ahrs3->v2 = mavlink_msg_ahrs3_get_v2(msg);
ahrs3->v3 = mavlink_msg_ahrs3_get_v3(msg);
ahrs3->v4 = mavlink_msg_ahrs3_get_v4(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_AHRS3_LEN? msg->len : MAVLINK_MSG_ID_AHRS3_LEN;
memset(ahrs3, 0, MAVLINK_MSG_ID_AHRS3_LEN);
memcpy(ahrs3, _MAV_PAYLOAD(msg), len);
#endif
}

View File

@@ -0,0 +1,488 @@
#pragma once
// MESSAGE AIRSPEED_AUTOCAL PACKING
#define MAVLINK_MSG_ID_AIRSPEED_AUTOCAL 174
MAVPACKED(
typedef struct __mavlink_airspeed_autocal_t {
float vx; /*< [m/s] GPS velocity north.*/
float vy; /*< [m/s] GPS velocity east.*/
float vz; /*< [m/s] GPS velocity down.*/
float diff_pressure; /*< [Pa] Differential pressure.*/
float EAS2TAS; /*< Estimated to true airspeed ratio.*/
float ratio; /*< Airspeed ratio.*/
float state_x; /*< EKF state x.*/
float state_y; /*< EKF state y.*/
float state_z; /*< EKF state z.*/
float Pax; /*< EKF Pax.*/
float Pby; /*< EKF Pby.*/
float Pcz; /*< EKF Pcz.*/
}) mavlink_airspeed_autocal_t;
#define MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN 48
#define MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_MIN_LEN 48
#define MAVLINK_MSG_ID_174_LEN 48
#define MAVLINK_MSG_ID_174_MIN_LEN 48
#define MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_CRC 167
#define MAVLINK_MSG_ID_174_CRC 167
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_AIRSPEED_AUTOCAL { \
174, \
"AIRSPEED_AUTOCAL", \
12, \
{ { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_airspeed_autocal_t, vx) }, \
{ "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_airspeed_autocal_t, vy) }, \
{ "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_airspeed_autocal_t, vz) }, \
{ "diff_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_airspeed_autocal_t, diff_pressure) }, \
{ "EAS2TAS", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_airspeed_autocal_t, EAS2TAS) }, \
{ "ratio", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_airspeed_autocal_t, ratio) }, \
{ "state_x", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_airspeed_autocal_t, state_x) }, \
{ "state_y", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_airspeed_autocal_t, state_y) }, \
{ "state_z", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_airspeed_autocal_t, state_z) }, \
{ "Pax", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_airspeed_autocal_t, Pax) }, \
{ "Pby", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_airspeed_autocal_t, Pby) }, \
{ "Pcz", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_airspeed_autocal_t, Pcz) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_AIRSPEED_AUTOCAL { \
"AIRSPEED_AUTOCAL", \
12, \
{ { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_airspeed_autocal_t, vx) }, \
{ "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_airspeed_autocal_t, vy) }, \
{ "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_airspeed_autocal_t, vz) }, \
{ "diff_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_airspeed_autocal_t, diff_pressure) }, \
{ "EAS2TAS", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_airspeed_autocal_t, EAS2TAS) }, \
{ "ratio", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_airspeed_autocal_t, ratio) }, \
{ "state_x", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_airspeed_autocal_t, state_x) }, \
{ "state_y", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_airspeed_autocal_t, state_y) }, \
{ "state_z", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_airspeed_autocal_t, state_z) }, \
{ "Pax", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_airspeed_autocal_t, Pax) }, \
{ "Pby", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_airspeed_autocal_t, Pby) }, \
{ "Pcz", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_airspeed_autocal_t, Pcz) }, \
} \
}
#endif
/**
* @brief Pack a airspeed_autocal 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 vx [m/s] GPS velocity north.
* @param vy [m/s] GPS velocity east.
* @param vz [m/s] GPS velocity down.
* @param diff_pressure [Pa] Differential pressure.
* @param EAS2TAS Estimated to true airspeed ratio.
* @param ratio Airspeed ratio.
* @param state_x EKF state x.
* @param state_y EKF state y.
* @param state_z EKF state z.
* @param Pax EKF Pax.
* @param Pby EKF Pby.
* @param Pcz EKF Pcz.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_airspeed_autocal_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
float vx, float vy, float vz, float diff_pressure, float EAS2TAS, float ratio, float state_x, float state_y, float state_z, float Pax, float Pby, float Pcz)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN];
_mav_put_float(buf, 0, vx);
_mav_put_float(buf, 4, vy);
_mav_put_float(buf, 8, vz);
_mav_put_float(buf, 12, diff_pressure);
_mav_put_float(buf, 16, EAS2TAS);
_mav_put_float(buf, 20, ratio);
_mav_put_float(buf, 24, state_x);
_mav_put_float(buf, 28, state_y);
_mav_put_float(buf, 32, state_z);
_mav_put_float(buf, 36, Pax);
_mav_put_float(buf, 40, Pby);
_mav_put_float(buf, 44, Pcz);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN);
#else
mavlink_airspeed_autocal_t packet;
packet.vx = vx;
packet.vy = vy;
packet.vz = vz;
packet.diff_pressure = diff_pressure;
packet.EAS2TAS = EAS2TAS;
packet.ratio = ratio;
packet.state_x = state_x;
packet.state_y = state_y;
packet.state_z = state_z;
packet.Pax = Pax;
packet.Pby = Pby;
packet.Pcz = Pcz;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_AIRSPEED_AUTOCAL;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_MIN_LEN, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_CRC);
}
/**
* @brief Pack a airspeed_autocal message on a channel
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param vx [m/s] GPS velocity north.
* @param vy [m/s] GPS velocity east.
* @param vz [m/s] GPS velocity down.
* @param diff_pressure [Pa] Differential pressure.
* @param EAS2TAS Estimated to true airspeed ratio.
* @param ratio Airspeed ratio.
* @param state_x EKF state x.
* @param state_y EKF state y.
* @param state_z EKF state z.
* @param Pax EKF Pax.
* @param Pby EKF Pby.
* @param Pcz EKF Pcz.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_airspeed_autocal_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
float vx,float vy,float vz,float diff_pressure,float EAS2TAS,float ratio,float state_x,float state_y,float state_z,float Pax,float Pby,float Pcz)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN];
_mav_put_float(buf, 0, vx);
_mav_put_float(buf, 4, vy);
_mav_put_float(buf, 8, vz);
_mav_put_float(buf, 12, diff_pressure);
_mav_put_float(buf, 16, EAS2TAS);
_mav_put_float(buf, 20, ratio);
_mav_put_float(buf, 24, state_x);
_mav_put_float(buf, 28, state_y);
_mav_put_float(buf, 32, state_z);
_mav_put_float(buf, 36, Pax);
_mav_put_float(buf, 40, Pby);
_mav_put_float(buf, 44, Pcz);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN);
#else
mavlink_airspeed_autocal_t packet;
packet.vx = vx;
packet.vy = vy;
packet.vz = vz;
packet.diff_pressure = diff_pressure;
packet.EAS2TAS = EAS2TAS;
packet.ratio = ratio;
packet.state_x = state_x;
packet.state_y = state_y;
packet.state_z = state_z;
packet.Pax = Pax;
packet.Pby = Pby;
packet.Pcz = Pcz;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_AIRSPEED_AUTOCAL;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_MIN_LEN, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_CRC);
}
/**
* @brief Encode a airspeed_autocal struct
*
* @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_autocal C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_airspeed_autocal_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_airspeed_autocal_t* airspeed_autocal)
{
return mavlink_msg_airspeed_autocal_pack(system_id, component_id, msg, airspeed_autocal->vx, airspeed_autocal->vy, airspeed_autocal->vz, airspeed_autocal->diff_pressure, airspeed_autocal->EAS2TAS, airspeed_autocal->ratio, airspeed_autocal->state_x, airspeed_autocal->state_y, airspeed_autocal->state_z, airspeed_autocal->Pax, airspeed_autocal->Pby, airspeed_autocal->Pcz);
}
/**
* @brief Encode a airspeed_autocal struct on a channel
*
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param airspeed_autocal C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_airspeed_autocal_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_airspeed_autocal_t* airspeed_autocal)
{
return mavlink_msg_airspeed_autocal_pack_chan(system_id, component_id, chan, msg, airspeed_autocal->vx, airspeed_autocal->vy, airspeed_autocal->vz, airspeed_autocal->diff_pressure, airspeed_autocal->EAS2TAS, airspeed_autocal->ratio, airspeed_autocal->state_x, airspeed_autocal->state_y, airspeed_autocal->state_z, airspeed_autocal->Pax, airspeed_autocal->Pby, airspeed_autocal->Pcz);
}
/**
* @brief Send a airspeed_autocal message
* @param chan MAVLink channel to send the message
*
* @param vx [m/s] GPS velocity north.
* @param vy [m/s] GPS velocity east.
* @param vz [m/s] GPS velocity down.
* @param diff_pressure [Pa] Differential pressure.
* @param EAS2TAS Estimated to true airspeed ratio.
* @param ratio Airspeed ratio.
* @param state_x EKF state x.
* @param state_y EKF state y.
* @param state_z EKF state z.
* @param Pax EKF Pax.
* @param Pby EKF Pby.
* @param Pcz EKF Pcz.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_airspeed_autocal_send(mavlink_channel_t chan, float vx, float vy, float vz, float diff_pressure, float EAS2TAS, float ratio, float state_x, float state_y, float state_z, float Pax, float Pby, float Pcz)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN];
_mav_put_float(buf, 0, vx);
_mav_put_float(buf, 4, vy);
_mav_put_float(buf, 8, vz);
_mav_put_float(buf, 12, diff_pressure);
_mav_put_float(buf, 16, EAS2TAS);
_mav_put_float(buf, 20, ratio);
_mav_put_float(buf, 24, state_x);
_mav_put_float(buf, 28, state_y);
_mav_put_float(buf, 32, state_z);
_mav_put_float(buf, 36, Pax);
_mav_put_float(buf, 40, Pby);
_mav_put_float(buf, 44, Pcz);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL, buf, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_MIN_LEN, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_CRC);
#else
mavlink_airspeed_autocal_t packet;
packet.vx = vx;
packet.vy = vy;
packet.vz = vz;
packet.diff_pressure = diff_pressure;
packet.EAS2TAS = EAS2TAS;
packet.ratio = ratio;
packet.state_x = state_x;
packet.state_y = state_y;
packet.state_z = state_z;
packet.Pax = Pax;
packet.Pby = Pby;
packet.Pcz = Pcz;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL, (const char *)&packet, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_MIN_LEN, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_CRC);
#endif
}
/**
* @brief Send a airspeed_autocal message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_airspeed_autocal_send_struct(mavlink_channel_t chan, const mavlink_airspeed_autocal_t* airspeed_autocal)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_airspeed_autocal_send(chan, airspeed_autocal->vx, airspeed_autocal->vy, airspeed_autocal->vz, airspeed_autocal->diff_pressure, airspeed_autocal->EAS2TAS, airspeed_autocal->ratio, airspeed_autocal->state_x, airspeed_autocal->state_y, airspeed_autocal->state_z, airspeed_autocal->Pax, airspeed_autocal->Pby, airspeed_autocal->Pcz);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL, (const char *)airspeed_autocal, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_MIN_LEN, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_CRC);
#endif
}
#if MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_airspeed_autocal_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float vx, float vy, float vz, float diff_pressure, float EAS2TAS, float ratio, float state_x, float state_y, float state_z, float Pax, float Pby, float Pcz)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_float(buf, 0, vx);
_mav_put_float(buf, 4, vy);
_mav_put_float(buf, 8, vz);
_mav_put_float(buf, 12, diff_pressure);
_mav_put_float(buf, 16, EAS2TAS);
_mav_put_float(buf, 20, ratio);
_mav_put_float(buf, 24, state_x);
_mav_put_float(buf, 28, state_y);
_mav_put_float(buf, 32, state_z);
_mav_put_float(buf, 36, Pax);
_mav_put_float(buf, 40, Pby);
_mav_put_float(buf, 44, Pcz);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL, buf, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_MIN_LEN, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_CRC);
#else
mavlink_airspeed_autocal_t *packet = (mavlink_airspeed_autocal_t *)msgbuf;
packet->vx = vx;
packet->vy = vy;
packet->vz = vz;
packet->diff_pressure = diff_pressure;
packet->EAS2TAS = EAS2TAS;
packet->ratio = ratio;
packet->state_x = state_x;
packet->state_y = state_y;
packet->state_z = state_z;
packet->Pax = Pax;
packet->Pby = Pby;
packet->Pcz = Pcz;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL, (const char *)packet, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_MIN_LEN, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_CRC);
#endif
}
#endif
#endif
// MESSAGE AIRSPEED_AUTOCAL UNPACKING
/**
* @brief Get field vx from airspeed_autocal message
*
* @return [m/s] GPS velocity north.
*/
static inline float mavlink_msg_airspeed_autocal_get_vx(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 0);
}
/**
* @brief Get field vy from airspeed_autocal message
*
* @return [m/s] GPS velocity east.
*/
static inline float mavlink_msg_airspeed_autocal_get_vy(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 4);
}
/**
* @brief Get field vz from airspeed_autocal message
*
* @return [m/s] GPS velocity down.
*/
static inline float mavlink_msg_airspeed_autocal_get_vz(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
/**
* @brief Get field diff_pressure from airspeed_autocal message
*
* @return [Pa] Differential pressure.
*/
static inline float mavlink_msg_airspeed_autocal_get_diff_pressure(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
/**
* @brief Get field EAS2TAS from airspeed_autocal message
*
* @return Estimated to true airspeed ratio.
*/
static inline float mavlink_msg_airspeed_autocal_get_EAS2TAS(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 16);
}
/**
* @brief Get field ratio from airspeed_autocal message
*
* @return Airspeed ratio.
*/
static inline float mavlink_msg_airspeed_autocal_get_ratio(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 20);
}
/**
* @brief Get field state_x from airspeed_autocal message
*
* @return EKF state x.
*/
static inline float mavlink_msg_airspeed_autocal_get_state_x(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 24);
}
/**
* @brief Get field state_y from airspeed_autocal message
*
* @return EKF state y.
*/
static inline float mavlink_msg_airspeed_autocal_get_state_y(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 28);
}
/**
* @brief Get field state_z from airspeed_autocal message
*
* @return EKF state z.
*/
static inline float mavlink_msg_airspeed_autocal_get_state_z(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 32);
}
/**
* @brief Get field Pax from airspeed_autocal message
*
* @return EKF Pax.
*/
static inline float mavlink_msg_airspeed_autocal_get_Pax(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 36);
}
/**
* @brief Get field Pby from airspeed_autocal message
*
* @return EKF Pby.
*/
static inline float mavlink_msg_airspeed_autocal_get_Pby(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 40);
}
/**
* @brief Get field Pcz from airspeed_autocal message
*
* @return EKF Pcz.
*/
static inline float mavlink_msg_airspeed_autocal_get_Pcz(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 44);
}
/**
* @brief Decode a airspeed_autocal message into a struct
*
* @param msg The message to decode
* @param airspeed_autocal C-struct to decode the message contents into
*/
static inline void mavlink_msg_airspeed_autocal_decode(const mavlink_message_t* msg, mavlink_airspeed_autocal_t* airspeed_autocal)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
airspeed_autocal->vx = mavlink_msg_airspeed_autocal_get_vx(msg);
airspeed_autocal->vy = mavlink_msg_airspeed_autocal_get_vy(msg);
airspeed_autocal->vz = mavlink_msg_airspeed_autocal_get_vz(msg);
airspeed_autocal->diff_pressure = mavlink_msg_airspeed_autocal_get_diff_pressure(msg);
airspeed_autocal->EAS2TAS = mavlink_msg_airspeed_autocal_get_EAS2TAS(msg);
airspeed_autocal->ratio = mavlink_msg_airspeed_autocal_get_ratio(msg);
airspeed_autocal->state_x = mavlink_msg_airspeed_autocal_get_state_x(msg);
airspeed_autocal->state_y = mavlink_msg_airspeed_autocal_get_state_y(msg);
airspeed_autocal->state_z = mavlink_msg_airspeed_autocal_get_state_z(msg);
airspeed_autocal->Pax = mavlink_msg_airspeed_autocal_get_Pax(msg);
airspeed_autocal->Pby = mavlink_msg_airspeed_autocal_get_Pby(msg);
airspeed_autocal->Pcz = mavlink_msg_airspeed_autocal_get_Pcz(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN? msg->len : MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN;
memset(airspeed_autocal, 0, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN);
memcpy(airspeed_autocal, _MAV_PAYLOAD(msg), len);
#endif
}

View File

@@ -0,0 +1,263 @@
#pragma once
// MESSAGE AOA_SSA PACKING
#define MAVLINK_MSG_ID_AOA_SSA 11020
MAVPACKED(
typedef struct __mavlink_aoa_ssa_t {
uint64_t time_usec; /*< [us] Timestamp (since boot or Unix epoch).*/
float AOA; /*< [deg] Angle of Attack.*/
float SSA; /*< [deg] Side Slip Angle.*/
}) mavlink_aoa_ssa_t;
#define MAVLINK_MSG_ID_AOA_SSA_LEN 16
#define MAVLINK_MSG_ID_AOA_SSA_MIN_LEN 16
#define MAVLINK_MSG_ID_11020_LEN 16
#define MAVLINK_MSG_ID_11020_MIN_LEN 16
#define MAVLINK_MSG_ID_AOA_SSA_CRC 205
#define MAVLINK_MSG_ID_11020_CRC 205
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_AOA_SSA { \
11020, \
"AOA_SSA", \
3, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_aoa_ssa_t, time_usec) }, \
{ "AOA", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_aoa_ssa_t, AOA) }, \
{ "SSA", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_aoa_ssa_t, SSA) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_AOA_SSA { \
"AOA_SSA", \
3, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_aoa_ssa_t, time_usec) }, \
{ "AOA", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_aoa_ssa_t, AOA) }, \
{ "SSA", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_aoa_ssa_t, SSA) }, \
} \
}
#endif
/**
* @brief Pack a aoa_ssa 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 [us] Timestamp (since boot or Unix epoch).
* @param AOA [deg] Angle of Attack.
* @param SSA [deg] Side Slip Angle.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_aoa_ssa_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint64_t time_usec, float AOA, float SSA)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_AOA_SSA_LEN];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_float(buf, 8, AOA);
_mav_put_float(buf, 12, SSA);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AOA_SSA_LEN);
#else
mavlink_aoa_ssa_t packet;
packet.time_usec = time_usec;
packet.AOA = AOA;
packet.SSA = SSA;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AOA_SSA_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_AOA_SSA;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_AOA_SSA_MIN_LEN, MAVLINK_MSG_ID_AOA_SSA_LEN, MAVLINK_MSG_ID_AOA_SSA_CRC);
}
/**
* @brief Pack a aoa_ssa message on a channel
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_usec [us] Timestamp (since boot or Unix epoch).
* @param AOA [deg] Angle of Attack.
* @param SSA [deg] Side Slip Angle.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_aoa_ssa_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint64_t time_usec,float AOA,float SSA)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_AOA_SSA_LEN];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_float(buf, 8, AOA);
_mav_put_float(buf, 12, SSA);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AOA_SSA_LEN);
#else
mavlink_aoa_ssa_t packet;
packet.time_usec = time_usec;
packet.AOA = AOA;
packet.SSA = SSA;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AOA_SSA_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_AOA_SSA;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_AOA_SSA_MIN_LEN, MAVLINK_MSG_ID_AOA_SSA_LEN, MAVLINK_MSG_ID_AOA_SSA_CRC);
}
/**
* @brief Encode a aoa_ssa struct
*
* @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 aoa_ssa C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_aoa_ssa_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_aoa_ssa_t* aoa_ssa)
{
return mavlink_msg_aoa_ssa_pack(system_id, component_id, msg, aoa_ssa->time_usec, aoa_ssa->AOA, aoa_ssa->SSA);
}
/**
* @brief Encode a aoa_ssa struct on a channel
*
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param aoa_ssa C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_aoa_ssa_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_aoa_ssa_t* aoa_ssa)
{
return mavlink_msg_aoa_ssa_pack_chan(system_id, component_id, chan, msg, aoa_ssa->time_usec, aoa_ssa->AOA, aoa_ssa->SSA);
}
/**
* @brief Send a aoa_ssa message
* @param chan MAVLink channel to send the message
*
* @param time_usec [us] Timestamp (since boot or Unix epoch).
* @param AOA [deg] Angle of Attack.
* @param SSA [deg] Side Slip Angle.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_aoa_ssa_send(mavlink_channel_t chan, uint64_t time_usec, float AOA, float SSA)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_AOA_SSA_LEN];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_float(buf, 8, AOA);
_mav_put_float(buf, 12, SSA);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AOA_SSA, buf, MAVLINK_MSG_ID_AOA_SSA_MIN_LEN, MAVLINK_MSG_ID_AOA_SSA_LEN, MAVLINK_MSG_ID_AOA_SSA_CRC);
#else
mavlink_aoa_ssa_t packet;
packet.time_usec = time_usec;
packet.AOA = AOA;
packet.SSA = SSA;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AOA_SSA, (const char *)&packet, MAVLINK_MSG_ID_AOA_SSA_MIN_LEN, MAVLINK_MSG_ID_AOA_SSA_LEN, MAVLINK_MSG_ID_AOA_SSA_CRC);
#endif
}
/**
* @brief Send a aoa_ssa message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_aoa_ssa_send_struct(mavlink_channel_t chan, const mavlink_aoa_ssa_t* aoa_ssa)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_aoa_ssa_send(chan, aoa_ssa->time_usec, aoa_ssa->AOA, aoa_ssa->SSA);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AOA_SSA, (const char *)aoa_ssa, MAVLINK_MSG_ID_AOA_SSA_MIN_LEN, MAVLINK_MSG_ID_AOA_SSA_LEN, MAVLINK_MSG_ID_AOA_SSA_CRC);
#endif
}
#if MAVLINK_MSG_ID_AOA_SSA_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_aoa_ssa_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, float AOA, float SSA)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_float(buf, 8, AOA);
_mav_put_float(buf, 12, SSA);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AOA_SSA, buf, MAVLINK_MSG_ID_AOA_SSA_MIN_LEN, MAVLINK_MSG_ID_AOA_SSA_LEN, MAVLINK_MSG_ID_AOA_SSA_CRC);
#else
mavlink_aoa_ssa_t *packet = (mavlink_aoa_ssa_t *)msgbuf;
packet->time_usec = time_usec;
packet->AOA = AOA;
packet->SSA = SSA;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AOA_SSA, (const char *)packet, MAVLINK_MSG_ID_AOA_SSA_MIN_LEN, MAVLINK_MSG_ID_AOA_SSA_LEN, MAVLINK_MSG_ID_AOA_SSA_CRC);
#endif
}
#endif
#endif
// MESSAGE AOA_SSA UNPACKING
/**
* @brief Get field time_usec from aoa_ssa message
*
* @return [us] Timestamp (since boot or Unix epoch).
*/
static inline uint64_t mavlink_msg_aoa_ssa_get_time_usec(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint64_t(msg, 0);
}
/**
* @brief Get field AOA from aoa_ssa message
*
* @return [deg] Angle of Attack.
*/
static inline float mavlink_msg_aoa_ssa_get_AOA(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
/**
* @brief Get field SSA from aoa_ssa message
*
* @return [deg] Side Slip Angle.
*/
static inline float mavlink_msg_aoa_ssa_get_SSA(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
/**
* @brief Decode a aoa_ssa message into a struct
*
* @param msg The message to decode
* @param aoa_ssa C-struct to decode the message contents into
*/
static inline void mavlink_msg_aoa_ssa_decode(const mavlink_message_t* msg, mavlink_aoa_ssa_t* aoa_ssa)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
aoa_ssa->time_usec = mavlink_msg_aoa_ssa_get_time_usec(msg);
aoa_ssa->AOA = mavlink_msg_aoa_ssa_get_AOA(msg);
aoa_ssa->SSA = mavlink_msg_aoa_ssa_get_SSA(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_AOA_SSA_LEN? msg->len : MAVLINK_MSG_ID_AOA_SSA_LEN;
memset(aoa_ssa, 0, MAVLINK_MSG_ID_AOA_SSA_LEN);
memcpy(aoa_ssa, _MAV_PAYLOAD(msg), len);
#endif
}

View File

@@ -0,0 +1,338 @@
#pragma once
// MESSAGE AP_ADC PACKING
#define MAVLINK_MSG_ID_AP_ADC 153
MAVPACKED(
typedef struct __mavlink_ap_adc_t {
uint16_t adc1; /*< ADC output 1.*/
uint16_t adc2; /*< ADC output 2.*/
uint16_t adc3; /*< ADC output 3.*/
uint16_t adc4; /*< ADC output 4.*/
uint16_t adc5; /*< ADC output 5.*/
uint16_t adc6; /*< ADC output 6.*/
}) mavlink_ap_adc_t;
#define MAVLINK_MSG_ID_AP_ADC_LEN 12
#define MAVLINK_MSG_ID_AP_ADC_MIN_LEN 12
#define MAVLINK_MSG_ID_153_LEN 12
#define MAVLINK_MSG_ID_153_MIN_LEN 12
#define MAVLINK_MSG_ID_AP_ADC_CRC 188
#define MAVLINK_MSG_ID_153_CRC 188
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_AP_ADC { \
153, \
"AP_ADC", \
6, \
{ { "adc1", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_ap_adc_t, adc1) }, \
{ "adc2", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_ap_adc_t, adc2) }, \
{ "adc3", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_ap_adc_t, adc3) }, \
{ "adc4", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_ap_adc_t, adc4) }, \
{ "adc5", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_ap_adc_t, adc5) }, \
{ "adc6", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_ap_adc_t, adc6) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_AP_ADC { \
"AP_ADC", \
6, \
{ { "adc1", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_ap_adc_t, adc1) }, \
{ "adc2", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_ap_adc_t, adc2) }, \
{ "adc3", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_ap_adc_t, adc3) }, \
{ "adc4", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_ap_adc_t, adc4) }, \
{ "adc5", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_ap_adc_t, adc5) }, \
{ "adc6", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_ap_adc_t, adc6) }, \
} \
}
#endif
/**
* @brief Pack a ap_adc 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 ADC output 1.
* @param adc2 ADC output 2.
* @param adc3 ADC output 3.
* @param adc4 ADC output 4.
* @param adc5 ADC output 5.
* @param adc6 ADC output 6.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_ap_adc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint16_t adc1, uint16_t adc2, uint16_t adc3, uint16_t adc4, uint16_t adc5, uint16_t adc6)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_AP_ADC_LEN];
_mav_put_uint16_t(buf, 0, adc1);
_mav_put_uint16_t(buf, 2, adc2);
_mav_put_uint16_t(buf, 4, adc3);
_mav_put_uint16_t(buf, 6, adc4);
_mav_put_uint16_t(buf, 8, adc5);
_mav_put_uint16_t(buf, 10, adc6);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AP_ADC_LEN);
#else
mavlink_ap_adc_t packet;
packet.adc1 = adc1;
packet.adc2 = adc2;
packet.adc3 = adc3;
packet.adc4 = adc4;
packet.adc5 = adc5;
packet.adc6 = adc6;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AP_ADC_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_AP_ADC;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_AP_ADC_MIN_LEN, MAVLINK_MSG_ID_AP_ADC_LEN, MAVLINK_MSG_ID_AP_ADC_CRC);
}
/**
* @brief Pack a ap_adc message on a channel
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param adc1 ADC output 1.
* @param adc2 ADC output 2.
* @param adc3 ADC output 3.
* @param adc4 ADC output 4.
* @param adc5 ADC output 5.
* @param adc6 ADC output 6.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_ap_adc_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 adc5,uint16_t adc6)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_AP_ADC_LEN];
_mav_put_uint16_t(buf, 0, adc1);
_mav_put_uint16_t(buf, 2, adc2);
_mav_put_uint16_t(buf, 4, adc3);
_mav_put_uint16_t(buf, 6, adc4);
_mav_put_uint16_t(buf, 8, adc5);
_mav_put_uint16_t(buf, 10, adc6);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AP_ADC_LEN);
#else
mavlink_ap_adc_t packet;
packet.adc1 = adc1;
packet.adc2 = adc2;
packet.adc3 = adc3;
packet.adc4 = adc4;
packet.adc5 = adc5;
packet.adc6 = adc6;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AP_ADC_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_AP_ADC;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_AP_ADC_MIN_LEN, MAVLINK_MSG_ID_AP_ADC_LEN, MAVLINK_MSG_ID_AP_ADC_CRC);
}
/**
* @brief Encode a ap_adc struct
*
* @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 ap_adc C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_ap_adc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_ap_adc_t* ap_adc)
{
return mavlink_msg_ap_adc_pack(system_id, component_id, msg, ap_adc->adc1, ap_adc->adc2, ap_adc->adc3, ap_adc->adc4, ap_adc->adc5, ap_adc->adc6);
}
/**
* @brief Encode a ap_adc struct on a channel
*
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param ap_adc C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_ap_adc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_ap_adc_t* ap_adc)
{
return mavlink_msg_ap_adc_pack_chan(system_id, component_id, chan, msg, ap_adc->adc1, ap_adc->adc2, ap_adc->adc3, ap_adc->adc4, ap_adc->adc5, ap_adc->adc6);
}
/**
* @brief Send a ap_adc message
* @param chan MAVLink channel to send the message
*
* @param adc1 ADC output 1.
* @param adc2 ADC output 2.
* @param adc3 ADC output 3.
* @param adc4 ADC output 4.
* @param adc5 ADC output 5.
* @param adc6 ADC output 6.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_ap_adc_send(mavlink_channel_t chan, uint16_t adc1, uint16_t adc2, uint16_t adc3, uint16_t adc4, uint16_t adc5, uint16_t adc6)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_AP_ADC_LEN];
_mav_put_uint16_t(buf, 0, adc1);
_mav_put_uint16_t(buf, 2, adc2);
_mav_put_uint16_t(buf, 4, adc3);
_mav_put_uint16_t(buf, 6, adc4);
_mav_put_uint16_t(buf, 8, adc5);
_mav_put_uint16_t(buf, 10, adc6);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AP_ADC, buf, MAVLINK_MSG_ID_AP_ADC_MIN_LEN, MAVLINK_MSG_ID_AP_ADC_LEN, MAVLINK_MSG_ID_AP_ADC_CRC);
#else
mavlink_ap_adc_t packet;
packet.adc1 = adc1;
packet.adc2 = adc2;
packet.adc3 = adc3;
packet.adc4 = adc4;
packet.adc5 = adc5;
packet.adc6 = adc6;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AP_ADC, (const char *)&packet, MAVLINK_MSG_ID_AP_ADC_MIN_LEN, MAVLINK_MSG_ID_AP_ADC_LEN, MAVLINK_MSG_ID_AP_ADC_CRC);
#endif
}
/**
* @brief Send a ap_adc message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_ap_adc_send_struct(mavlink_channel_t chan, const mavlink_ap_adc_t* ap_adc)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_ap_adc_send(chan, ap_adc->adc1, ap_adc->adc2, ap_adc->adc3, ap_adc->adc4, ap_adc->adc5, ap_adc->adc6);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AP_ADC, (const char *)ap_adc, MAVLINK_MSG_ID_AP_ADC_MIN_LEN, MAVLINK_MSG_ID_AP_ADC_LEN, MAVLINK_MSG_ID_AP_ADC_CRC);
#endif
}
#if MAVLINK_MSG_ID_AP_ADC_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_ap_adc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t adc1, uint16_t adc2, uint16_t adc3, uint16_t adc4, uint16_t adc5, uint16_t adc6)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint16_t(buf, 0, adc1);
_mav_put_uint16_t(buf, 2, adc2);
_mav_put_uint16_t(buf, 4, adc3);
_mav_put_uint16_t(buf, 6, adc4);
_mav_put_uint16_t(buf, 8, adc5);
_mav_put_uint16_t(buf, 10, adc6);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AP_ADC, buf, MAVLINK_MSG_ID_AP_ADC_MIN_LEN, MAVLINK_MSG_ID_AP_ADC_LEN, MAVLINK_MSG_ID_AP_ADC_CRC);
#else
mavlink_ap_adc_t *packet = (mavlink_ap_adc_t *)msgbuf;
packet->adc1 = adc1;
packet->adc2 = adc2;
packet->adc3 = adc3;
packet->adc4 = adc4;
packet->adc5 = adc5;
packet->adc6 = adc6;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AP_ADC, (const char *)packet, MAVLINK_MSG_ID_AP_ADC_MIN_LEN, MAVLINK_MSG_ID_AP_ADC_LEN, MAVLINK_MSG_ID_AP_ADC_CRC);
#endif
}
#endif
#endif
// MESSAGE AP_ADC UNPACKING
/**
* @brief Get field adc1 from ap_adc message
*
* @return ADC output 1.
*/
static inline uint16_t mavlink_msg_ap_adc_get_adc1(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 0);
}
/**
* @brief Get field adc2 from ap_adc message
*
* @return ADC output 2.
*/
static inline uint16_t mavlink_msg_ap_adc_get_adc2(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 2);
}
/**
* @brief Get field adc3 from ap_adc message
*
* @return ADC output 3.
*/
static inline uint16_t mavlink_msg_ap_adc_get_adc3(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 4);
}
/**
* @brief Get field adc4 from ap_adc message
*
* @return ADC output 4.
*/
static inline uint16_t mavlink_msg_ap_adc_get_adc4(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 6);
}
/**
* @brief Get field adc5 from ap_adc message
*
* @return ADC output 5.
*/
static inline uint16_t mavlink_msg_ap_adc_get_adc5(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 8);
}
/**
* @brief Get field adc6 from ap_adc message
*
* @return ADC output 6.
*/
static inline uint16_t mavlink_msg_ap_adc_get_adc6(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 10);
}
/**
* @brief Decode a ap_adc message into a struct
*
* @param msg The message to decode
* @param ap_adc C-struct to decode the message contents into
*/
static inline void mavlink_msg_ap_adc_decode(const mavlink_message_t* msg, mavlink_ap_adc_t* ap_adc)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
ap_adc->adc1 = mavlink_msg_ap_adc_get_adc1(msg);
ap_adc->adc2 = mavlink_msg_ap_adc_get_adc2(msg);
ap_adc->adc3 = mavlink_msg_ap_adc_get_adc3(msg);
ap_adc->adc4 = mavlink_msg_ap_adc_get_adc4(msg);
ap_adc->adc5 = mavlink_msg_ap_adc_get_adc5(msg);
ap_adc->adc6 = mavlink_msg_ap_adc_get_adc6(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_AP_ADC_LEN? msg->len : MAVLINK_MSG_ID_AP_ADC_LEN;
memset(ap_adc, 0, MAVLINK_MSG_ID_AP_ADC_LEN);
memcpy(ap_adc, _MAV_PAYLOAD(msg), len);
#endif
}

View File

@@ -0,0 +1,238 @@
#pragma once
// MESSAGE AUTOPILOT_VERSION_REQUEST PACKING
#define MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST 183
MAVPACKED(
typedef struct __mavlink_autopilot_version_request_t {
uint8_t target_system; /*< System ID.*/
uint8_t target_component; /*< Component ID.*/
}) mavlink_autopilot_version_request_t;
#define MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST_LEN 2
#define MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST_MIN_LEN 2
#define MAVLINK_MSG_ID_183_LEN 2
#define MAVLINK_MSG_ID_183_MIN_LEN 2
#define MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST_CRC 85
#define MAVLINK_MSG_ID_183_CRC 85
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_AUTOPILOT_VERSION_REQUEST { \
183, \
"AUTOPILOT_VERSION_REQUEST", \
2, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_autopilot_version_request_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_autopilot_version_request_t, target_component) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_AUTOPILOT_VERSION_REQUEST { \
"AUTOPILOT_VERSION_REQUEST", \
2, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_autopilot_version_request_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_autopilot_version_request_t, target_component) }, \
} \
}
#endif
/**
* @brief Pack a autopilot_version_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.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_autopilot_version_request_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST_LEN];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST_LEN);
#else
mavlink_autopilot_version_request_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST_MIN_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST_CRC);
}
/**
* @brief Pack a autopilot_version_request message on a channel
* @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 will be 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_autopilot_version_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)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST_LEN];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST_LEN);
#else
mavlink_autopilot_version_request_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST_MIN_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST_CRC);
}
/**
* @brief Encode a autopilot_version_request struct
*
* @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 autopilot_version_request C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_autopilot_version_request_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_autopilot_version_request_t* autopilot_version_request)
{
return mavlink_msg_autopilot_version_request_pack(system_id, component_id, msg, autopilot_version_request->target_system, autopilot_version_request->target_component);
}
/**
* @brief Encode a autopilot_version_request struct on a channel
*
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param autopilot_version_request C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_autopilot_version_request_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_autopilot_version_request_t* autopilot_version_request)
{
return mavlink_msg_autopilot_version_request_pack_chan(system_id, component_id, chan, msg, autopilot_version_request->target_system, autopilot_version_request->target_component);
}
/**
* @brief Send a autopilot_version_request 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_autopilot_version_request_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST_LEN];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST, buf, MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST_MIN_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST_CRC);
#else
mavlink_autopilot_version_request_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST, (const char *)&packet, MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST_MIN_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST_CRC);
#endif
}
/**
* @brief Send a autopilot_version_request message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_autopilot_version_request_send_struct(mavlink_channel_t chan, const mavlink_autopilot_version_request_t* autopilot_version_request)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_autopilot_version_request_send(chan, autopilot_version_request->target_system, autopilot_version_request->target_component);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST, (const char *)autopilot_version_request, MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST_MIN_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST_CRC);
#endif
}
#if MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_autopilot_version_request_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST, buf, MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST_MIN_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST_CRC);
#else
mavlink_autopilot_version_request_t *packet = (mavlink_autopilot_version_request_t *)msgbuf;
packet->target_system = target_system;
packet->target_component = target_component;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST, (const char *)packet, MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST_MIN_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST_CRC);
#endif
}
#endif
#endif
// MESSAGE AUTOPILOT_VERSION_REQUEST UNPACKING
/**
* @brief Get field target_system from autopilot_version_request message
*
* @return System ID.
*/
static inline uint8_t mavlink_msg_autopilot_version_request_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 0);
}
/**
* @brief Get field target_component from autopilot_version_request message
*
* @return Component ID.
*/
static inline uint8_t mavlink_msg_autopilot_version_request_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 1);
}
/**
* @brief Decode a autopilot_version_request message into a struct
*
* @param msg The message to decode
* @param autopilot_version_request C-struct to decode the message contents into
*/
static inline void mavlink_msg_autopilot_version_request_decode(const mavlink_message_t* msg, mavlink_autopilot_version_request_t* autopilot_version_request)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
autopilot_version_request->target_system = mavlink_msg_autopilot_version_request_get_target_system(msg);
autopilot_version_request->target_component = mavlink_msg_autopilot_version_request_get_target_component(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST_LEN? msg->len : MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST_LEN;
memset(autopilot_version_request, 0, MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST_LEN);
memcpy(autopilot_version_request, _MAV_PAYLOAD(msg), len);
#endif
}

View File

@@ -0,0 +1,238 @@
#pragma once
// MESSAGE BATTERY2 PACKING
#define MAVLINK_MSG_ID_BATTERY2 181
MAVPACKED(
typedef struct __mavlink_battery2_t {
uint16_t voltage; /*< [mV] Voltage.*/
int16_t current_battery; /*< [cA] Battery current, -1: autopilot does not measure the current.*/
}) mavlink_battery2_t;
#define MAVLINK_MSG_ID_BATTERY2_LEN 4
#define MAVLINK_MSG_ID_BATTERY2_MIN_LEN 4
#define MAVLINK_MSG_ID_181_LEN 4
#define MAVLINK_MSG_ID_181_MIN_LEN 4
#define MAVLINK_MSG_ID_BATTERY2_CRC 174
#define MAVLINK_MSG_ID_181_CRC 174
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_BATTERY2 { \
181, \
"BATTERY2", \
2, \
{ { "voltage", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_battery2_t, voltage) }, \
{ "current_battery", NULL, MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_battery2_t, current_battery) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_BATTERY2 { \
"BATTERY2", \
2, \
{ { "voltage", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_battery2_t, voltage) }, \
{ "current_battery", NULL, MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_battery2_t, current_battery) }, \
} \
}
#endif
/**
* @brief Pack a battery2 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 voltage [mV] Voltage.
* @param current_battery [cA] Battery current, -1: autopilot does not measure the current.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_battery2_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint16_t voltage, int16_t current_battery)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_BATTERY2_LEN];
_mav_put_uint16_t(buf, 0, voltage);
_mav_put_int16_t(buf, 2, current_battery);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_BATTERY2_LEN);
#else
mavlink_battery2_t packet;
packet.voltage = voltage;
packet.current_battery = current_battery;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_BATTERY2_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_BATTERY2;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_BATTERY2_MIN_LEN, MAVLINK_MSG_ID_BATTERY2_LEN, MAVLINK_MSG_ID_BATTERY2_CRC);
}
/**
* @brief Pack a battery2 message on a channel
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param voltage [mV] Voltage.
* @param current_battery [cA] Battery current, -1: autopilot does not measure the current.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_battery2_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint16_t voltage,int16_t current_battery)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_BATTERY2_LEN];
_mav_put_uint16_t(buf, 0, voltage);
_mav_put_int16_t(buf, 2, current_battery);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_BATTERY2_LEN);
#else
mavlink_battery2_t packet;
packet.voltage = voltage;
packet.current_battery = current_battery;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_BATTERY2_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_BATTERY2;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_BATTERY2_MIN_LEN, MAVLINK_MSG_ID_BATTERY2_LEN, MAVLINK_MSG_ID_BATTERY2_CRC);
}
/**
* @brief Encode a battery2 struct
*
* @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 battery2 C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_battery2_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_battery2_t* battery2)
{
return mavlink_msg_battery2_pack(system_id, component_id, msg, battery2->voltage, battery2->current_battery);
}
/**
* @brief Encode a battery2 struct on a channel
*
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param battery2 C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_battery2_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_battery2_t* battery2)
{
return mavlink_msg_battery2_pack_chan(system_id, component_id, chan, msg, battery2->voltage, battery2->current_battery);
}
/**
* @brief Send a battery2 message
* @param chan MAVLink channel to send the message
*
* @param voltage [mV] Voltage.
* @param current_battery [cA] Battery current, -1: autopilot does not measure the current.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_battery2_send(mavlink_channel_t chan, uint16_t voltage, int16_t current_battery)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_BATTERY2_LEN];
_mav_put_uint16_t(buf, 0, voltage);
_mav_put_int16_t(buf, 2, current_battery);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY2, buf, MAVLINK_MSG_ID_BATTERY2_MIN_LEN, MAVLINK_MSG_ID_BATTERY2_LEN, MAVLINK_MSG_ID_BATTERY2_CRC);
#else
mavlink_battery2_t packet;
packet.voltage = voltage;
packet.current_battery = current_battery;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY2, (const char *)&packet, MAVLINK_MSG_ID_BATTERY2_MIN_LEN, MAVLINK_MSG_ID_BATTERY2_LEN, MAVLINK_MSG_ID_BATTERY2_CRC);
#endif
}
/**
* @brief Send a battery2 message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_battery2_send_struct(mavlink_channel_t chan, const mavlink_battery2_t* battery2)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_battery2_send(chan, battery2->voltage, battery2->current_battery);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY2, (const char *)battery2, MAVLINK_MSG_ID_BATTERY2_MIN_LEN, MAVLINK_MSG_ID_BATTERY2_LEN, MAVLINK_MSG_ID_BATTERY2_CRC);
#endif
}
#if MAVLINK_MSG_ID_BATTERY2_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_battery2_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t voltage, int16_t current_battery)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint16_t(buf, 0, voltage);
_mav_put_int16_t(buf, 2, current_battery);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY2, buf, MAVLINK_MSG_ID_BATTERY2_MIN_LEN, MAVLINK_MSG_ID_BATTERY2_LEN, MAVLINK_MSG_ID_BATTERY2_CRC);
#else
mavlink_battery2_t *packet = (mavlink_battery2_t *)msgbuf;
packet->voltage = voltage;
packet->current_battery = current_battery;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY2, (const char *)packet, MAVLINK_MSG_ID_BATTERY2_MIN_LEN, MAVLINK_MSG_ID_BATTERY2_LEN, MAVLINK_MSG_ID_BATTERY2_CRC);
#endif
}
#endif
#endif
// MESSAGE BATTERY2 UNPACKING
/**
* @brief Get field voltage from battery2 message
*
* @return [mV] Voltage.
*/
static inline uint16_t mavlink_msg_battery2_get_voltage(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 0);
}
/**
* @brief Get field current_battery from battery2 message
*
* @return [cA] Battery current, -1: autopilot does not measure the current.
*/
static inline int16_t mavlink_msg_battery2_get_current_battery(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 2);
}
/**
* @brief Decode a battery2 message into a struct
*
* @param msg The message to decode
* @param battery2 C-struct to decode the message contents into
*/
static inline void mavlink_msg_battery2_decode(const mavlink_message_t* msg, mavlink_battery2_t* battery2)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
battery2->voltage = mavlink_msg_battery2_get_voltage(msg);
battery2->current_battery = mavlink_msg_battery2_get_current_battery(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_BATTERY2_LEN? msg->len : MAVLINK_MSG_ID_BATTERY2_LEN;
memset(battery2, 0, MAVLINK_MSG_ID_BATTERY2_LEN);
memcpy(battery2, _MAV_PAYLOAD(msg), len);
#endif
}

View File

@@ -0,0 +1,538 @@
#pragma once
// MESSAGE CAMERA_FEEDBACK PACKING
#define MAVLINK_MSG_ID_CAMERA_FEEDBACK 180
MAVPACKED(
typedef struct __mavlink_camera_feedback_t {
uint64_t time_usec; /*< [us] Image timestamp (since UNIX epoch), as passed in by CAMERA_STATUS message (or autopilot if no CCB).*/
int32_t lat; /*< [degE7] Latitude.*/
int32_t lng; /*< [degE7] Longitude.*/
float alt_msl; /*< [m] Altitude Absolute (AMSL).*/
float alt_rel; /*< [m] Altitude Relative (above HOME location).*/
float roll; /*< [deg] Camera Roll angle (earth frame, +-180).*/
float pitch; /*< [deg] Camera Pitch angle (earth frame, +-180).*/
float yaw; /*< [deg] Camera Yaw (earth frame, 0-360, true).*/
float foc_len; /*< [mm] Focal Length.*/
uint16_t img_idx; /*< Image index.*/
uint8_t target_system; /*< System ID.*/
uint8_t cam_idx; /*< Camera ID.*/
uint8_t flags; /*< Feedback flags.*/
uint16_t completed_captures; /*< Completed image captures.*/
}) mavlink_camera_feedback_t;
#define MAVLINK_MSG_ID_CAMERA_FEEDBACK_LEN 47
#define MAVLINK_MSG_ID_CAMERA_FEEDBACK_MIN_LEN 45
#define MAVLINK_MSG_ID_180_LEN 47
#define MAVLINK_MSG_ID_180_MIN_LEN 45
#define MAVLINK_MSG_ID_CAMERA_FEEDBACK_CRC 52
#define MAVLINK_MSG_ID_180_CRC 52
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_CAMERA_FEEDBACK { \
180, \
"CAMERA_FEEDBACK", \
14, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_camera_feedback_t, time_usec) }, \
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_camera_feedback_t, target_system) }, \
{ "cam_idx", NULL, MAVLINK_TYPE_UINT8_T, 0, 43, offsetof(mavlink_camera_feedback_t, cam_idx) }, \
{ "img_idx", NULL, MAVLINK_TYPE_UINT16_T, 0, 40, offsetof(mavlink_camera_feedback_t, img_idx) }, \
{ "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_camera_feedback_t, lat) }, \
{ "lng", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_camera_feedback_t, lng) }, \
{ "alt_msl", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_camera_feedback_t, alt_msl) }, \
{ "alt_rel", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_camera_feedback_t, alt_rel) }, \
{ "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_camera_feedback_t, roll) }, \
{ "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_camera_feedback_t, pitch) }, \
{ "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_camera_feedback_t, yaw) }, \
{ "foc_len", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_camera_feedback_t, foc_len) }, \
{ "flags", NULL, MAVLINK_TYPE_UINT8_T, 0, 44, offsetof(mavlink_camera_feedback_t, flags) }, \
{ "completed_captures", NULL, MAVLINK_TYPE_UINT16_T, 0, 45, offsetof(mavlink_camera_feedback_t, completed_captures) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_CAMERA_FEEDBACK { \
"CAMERA_FEEDBACK", \
14, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_camera_feedback_t, time_usec) }, \
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_camera_feedback_t, target_system) }, \
{ "cam_idx", NULL, MAVLINK_TYPE_UINT8_T, 0, 43, offsetof(mavlink_camera_feedback_t, cam_idx) }, \
{ "img_idx", NULL, MAVLINK_TYPE_UINT16_T, 0, 40, offsetof(mavlink_camera_feedback_t, img_idx) }, \
{ "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_camera_feedback_t, lat) }, \
{ "lng", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_camera_feedback_t, lng) }, \
{ "alt_msl", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_camera_feedback_t, alt_msl) }, \
{ "alt_rel", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_camera_feedback_t, alt_rel) }, \
{ "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_camera_feedback_t, roll) }, \
{ "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_camera_feedback_t, pitch) }, \
{ "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_camera_feedback_t, yaw) }, \
{ "foc_len", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_camera_feedback_t, foc_len) }, \
{ "flags", NULL, MAVLINK_TYPE_UINT8_T, 0, 44, offsetof(mavlink_camera_feedback_t, flags) }, \
{ "completed_captures", NULL, MAVLINK_TYPE_UINT16_T, 0, 45, offsetof(mavlink_camera_feedback_t, completed_captures) }, \
} \
}
#endif
/**
* @brief Pack a camera_feedback 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 [us] Image timestamp (since UNIX epoch), as passed in by CAMERA_STATUS message (or autopilot if no CCB).
* @param target_system System ID.
* @param cam_idx Camera ID.
* @param img_idx Image index.
* @param lat [degE7] Latitude.
* @param lng [degE7] Longitude.
* @param alt_msl [m] Altitude Absolute (AMSL).
* @param alt_rel [m] Altitude Relative (above HOME location).
* @param roll [deg] Camera Roll angle (earth frame, +-180).
* @param pitch [deg] Camera Pitch angle (earth frame, +-180).
* @param yaw [deg] Camera Yaw (earth frame, 0-360, true).
* @param foc_len [mm] Focal Length.
* @param flags Feedback flags.
* @param completed_captures Completed image captures.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_camera_feedback_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint64_t time_usec, uint8_t target_system, uint8_t cam_idx, uint16_t img_idx, int32_t lat, int32_t lng, float alt_msl, float alt_rel, float roll, float pitch, float yaw, float foc_len, uint8_t flags, uint16_t completed_captures)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_CAMERA_FEEDBACK_LEN];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_int32_t(buf, 8, lat);
_mav_put_int32_t(buf, 12, lng);
_mav_put_float(buf, 16, alt_msl);
_mav_put_float(buf, 20, alt_rel);
_mav_put_float(buf, 24, roll);
_mav_put_float(buf, 28, pitch);
_mav_put_float(buf, 32, yaw);
_mav_put_float(buf, 36, foc_len);
_mav_put_uint16_t(buf, 40, img_idx);
_mav_put_uint8_t(buf, 42, target_system);
_mav_put_uint8_t(buf, 43, cam_idx);
_mav_put_uint8_t(buf, 44, flags);
_mav_put_uint16_t(buf, 45, completed_captures);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CAMERA_FEEDBACK_LEN);
#else
mavlink_camera_feedback_t packet;
packet.time_usec = time_usec;
packet.lat = lat;
packet.lng = lng;
packet.alt_msl = alt_msl;
packet.alt_rel = alt_rel;
packet.roll = roll;
packet.pitch = pitch;
packet.yaw = yaw;
packet.foc_len = foc_len;
packet.img_idx = img_idx;
packet.target_system = target_system;
packet.cam_idx = cam_idx;
packet.flags = flags;
packet.completed_captures = completed_captures;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CAMERA_FEEDBACK_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_CAMERA_FEEDBACK;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CAMERA_FEEDBACK_MIN_LEN, MAVLINK_MSG_ID_CAMERA_FEEDBACK_LEN, MAVLINK_MSG_ID_CAMERA_FEEDBACK_CRC);
}
/**
* @brief Pack a camera_feedback message on a channel
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_usec [us] Image timestamp (since UNIX epoch), as passed in by CAMERA_STATUS message (or autopilot if no CCB).
* @param target_system System ID.
* @param cam_idx Camera ID.
* @param img_idx Image index.
* @param lat [degE7] Latitude.
* @param lng [degE7] Longitude.
* @param alt_msl [m] Altitude Absolute (AMSL).
* @param alt_rel [m] Altitude Relative (above HOME location).
* @param roll [deg] Camera Roll angle (earth frame, +-180).
* @param pitch [deg] Camera Pitch angle (earth frame, +-180).
* @param yaw [deg] Camera Yaw (earth frame, 0-360, true).
* @param foc_len [mm] Focal Length.
* @param flags Feedback flags.
* @param completed_captures Completed image captures.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_camera_feedback_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint64_t time_usec,uint8_t target_system,uint8_t cam_idx,uint16_t img_idx,int32_t lat,int32_t lng,float alt_msl,float alt_rel,float roll,float pitch,float yaw,float foc_len,uint8_t flags,uint16_t completed_captures)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_CAMERA_FEEDBACK_LEN];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_int32_t(buf, 8, lat);
_mav_put_int32_t(buf, 12, lng);
_mav_put_float(buf, 16, alt_msl);
_mav_put_float(buf, 20, alt_rel);
_mav_put_float(buf, 24, roll);
_mav_put_float(buf, 28, pitch);
_mav_put_float(buf, 32, yaw);
_mav_put_float(buf, 36, foc_len);
_mav_put_uint16_t(buf, 40, img_idx);
_mav_put_uint8_t(buf, 42, target_system);
_mav_put_uint8_t(buf, 43, cam_idx);
_mav_put_uint8_t(buf, 44, flags);
_mav_put_uint16_t(buf, 45, completed_captures);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CAMERA_FEEDBACK_LEN);
#else
mavlink_camera_feedback_t packet;
packet.time_usec = time_usec;
packet.lat = lat;
packet.lng = lng;
packet.alt_msl = alt_msl;
packet.alt_rel = alt_rel;
packet.roll = roll;
packet.pitch = pitch;
packet.yaw = yaw;
packet.foc_len = foc_len;
packet.img_idx = img_idx;
packet.target_system = target_system;
packet.cam_idx = cam_idx;
packet.flags = flags;
packet.completed_captures = completed_captures;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CAMERA_FEEDBACK_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_CAMERA_FEEDBACK;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CAMERA_FEEDBACK_MIN_LEN, MAVLINK_MSG_ID_CAMERA_FEEDBACK_LEN, MAVLINK_MSG_ID_CAMERA_FEEDBACK_CRC);
}
/**
* @brief Encode a camera_feedback struct
*
* @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 camera_feedback C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_camera_feedback_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_camera_feedback_t* camera_feedback)
{
return mavlink_msg_camera_feedback_pack(system_id, component_id, msg, camera_feedback->time_usec, camera_feedback->target_system, camera_feedback->cam_idx, camera_feedback->img_idx, camera_feedback->lat, camera_feedback->lng, camera_feedback->alt_msl, camera_feedback->alt_rel, camera_feedback->roll, camera_feedback->pitch, camera_feedback->yaw, camera_feedback->foc_len, camera_feedback->flags, camera_feedback->completed_captures);
}
/**
* @brief Encode a camera_feedback struct on a channel
*
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param camera_feedback C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_camera_feedback_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_camera_feedback_t* camera_feedback)
{
return mavlink_msg_camera_feedback_pack_chan(system_id, component_id, chan, msg, camera_feedback->time_usec, camera_feedback->target_system, camera_feedback->cam_idx, camera_feedback->img_idx, camera_feedback->lat, camera_feedback->lng, camera_feedback->alt_msl, camera_feedback->alt_rel, camera_feedback->roll, camera_feedback->pitch, camera_feedback->yaw, camera_feedback->foc_len, camera_feedback->flags, camera_feedback->completed_captures);
}
/**
* @brief Send a camera_feedback message
* @param chan MAVLink channel to send the message
*
* @param time_usec [us] Image timestamp (since UNIX epoch), as passed in by CAMERA_STATUS message (or autopilot if no CCB).
* @param target_system System ID.
* @param cam_idx Camera ID.
* @param img_idx Image index.
* @param lat [degE7] Latitude.
* @param lng [degE7] Longitude.
* @param alt_msl [m] Altitude Absolute (AMSL).
* @param alt_rel [m] Altitude Relative (above HOME location).
* @param roll [deg] Camera Roll angle (earth frame, +-180).
* @param pitch [deg] Camera Pitch angle (earth frame, +-180).
* @param yaw [deg] Camera Yaw (earth frame, 0-360, true).
* @param foc_len [mm] Focal Length.
* @param flags Feedback flags.
* @param completed_captures Completed image captures.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_camera_feedback_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t target_system, uint8_t cam_idx, uint16_t img_idx, int32_t lat, int32_t lng, float alt_msl, float alt_rel, float roll, float pitch, float yaw, float foc_len, uint8_t flags, uint16_t completed_captures)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_CAMERA_FEEDBACK_LEN];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_int32_t(buf, 8, lat);
_mav_put_int32_t(buf, 12, lng);
_mav_put_float(buf, 16, alt_msl);
_mav_put_float(buf, 20, alt_rel);
_mav_put_float(buf, 24, roll);
_mav_put_float(buf, 28, pitch);
_mav_put_float(buf, 32, yaw);
_mav_put_float(buf, 36, foc_len);
_mav_put_uint16_t(buf, 40, img_idx);
_mav_put_uint8_t(buf, 42, target_system);
_mav_put_uint8_t(buf, 43, cam_idx);
_mav_put_uint8_t(buf, 44, flags);
_mav_put_uint16_t(buf, 45, completed_captures);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_FEEDBACK, buf, MAVLINK_MSG_ID_CAMERA_FEEDBACK_MIN_LEN, MAVLINK_MSG_ID_CAMERA_FEEDBACK_LEN, MAVLINK_MSG_ID_CAMERA_FEEDBACK_CRC);
#else
mavlink_camera_feedback_t packet;
packet.time_usec = time_usec;
packet.lat = lat;
packet.lng = lng;
packet.alt_msl = alt_msl;
packet.alt_rel = alt_rel;
packet.roll = roll;
packet.pitch = pitch;
packet.yaw = yaw;
packet.foc_len = foc_len;
packet.img_idx = img_idx;
packet.target_system = target_system;
packet.cam_idx = cam_idx;
packet.flags = flags;
packet.completed_captures = completed_captures;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_FEEDBACK, (const char *)&packet, MAVLINK_MSG_ID_CAMERA_FEEDBACK_MIN_LEN, MAVLINK_MSG_ID_CAMERA_FEEDBACK_LEN, MAVLINK_MSG_ID_CAMERA_FEEDBACK_CRC);
#endif
}
/**
* @brief Send a camera_feedback message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_camera_feedback_send_struct(mavlink_channel_t chan, const mavlink_camera_feedback_t* camera_feedback)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_camera_feedback_send(chan, camera_feedback->time_usec, camera_feedback->target_system, camera_feedback->cam_idx, camera_feedback->img_idx, camera_feedback->lat, camera_feedback->lng, camera_feedback->alt_msl, camera_feedback->alt_rel, camera_feedback->roll, camera_feedback->pitch, camera_feedback->yaw, camera_feedback->foc_len, camera_feedback->flags, camera_feedback->completed_captures);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_FEEDBACK, (const char *)camera_feedback, MAVLINK_MSG_ID_CAMERA_FEEDBACK_MIN_LEN, MAVLINK_MSG_ID_CAMERA_FEEDBACK_LEN, MAVLINK_MSG_ID_CAMERA_FEEDBACK_CRC);
#endif
}
#if MAVLINK_MSG_ID_CAMERA_FEEDBACK_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_camera_feedback_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint8_t target_system, uint8_t cam_idx, uint16_t img_idx, int32_t lat, int32_t lng, float alt_msl, float alt_rel, float roll, float pitch, float yaw, float foc_len, uint8_t flags, uint16_t completed_captures)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_int32_t(buf, 8, lat);
_mav_put_int32_t(buf, 12, lng);
_mav_put_float(buf, 16, alt_msl);
_mav_put_float(buf, 20, alt_rel);
_mav_put_float(buf, 24, roll);
_mav_put_float(buf, 28, pitch);
_mav_put_float(buf, 32, yaw);
_mav_put_float(buf, 36, foc_len);
_mav_put_uint16_t(buf, 40, img_idx);
_mav_put_uint8_t(buf, 42, target_system);
_mav_put_uint8_t(buf, 43, cam_idx);
_mav_put_uint8_t(buf, 44, flags);
_mav_put_uint16_t(buf, 45, completed_captures);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_FEEDBACK, buf, MAVLINK_MSG_ID_CAMERA_FEEDBACK_MIN_LEN, MAVLINK_MSG_ID_CAMERA_FEEDBACK_LEN, MAVLINK_MSG_ID_CAMERA_FEEDBACK_CRC);
#else
mavlink_camera_feedback_t *packet = (mavlink_camera_feedback_t *)msgbuf;
packet->time_usec = time_usec;
packet->lat = lat;
packet->lng = lng;
packet->alt_msl = alt_msl;
packet->alt_rel = alt_rel;
packet->roll = roll;
packet->pitch = pitch;
packet->yaw = yaw;
packet->foc_len = foc_len;
packet->img_idx = img_idx;
packet->target_system = target_system;
packet->cam_idx = cam_idx;
packet->flags = flags;
packet->completed_captures = completed_captures;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_FEEDBACK, (const char *)packet, MAVLINK_MSG_ID_CAMERA_FEEDBACK_MIN_LEN, MAVLINK_MSG_ID_CAMERA_FEEDBACK_LEN, MAVLINK_MSG_ID_CAMERA_FEEDBACK_CRC);
#endif
}
#endif
#endif
// MESSAGE CAMERA_FEEDBACK UNPACKING
/**
* @brief Get field time_usec from camera_feedback message
*
* @return [us] Image timestamp (since UNIX epoch), as passed in by CAMERA_STATUS message (or autopilot if no CCB).
*/
static inline uint64_t mavlink_msg_camera_feedback_get_time_usec(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint64_t(msg, 0);
}
/**
* @brief Get field target_system from camera_feedback message
*
* @return System ID.
*/
static inline uint8_t mavlink_msg_camera_feedback_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 42);
}
/**
* @brief Get field cam_idx from camera_feedback message
*
* @return Camera ID.
*/
static inline uint8_t mavlink_msg_camera_feedback_get_cam_idx(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 43);
}
/**
* @brief Get field img_idx from camera_feedback message
*
* @return Image index.
*/
static inline uint16_t mavlink_msg_camera_feedback_get_img_idx(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 40);
}
/**
* @brief Get field lat from camera_feedback message
*
* @return [degE7] Latitude.
*/
static inline int32_t mavlink_msg_camera_feedback_get_lat(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 8);
}
/**
* @brief Get field lng from camera_feedback message
*
* @return [degE7] Longitude.
*/
static inline int32_t mavlink_msg_camera_feedback_get_lng(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 12);
}
/**
* @brief Get field alt_msl from camera_feedback message
*
* @return [m] Altitude Absolute (AMSL).
*/
static inline float mavlink_msg_camera_feedback_get_alt_msl(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 16);
}
/**
* @brief Get field alt_rel from camera_feedback message
*
* @return [m] Altitude Relative (above HOME location).
*/
static inline float mavlink_msg_camera_feedback_get_alt_rel(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 20);
}
/**
* @brief Get field roll from camera_feedback message
*
* @return [deg] Camera Roll angle (earth frame, +-180).
*/
static inline float mavlink_msg_camera_feedback_get_roll(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 24);
}
/**
* @brief Get field pitch from camera_feedback message
*
* @return [deg] Camera Pitch angle (earth frame, +-180).
*/
static inline float mavlink_msg_camera_feedback_get_pitch(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 28);
}
/**
* @brief Get field yaw from camera_feedback message
*
* @return [deg] Camera Yaw (earth frame, 0-360, true).
*/
static inline float mavlink_msg_camera_feedback_get_yaw(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 32);
}
/**
* @brief Get field foc_len from camera_feedback message
*
* @return [mm] Focal Length.
*/
static inline float mavlink_msg_camera_feedback_get_foc_len(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 36);
}
/**
* @brief Get field flags from camera_feedback message
*
* @return Feedback flags.
*/
static inline uint8_t mavlink_msg_camera_feedback_get_flags(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 44);
}
/**
* @brief Get field completed_captures from camera_feedback message
*
* @return Completed image captures.
*/
static inline uint16_t mavlink_msg_camera_feedback_get_completed_captures(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 45);
}
/**
* @brief Decode a camera_feedback message into a struct
*
* @param msg The message to decode
* @param camera_feedback C-struct to decode the message contents into
*/
static inline void mavlink_msg_camera_feedback_decode(const mavlink_message_t* msg, mavlink_camera_feedback_t* camera_feedback)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
camera_feedback->time_usec = mavlink_msg_camera_feedback_get_time_usec(msg);
camera_feedback->lat = mavlink_msg_camera_feedback_get_lat(msg);
camera_feedback->lng = mavlink_msg_camera_feedback_get_lng(msg);
camera_feedback->alt_msl = mavlink_msg_camera_feedback_get_alt_msl(msg);
camera_feedback->alt_rel = mavlink_msg_camera_feedback_get_alt_rel(msg);
camera_feedback->roll = mavlink_msg_camera_feedback_get_roll(msg);
camera_feedback->pitch = mavlink_msg_camera_feedback_get_pitch(msg);
camera_feedback->yaw = mavlink_msg_camera_feedback_get_yaw(msg);
camera_feedback->foc_len = mavlink_msg_camera_feedback_get_foc_len(msg);
camera_feedback->img_idx = mavlink_msg_camera_feedback_get_img_idx(msg);
camera_feedback->target_system = mavlink_msg_camera_feedback_get_target_system(msg);
camera_feedback->cam_idx = mavlink_msg_camera_feedback_get_cam_idx(msg);
camera_feedback->flags = mavlink_msg_camera_feedback_get_flags(msg);
camera_feedback->completed_captures = mavlink_msg_camera_feedback_get_completed_captures(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_CAMERA_FEEDBACK_LEN? msg->len : MAVLINK_MSG_ID_CAMERA_FEEDBACK_LEN;
memset(camera_feedback, 0, MAVLINK_MSG_ID_CAMERA_FEEDBACK_LEN);
memcpy(camera_feedback, _MAV_PAYLOAD(msg), len);
#endif
}

View File

@@ -0,0 +1,413 @@
#pragma once
// MESSAGE CAMERA_STATUS PACKING
#define MAVLINK_MSG_ID_CAMERA_STATUS 179
MAVPACKED(
typedef struct __mavlink_camera_status_t {
uint64_t time_usec; /*< [us] Image timestamp (since UNIX epoch, according to camera clock).*/
float p1; /*< Parameter 1 (meaning depends on event_id, see CAMERA_STATUS_TYPES enum).*/
float p2; /*< Parameter 2 (meaning depends on event_id, see CAMERA_STATUS_TYPES enum).*/
float p3; /*< Parameter 3 (meaning depends on event_id, see CAMERA_STATUS_TYPES enum).*/
float p4; /*< Parameter 4 (meaning depends on event_id, see CAMERA_STATUS_TYPES enum).*/
uint16_t img_idx; /*< Image index.*/
uint8_t target_system; /*< System ID.*/
uint8_t cam_idx; /*< Camera ID.*/
uint8_t event_id; /*< Event type.*/
}) mavlink_camera_status_t;
#define MAVLINK_MSG_ID_CAMERA_STATUS_LEN 29
#define MAVLINK_MSG_ID_CAMERA_STATUS_MIN_LEN 29
#define MAVLINK_MSG_ID_179_LEN 29
#define MAVLINK_MSG_ID_179_MIN_LEN 29
#define MAVLINK_MSG_ID_CAMERA_STATUS_CRC 189
#define MAVLINK_MSG_ID_179_CRC 189
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_CAMERA_STATUS { \
179, \
"CAMERA_STATUS", \
9, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_camera_status_t, time_usec) }, \
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_camera_status_t, target_system) }, \
{ "cam_idx", NULL, MAVLINK_TYPE_UINT8_T, 0, 27, offsetof(mavlink_camera_status_t, cam_idx) }, \
{ "img_idx", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_camera_status_t, img_idx) }, \
{ "event_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_camera_status_t, event_id) }, \
{ "p1", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_camera_status_t, p1) }, \
{ "p2", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_camera_status_t, p2) }, \
{ "p3", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_camera_status_t, p3) }, \
{ "p4", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_camera_status_t, p4) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_CAMERA_STATUS { \
"CAMERA_STATUS", \
9, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_camera_status_t, time_usec) }, \
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_camera_status_t, target_system) }, \
{ "cam_idx", NULL, MAVLINK_TYPE_UINT8_T, 0, 27, offsetof(mavlink_camera_status_t, cam_idx) }, \
{ "img_idx", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_camera_status_t, img_idx) }, \
{ "event_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_camera_status_t, event_id) }, \
{ "p1", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_camera_status_t, p1) }, \
{ "p2", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_camera_status_t, p2) }, \
{ "p3", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_camera_status_t, p3) }, \
{ "p4", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_camera_status_t, p4) }, \
} \
}
#endif
/**
* @brief Pack a camera_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 time_usec [us] Image timestamp (since UNIX epoch, according to camera clock).
* @param target_system System ID.
* @param cam_idx Camera ID.
* @param img_idx Image index.
* @param event_id Event type.
* @param p1 Parameter 1 (meaning depends on event_id, see CAMERA_STATUS_TYPES enum).
* @param p2 Parameter 2 (meaning depends on event_id, see CAMERA_STATUS_TYPES enum).
* @param p3 Parameter 3 (meaning depends on event_id, see CAMERA_STATUS_TYPES enum).
* @param p4 Parameter 4 (meaning depends on event_id, see CAMERA_STATUS_TYPES enum).
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_camera_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint64_t time_usec, uint8_t target_system, uint8_t cam_idx, uint16_t img_idx, uint8_t event_id, float p1, float p2, float p3, float p4)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_CAMERA_STATUS_LEN];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_float(buf, 8, p1);
_mav_put_float(buf, 12, p2);
_mav_put_float(buf, 16, p3);
_mav_put_float(buf, 20, p4);
_mav_put_uint16_t(buf, 24, img_idx);
_mav_put_uint8_t(buf, 26, target_system);
_mav_put_uint8_t(buf, 27, cam_idx);
_mav_put_uint8_t(buf, 28, event_id);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CAMERA_STATUS_LEN);
#else
mavlink_camera_status_t packet;
packet.time_usec = time_usec;
packet.p1 = p1;
packet.p2 = p2;
packet.p3 = p3;
packet.p4 = p4;
packet.img_idx = img_idx;
packet.target_system = target_system;
packet.cam_idx = cam_idx;
packet.event_id = event_id;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CAMERA_STATUS_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_CAMERA_STATUS;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CAMERA_STATUS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_STATUS_LEN, MAVLINK_MSG_ID_CAMERA_STATUS_CRC);
}
/**
* @brief Pack a camera_status message on a channel
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_usec [us] Image timestamp (since UNIX epoch, according to camera clock).
* @param target_system System ID.
* @param cam_idx Camera ID.
* @param img_idx Image index.
* @param event_id Event type.
* @param p1 Parameter 1 (meaning depends on event_id, see CAMERA_STATUS_TYPES enum).
* @param p2 Parameter 2 (meaning depends on event_id, see CAMERA_STATUS_TYPES enum).
* @param p3 Parameter 3 (meaning depends on event_id, see CAMERA_STATUS_TYPES enum).
* @param p4 Parameter 4 (meaning depends on event_id, see CAMERA_STATUS_TYPES enum).
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_camera_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint64_t time_usec,uint8_t target_system,uint8_t cam_idx,uint16_t img_idx,uint8_t event_id,float p1,float p2,float p3,float p4)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_CAMERA_STATUS_LEN];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_float(buf, 8, p1);
_mav_put_float(buf, 12, p2);
_mav_put_float(buf, 16, p3);
_mav_put_float(buf, 20, p4);
_mav_put_uint16_t(buf, 24, img_idx);
_mav_put_uint8_t(buf, 26, target_system);
_mav_put_uint8_t(buf, 27, cam_idx);
_mav_put_uint8_t(buf, 28, event_id);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CAMERA_STATUS_LEN);
#else
mavlink_camera_status_t packet;
packet.time_usec = time_usec;
packet.p1 = p1;
packet.p2 = p2;
packet.p3 = p3;
packet.p4 = p4;
packet.img_idx = img_idx;
packet.target_system = target_system;
packet.cam_idx = cam_idx;
packet.event_id = event_id;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CAMERA_STATUS_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_CAMERA_STATUS;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CAMERA_STATUS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_STATUS_LEN, MAVLINK_MSG_ID_CAMERA_STATUS_CRC);
}
/**
* @brief Encode a camera_status struct
*
* @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 camera_status C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_camera_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_camera_status_t* camera_status)
{
return mavlink_msg_camera_status_pack(system_id, component_id, msg, camera_status->time_usec, camera_status->target_system, camera_status->cam_idx, camera_status->img_idx, camera_status->event_id, camera_status->p1, camera_status->p2, camera_status->p3, camera_status->p4);
}
/**
* @brief Encode a camera_status struct on a channel
*
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param camera_status C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_camera_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_camera_status_t* camera_status)
{
return mavlink_msg_camera_status_pack_chan(system_id, component_id, chan, msg, camera_status->time_usec, camera_status->target_system, camera_status->cam_idx, camera_status->img_idx, camera_status->event_id, camera_status->p1, camera_status->p2, camera_status->p3, camera_status->p4);
}
/**
* @brief Send a camera_status message
* @param chan MAVLink channel to send the message
*
* @param time_usec [us] Image timestamp (since UNIX epoch, according to camera clock).
* @param target_system System ID.
* @param cam_idx Camera ID.
* @param img_idx Image index.
* @param event_id Event type.
* @param p1 Parameter 1 (meaning depends on event_id, see CAMERA_STATUS_TYPES enum).
* @param p2 Parameter 2 (meaning depends on event_id, see CAMERA_STATUS_TYPES enum).
* @param p3 Parameter 3 (meaning depends on event_id, see CAMERA_STATUS_TYPES enum).
* @param p4 Parameter 4 (meaning depends on event_id, see CAMERA_STATUS_TYPES enum).
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_camera_status_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t target_system, uint8_t cam_idx, uint16_t img_idx, uint8_t event_id, float p1, float p2, float p3, float p4)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_CAMERA_STATUS_LEN];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_float(buf, 8, p1);
_mav_put_float(buf, 12, p2);
_mav_put_float(buf, 16, p3);
_mav_put_float(buf, 20, p4);
_mav_put_uint16_t(buf, 24, img_idx);
_mav_put_uint8_t(buf, 26, target_system);
_mav_put_uint8_t(buf, 27, cam_idx);
_mav_put_uint8_t(buf, 28, event_id);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_STATUS, buf, MAVLINK_MSG_ID_CAMERA_STATUS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_STATUS_LEN, MAVLINK_MSG_ID_CAMERA_STATUS_CRC);
#else
mavlink_camera_status_t packet;
packet.time_usec = time_usec;
packet.p1 = p1;
packet.p2 = p2;
packet.p3 = p3;
packet.p4 = p4;
packet.img_idx = img_idx;
packet.target_system = target_system;
packet.cam_idx = cam_idx;
packet.event_id = event_id;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_STATUS, (const char *)&packet, MAVLINK_MSG_ID_CAMERA_STATUS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_STATUS_LEN, MAVLINK_MSG_ID_CAMERA_STATUS_CRC);
#endif
}
/**
* @brief Send a camera_status message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_camera_status_send_struct(mavlink_channel_t chan, const mavlink_camera_status_t* camera_status)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_camera_status_send(chan, camera_status->time_usec, camera_status->target_system, camera_status->cam_idx, camera_status->img_idx, camera_status->event_id, camera_status->p1, camera_status->p2, camera_status->p3, camera_status->p4);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_STATUS, (const char *)camera_status, MAVLINK_MSG_ID_CAMERA_STATUS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_STATUS_LEN, MAVLINK_MSG_ID_CAMERA_STATUS_CRC);
#endif
}
#if MAVLINK_MSG_ID_CAMERA_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_camera_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint8_t target_system, uint8_t cam_idx, uint16_t img_idx, uint8_t event_id, float p1, float p2, float p3, float p4)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_float(buf, 8, p1);
_mav_put_float(buf, 12, p2);
_mav_put_float(buf, 16, p3);
_mav_put_float(buf, 20, p4);
_mav_put_uint16_t(buf, 24, img_idx);
_mav_put_uint8_t(buf, 26, target_system);
_mav_put_uint8_t(buf, 27, cam_idx);
_mav_put_uint8_t(buf, 28, event_id);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_STATUS, buf, MAVLINK_MSG_ID_CAMERA_STATUS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_STATUS_LEN, MAVLINK_MSG_ID_CAMERA_STATUS_CRC);
#else
mavlink_camera_status_t *packet = (mavlink_camera_status_t *)msgbuf;
packet->time_usec = time_usec;
packet->p1 = p1;
packet->p2 = p2;
packet->p3 = p3;
packet->p4 = p4;
packet->img_idx = img_idx;
packet->target_system = target_system;
packet->cam_idx = cam_idx;
packet->event_id = event_id;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_STATUS, (const char *)packet, MAVLINK_MSG_ID_CAMERA_STATUS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_STATUS_LEN, MAVLINK_MSG_ID_CAMERA_STATUS_CRC);
#endif
}
#endif
#endif
// MESSAGE CAMERA_STATUS UNPACKING
/**
* @brief Get field time_usec from camera_status message
*
* @return [us] Image timestamp (since UNIX epoch, according to camera clock).
*/
static inline uint64_t mavlink_msg_camera_status_get_time_usec(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint64_t(msg, 0);
}
/**
* @brief Get field target_system from camera_status message
*
* @return System ID.
*/
static inline uint8_t mavlink_msg_camera_status_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 26);
}
/**
* @brief Get field cam_idx from camera_status message
*
* @return Camera ID.
*/
static inline uint8_t mavlink_msg_camera_status_get_cam_idx(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 27);
}
/**
* @brief Get field img_idx from camera_status message
*
* @return Image index.
*/
static inline uint16_t mavlink_msg_camera_status_get_img_idx(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 24);
}
/**
* @brief Get field event_id from camera_status message
*
* @return Event type.
*/
static inline uint8_t mavlink_msg_camera_status_get_event_id(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 28);
}
/**
* @brief Get field p1 from camera_status message
*
* @return Parameter 1 (meaning depends on event_id, see CAMERA_STATUS_TYPES enum).
*/
static inline float mavlink_msg_camera_status_get_p1(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
/**
* @brief Get field p2 from camera_status message
*
* @return Parameter 2 (meaning depends on event_id, see CAMERA_STATUS_TYPES enum).
*/
static inline float mavlink_msg_camera_status_get_p2(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
/**
* @brief Get field p3 from camera_status message
*
* @return Parameter 3 (meaning depends on event_id, see CAMERA_STATUS_TYPES enum).
*/
static inline float mavlink_msg_camera_status_get_p3(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 16);
}
/**
* @brief Get field p4 from camera_status message
*
* @return Parameter 4 (meaning depends on event_id, see CAMERA_STATUS_TYPES enum).
*/
static inline float mavlink_msg_camera_status_get_p4(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 20);
}
/**
* @brief Decode a camera_status message into a struct
*
* @param msg The message to decode
* @param camera_status C-struct to decode the message contents into
*/
static inline void mavlink_msg_camera_status_decode(const mavlink_message_t* msg, mavlink_camera_status_t* camera_status)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
camera_status->time_usec = mavlink_msg_camera_status_get_time_usec(msg);
camera_status->p1 = mavlink_msg_camera_status_get_p1(msg);
camera_status->p2 = mavlink_msg_camera_status_get_p2(msg);
camera_status->p3 = mavlink_msg_camera_status_get_p3(msg);
camera_status->p4 = mavlink_msg_camera_status_get_p4(msg);
camera_status->img_idx = mavlink_msg_camera_status_get_img_idx(msg);
camera_status->target_system = mavlink_msg_camera_status_get_target_system(msg);
camera_status->cam_idx = mavlink_msg_camera_status_get_cam_idx(msg);
camera_status->event_id = mavlink_msg_camera_status_get_event_id(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_CAMERA_STATUS_LEN? msg->len : MAVLINK_MSG_ID_CAMERA_STATUS_LEN;
memset(camera_status, 0, MAVLINK_MSG_ID_CAMERA_STATUS_LEN);
memcpy(camera_status, _MAV_PAYLOAD(msg), len);
#endif
}

View File

@@ -0,0 +1,338 @@
#pragma once
// MESSAGE COMPASSMOT_STATUS PACKING
#define MAVLINK_MSG_ID_COMPASSMOT_STATUS 177
MAVPACKED(
typedef struct __mavlink_compassmot_status_t {
float current; /*< [A] Current.*/
float CompensationX; /*< Motor Compensation X.*/
float CompensationY; /*< Motor Compensation Y.*/
float CompensationZ; /*< Motor Compensation Z.*/
uint16_t throttle; /*< [d%] Throttle.*/
uint16_t interference; /*< [%] Interference.*/
}) mavlink_compassmot_status_t;
#define MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN 20
#define MAVLINK_MSG_ID_COMPASSMOT_STATUS_MIN_LEN 20
#define MAVLINK_MSG_ID_177_LEN 20
#define MAVLINK_MSG_ID_177_MIN_LEN 20
#define MAVLINK_MSG_ID_COMPASSMOT_STATUS_CRC 240
#define MAVLINK_MSG_ID_177_CRC 240
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_COMPASSMOT_STATUS { \
177, \
"COMPASSMOT_STATUS", \
6, \
{ { "throttle", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_compassmot_status_t, throttle) }, \
{ "current", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_compassmot_status_t, current) }, \
{ "interference", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_compassmot_status_t, interference) }, \
{ "CompensationX", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_compassmot_status_t, CompensationX) }, \
{ "CompensationY", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_compassmot_status_t, CompensationY) }, \
{ "CompensationZ", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_compassmot_status_t, CompensationZ) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_COMPASSMOT_STATUS { \
"COMPASSMOT_STATUS", \
6, \
{ { "throttle", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_compassmot_status_t, throttle) }, \
{ "current", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_compassmot_status_t, current) }, \
{ "interference", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_compassmot_status_t, interference) }, \
{ "CompensationX", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_compassmot_status_t, CompensationX) }, \
{ "CompensationY", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_compassmot_status_t, CompensationY) }, \
{ "CompensationZ", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_compassmot_status_t, CompensationZ) }, \
} \
}
#endif
/**
* @brief Pack a compassmot_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 throttle [d%] Throttle.
* @param current [A] Current.
* @param interference [%] Interference.
* @param CompensationX Motor Compensation X.
* @param CompensationY Motor Compensation Y.
* @param CompensationZ Motor Compensation Z.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_compassmot_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint16_t throttle, float current, uint16_t interference, float CompensationX, float CompensationY, float CompensationZ)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN];
_mav_put_float(buf, 0, current);
_mav_put_float(buf, 4, CompensationX);
_mav_put_float(buf, 8, CompensationY);
_mav_put_float(buf, 12, CompensationZ);
_mav_put_uint16_t(buf, 16, throttle);
_mav_put_uint16_t(buf, 18, interference);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN);
#else
mavlink_compassmot_status_t packet;
packet.current = current;
packet.CompensationX = CompensationX;
packet.CompensationY = CompensationY;
packet.CompensationZ = CompensationZ;
packet.throttle = throttle;
packet.interference = interference;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_COMPASSMOT_STATUS;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_COMPASSMOT_STATUS_MIN_LEN, MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN, MAVLINK_MSG_ID_COMPASSMOT_STATUS_CRC);
}
/**
* @brief Pack a compassmot_status message on a channel
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param throttle [d%] Throttle.
* @param current [A] Current.
* @param interference [%] Interference.
* @param CompensationX Motor Compensation X.
* @param CompensationY Motor Compensation Y.
* @param CompensationZ Motor Compensation Z.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_compassmot_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint16_t throttle,float current,uint16_t interference,float CompensationX,float CompensationY,float CompensationZ)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN];
_mav_put_float(buf, 0, current);
_mav_put_float(buf, 4, CompensationX);
_mav_put_float(buf, 8, CompensationY);
_mav_put_float(buf, 12, CompensationZ);
_mav_put_uint16_t(buf, 16, throttle);
_mav_put_uint16_t(buf, 18, interference);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN);
#else
mavlink_compassmot_status_t packet;
packet.current = current;
packet.CompensationX = CompensationX;
packet.CompensationY = CompensationY;
packet.CompensationZ = CompensationZ;
packet.throttle = throttle;
packet.interference = interference;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_COMPASSMOT_STATUS;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_COMPASSMOT_STATUS_MIN_LEN, MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN, MAVLINK_MSG_ID_COMPASSMOT_STATUS_CRC);
}
/**
* @brief Encode a compassmot_status struct
*
* @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 compassmot_status C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_compassmot_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_compassmot_status_t* compassmot_status)
{
return mavlink_msg_compassmot_status_pack(system_id, component_id, msg, compassmot_status->throttle, compassmot_status->current, compassmot_status->interference, compassmot_status->CompensationX, compassmot_status->CompensationY, compassmot_status->CompensationZ);
}
/**
* @brief Encode a compassmot_status struct on a channel
*
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param compassmot_status C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_compassmot_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_compassmot_status_t* compassmot_status)
{
return mavlink_msg_compassmot_status_pack_chan(system_id, component_id, chan, msg, compassmot_status->throttle, compassmot_status->current, compassmot_status->interference, compassmot_status->CompensationX, compassmot_status->CompensationY, compassmot_status->CompensationZ);
}
/**
* @brief Send a compassmot_status message
* @param chan MAVLink channel to send the message
*
* @param throttle [d%] Throttle.
* @param current [A] Current.
* @param interference [%] Interference.
* @param CompensationX Motor Compensation X.
* @param CompensationY Motor Compensation Y.
* @param CompensationZ Motor Compensation Z.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_compassmot_status_send(mavlink_channel_t chan, uint16_t throttle, float current, uint16_t interference, float CompensationX, float CompensationY, float CompensationZ)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN];
_mav_put_float(buf, 0, current);
_mav_put_float(buf, 4, CompensationX);
_mav_put_float(buf, 8, CompensationY);
_mav_put_float(buf, 12, CompensationZ);
_mav_put_uint16_t(buf, 16, throttle);
_mav_put_uint16_t(buf, 18, interference);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMPASSMOT_STATUS, buf, MAVLINK_MSG_ID_COMPASSMOT_STATUS_MIN_LEN, MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN, MAVLINK_MSG_ID_COMPASSMOT_STATUS_CRC);
#else
mavlink_compassmot_status_t packet;
packet.current = current;
packet.CompensationX = CompensationX;
packet.CompensationY = CompensationY;
packet.CompensationZ = CompensationZ;
packet.throttle = throttle;
packet.interference = interference;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMPASSMOT_STATUS, (const char *)&packet, MAVLINK_MSG_ID_COMPASSMOT_STATUS_MIN_LEN, MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN, MAVLINK_MSG_ID_COMPASSMOT_STATUS_CRC);
#endif
}
/**
* @brief Send a compassmot_status message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_compassmot_status_send_struct(mavlink_channel_t chan, const mavlink_compassmot_status_t* compassmot_status)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_compassmot_status_send(chan, compassmot_status->throttle, compassmot_status->current, compassmot_status->interference, compassmot_status->CompensationX, compassmot_status->CompensationY, compassmot_status->CompensationZ);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMPASSMOT_STATUS, (const char *)compassmot_status, MAVLINK_MSG_ID_COMPASSMOT_STATUS_MIN_LEN, MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN, MAVLINK_MSG_ID_COMPASSMOT_STATUS_CRC);
#endif
}
#if MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_compassmot_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t throttle, float current, uint16_t interference, float CompensationX, float CompensationY, float CompensationZ)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_float(buf, 0, current);
_mav_put_float(buf, 4, CompensationX);
_mav_put_float(buf, 8, CompensationY);
_mav_put_float(buf, 12, CompensationZ);
_mav_put_uint16_t(buf, 16, throttle);
_mav_put_uint16_t(buf, 18, interference);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMPASSMOT_STATUS, buf, MAVLINK_MSG_ID_COMPASSMOT_STATUS_MIN_LEN, MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN, MAVLINK_MSG_ID_COMPASSMOT_STATUS_CRC);
#else
mavlink_compassmot_status_t *packet = (mavlink_compassmot_status_t *)msgbuf;
packet->current = current;
packet->CompensationX = CompensationX;
packet->CompensationY = CompensationY;
packet->CompensationZ = CompensationZ;
packet->throttle = throttle;
packet->interference = interference;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMPASSMOT_STATUS, (const char *)packet, MAVLINK_MSG_ID_COMPASSMOT_STATUS_MIN_LEN, MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN, MAVLINK_MSG_ID_COMPASSMOT_STATUS_CRC);
#endif
}
#endif
#endif
// MESSAGE COMPASSMOT_STATUS UNPACKING
/**
* @brief Get field throttle from compassmot_status message
*
* @return [d%] Throttle.
*/
static inline uint16_t mavlink_msg_compassmot_status_get_throttle(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 16);
}
/**
* @brief Get field current from compassmot_status message
*
* @return [A] Current.
*/
static inline float mavlink_msg_compassmot_status_get_current(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 0);
}
/**
* @brief Get field interference from compassmot_status message
*
* @return [%] Interference.
*/
static inline uint16_t mavlink_msg_compassmot_status_get_interference(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 18);
}
/**
* @brief Get field CompensationX from compassmot_status message
*
* @return Motor Compensation X.
*/
static inline float mavlink_msg_compassmot_status_get_CompensationX(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 4);
}
/**
* @brief Get field CompensationY from compassmot_status message
*
* @return Motor Compensation Y.
*/
static inline float mavlink_msg_compassmot_status_get_CompensationY(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
/**
* @brief Get field CompensationZ from compassmot_status message
*
* @return Motor Compensation Z.
*/
static inline float mavlink_msg_compassmot_status_get_CompensationZ(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
/**
* @brief Decode a compassmot_status message into a struct
*
* @param msg The message to decode
* @param compassmot_status C-struct to decode the message contents into
*/
static inline void mavlink_msg_compassmot_status_decode(const mavlink_message_t* msg, mavlink_compassmot_status_t* compassmot_status)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
compassmot_status->current = mavlink_msg_compassmot_status_get_current(msg);
compassmot_status->CompensationX = mavlink_msg_compassmot_status_get_CompensationX(msg);
compassmot_status->CompensationY = mavlink_msg_compassmot_status_get_CompensationY(msg);
compassmot_status->CompensationZ = mavlink_msg_compassmot_status_get_CompensationZ(msg);
compassmot_status->throttle = mavlink_msg_compassmot_status_get_throttle(msg);
compassmot_status->interference = mavlink_msg_compassmot_status_get_interference(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN? msg->len : MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN;
memset(compassmot_status, 0, MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN);
memcpy(compassmot_status, _MAV_PAYLOAD(msg), len);
#endif
}

View File

@@ -0,0 +1,255 @@
#pragma once
// MESSAGE DATA16 PACKING
#define MAVLINK_MSG_ID_DATA16 169
MAVPACKED(
typedef struct __mavlink_data16_t {
uint8_t type; /*< Data type.*/
uint8_t len; /*< [bytes] Data length.*/
uint8_t data[16]; /*< Raw data.*/
}) mavlink_data16_t;
#define MAVLINK_MSG_ID_DATA16_LEN 18
#define MAVLINK_MSG_ID_DATA16_MIN_LEN 18
#define MAVLINK_MSG_ID_169_LEN 18
#define MAVLINK_MSG_ID_169_MIN_LEN 18
#define MAVLINK_MSG_ID_DATA16_CRC 234
#define MAVLINK_MSG_ID_169_CRC 234
#define MAVLINK_MSG_DATA16_FIELD_DATA_LEN 16
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_DATA16 { \
169, \
"DATA16", \
3, \
{ { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_data16_t, type) }, \
{ "len", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_data16_t, len) }, \
{ "data", NULL, MAVLINK_TYPE_UINT8_T, 16, 2, offsetof(mavlink_data16_t, data) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_DATA16 { \
"DATA16", \
3, \
{ { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_data16_t, type) }, \
{ "len", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_data16_t, len) }, \
{ "data", NULL, MAVLINK_TYPE_UINT8_T, 16, 2, offsetof(mavlink_data16_t, data) }, \
} \
}
#endif
/**
* @brief Pack a data16 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 Data type.
* @param len [bytes] Data length.
* @param data Raw data.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_data16_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t type, uint8_t len, const uint8_t *data)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_DATA16_LEN];
_mav_put_uint8_t(buf, 0, type);
_mav_put_uint8_t(buf, 1, len);
_mav_put_uint8_t_array(buf, 2, data, 16);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DATA16_LEN);
#else
mavlink_data16_t packet;
packet.type = type;
packet.len = len;
mav_array_memcpy(packet.data, data, sizeof(uint8_t)*16);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DATA16_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_DATA16;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DATA16_MIN_LEN, MAVLINK_MSG_ID_DATA16_LEN, MAVLINK_MSG_ID_DATA16_CRC);
}
/**
* @brief Pack a data16 message on a channel
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param type Data type.
* @param len [bytes] Data length.
* @param data Raw data.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_data16_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint8_t type,uint8_t len,const uint8_t *data)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_DATA16_LEN];
_mav_put_uint8_t(buf, 0, type);
_mav_put_uint8_t(buf, 1, len);
_mav_put_uint8_t_array(buf, 2, data, 16);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DATA16_LEN);
#else
mavlink_data16_t packet;
packet.type = type;
packet.len = len;
mav_array_memcpy(packet.data, data, sizeof(uint8_t)*16);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DATA16_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_DATA16;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DATA16_MIN_LEN, MAVLINK_MSG_ID_DATA16_LEN, MAVLINK_MSG_ID_DATA16_CRC);
}
/**
* @brief Encode a data16 struct
*
* @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 data16 C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_data16_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_data16_t* data16)
{
return mavlink_msg_data16_pack(system_id, component_id, msg, data16->type, data16->len, data16->data);
}
/**
* @brief Encode a data16 struct on a channel
*
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param data16 C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_data16_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_data16_t* data16)
{
return mavlink_msg_data16_pack_chan(system_id, component_id, chan, msg, data16->type, data16->len, data16->data);
}
/**
* @brief Send a data16 message
* @param chan MAVLink channel to send the message
*
* @param type Data type.
* @param len [bytes] Data length.
* @param data Raw data.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_data16_send(mavlink_channel_t chan, uint8_t type, uint8_t len, const uint8_t *data)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_DATA16_LEN];
_mav_put_uint8_t(buf, 0, type);
_mav_put_uint8_t(buf, 1, len);
_mav_put_uint8_t_array(buf, 2, data, 16);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA16, buf, MAVLINK_MSG_ID_DATA16_MIN_LEN, MAVLINK_MSG_ID_DATA16_LEN, MAVLINK_MSG_ID_DATA16_CRC);
#else
mavlink_data16_t packet;
packet.type = type;
packet.len = len;
mav_array_memcpy(packet.data, data, sizeof(uint8_t)*16);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA16, (const char *)&packet, MAVLINK_MSG_ID_DATA16_MIN_LEN, MAVLINK_MSG_ID_DATA16_LEN, MAVLINK_MSG_ID_DATA16_CRC);
#endif
}
/**
* @brief Send a data16 message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_data16_send_struct(mavlink_channel_t chan, const mavlink_data16_t* data16)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_data16_send(chan, data16->type, data16->len, data16->data);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA16, (const char *)data16, MAVLINK_MSG_ID_DATA16_MIN_LEN, MAVLINK_MSG_ID_DATA16_LEN, MAVLINK_MSG_ID_DATA16_CRC);
#endif
}
#if MAVLINK_MSG_ID_DATA16_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_data16_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t type, uint8_t len, const uint8_t *data)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint8_t(buf, 0, type);
_mav_put_uint8_t(buf, 1, len);
_mav_put_uint8_t_array(buf, 2, data, 16);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA16, buf, MAVLINK_MSG_ID_DATA16_MIN_LEN, MAVLINK_MSG_ID_DATA16_LEN, MAVLINK_MSG_ID_DATA16_CRC);
#else
mavlink_data16_t *packet = (mavlink_data16_t *)msgbuf;
packet->type = type;
packet->len = len;
mav_array_memcpy(packet->data, data, sizeof(uint8_t)*16);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA16, (const char *)packet, MAVLINK_MSG_ID_DATA16_MIN_LEN, MAVLINK_MSG_ID_DATA16_LEN, MAVLINK_MSG_ID_DATA16_CRC);
#endif
}
#endif
#endif
// MESSAGE DATA16 UNPACKING
/**
* @brief Get field type from data16 message
*
* @return Data type.
*/
static inline uint8_t mavlink_msg_data16_get_type(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 0);
}
/**
* @brief Get field len from data16 message
*
* @return [bytes] Data length.
*/
static inline uint8_t mavlink_msg_data16_get_len(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 1);
}
/**
* @brief Get field data from data16 message
*
* @return Raw data.
*/
static inline uint16_t mavlink_msg_data16_get_data(const mavlink_message_t* msg, uint8_t *data)
{
return _MAV_RETURN_uint8_t_array(msg, data, 16, 2);
}
/**
* @brief Decode a data16 message into a struct
*
* @param msg The message to decode
* @param data16 C-struct to decode the message contents into
*/
static inline void mavlink_msg_data16_decode(const mavlink_message_t* msg, mavlink_data16_t* data16)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
data16->type = mavlink_msg_data16_get_type(msg);
data16->len = mavlink_msg_data16_get_len(msg);
mavlink_msg_data16_get_data(msg, data16->data);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_DATA16_LEN? msg->len : MAVLINK_MSG_ID_DATA16_LEN;
memset(data16, 0, MAVLINK_MSG_ID_DATA16_LEN);
memcpy(data16, _MAV_PAYLOAD(msg), len);
#endif
}

View File

@@ -0,0 +1,255 @@
#pragma once
// MESSAGE DATA32 PACKING
#define MAVLINK_MSG_ID_DATA32 170
MAVPACKED(
typedef struct __mavlink_data32_t {
uint8_t type; /*< Data type.*/
uint8_t len; /*< [bytes] Data length.*/
uint8_t data[32]; /*< Raw data.*/
}) mavlink_data32_t;
#define MAVLINK_MSG_ID_DATA32_LEN 34
#define MAVLINK_MSG_ID_DATA32_MIN_LEN 34
#define MAVLINK_MSG_ID_170_LEN 34
#define MAVLINK_MSG_ID_170_MIN_LEN 34
#define MAVLINK_MSG_ID_DATA32_CRC 73
#define MAVLINK_MSG_ID_170_CRC 73
#define MAVLINK_MSG_DATA32_FIELD_DATA_LEN 32
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_DATA32 { \
170, \
"DATA32", \
3, \
{ { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_data32_t, type) }, \
{ "len", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_data32_t, len) }, \
{ "data", NULL, MAVLINK_TYPE_UINT8_T, 32, 2, offsetof(mavlink_data32_t, data) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_DATA32 { \
"DATA32", \
3, \
{ { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_data32_t, type) }, \
{ "len", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_data32_t, len) }, \
{ "data", NULL, MAVLINK_TYPE_UINT8_T, 32, 2, offsetof(mavlink_data32_t, data) }, \
} \
}
#endif
/**
* @brief Pack a data32 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 Data type.
* @param len [bytes] Data length.
* @param data Raw data.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_data32_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t type, uint8_t len, const uint8_t *data)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_DATA32_LEN];
_mav_put_uint8_t(buf, 0, type);
_mav_put_uint8_t(buf, 1, len);
_mav_put_uint8_t_array(buf, 2, data, 32);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DATA32_LEN);
#else
mavlink_data32_t packet;
packet.type = type;
packet.len = len;
mav_array_memcpy(packet.data, data, sizeof(uint8_t)*32);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DATA32_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_DATA32;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DATA32_MIN_LEN, MAVLINK_MSG_ID_DATA32_LEN, MAVLINK_MSG_ID_DATA32_CRC);
}
/**
* @brief Pack a data32 message on a channel
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param type Data type.
* @param len [bytes] Data length.
* @param data Raw data.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_data32_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint8_t type,uint8_t len,const uint8_t *data)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_DATA32_LEN];
_mav_put_uint8_t(buf, 0, type);
_mav_put_uint8_t(buf, 1, len);
_mav_put_uint8_t_array(buf, 2, data, 32);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DATA32_LEN);
#else
mavlink_data32_t packet;
packet.type = type;
packet.len = len;
mav_array_memcpy(packet.data, data, sizeof(uint8_t)*32);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DATA32_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_DATA32;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DATA32_MIN_LEN, MAVLINK_MSG_ID_DATA32_LEN, MAVLINK_MSG_ID_DATA32_CRC);
}
/**
* @brief Encode a data32 struct
*
* @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 data32 C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_data32_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_data32_t* data32)
{
return mavlink_msg_data32_pack(system_id, component_id, msg, data32->type, data32->len, data32->data);
}
/**
* @brief Encode a data32 struct on a channel
*
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param data32 C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_data32_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_data32_t* data32)
{
return mavlink_msg_data32_pack_chan(system_id, component_id, chan, msg, data32->type, data32->len, data32->data);
}
/**
* @brief Send a data32 message
* @param chan MAVLink channel to send the message
*
* @param type Data type.
* @param len [bytes] Data length.
* @param data Raw data.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_data32_send(mavlink_channel_t chan, uint8_t type, uint8_t len, const uint8_t *data)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_DATA32_LEN];
_mav_put_uint8_t(buf, 0, type);
_mav_put_uint8_t(buf, 1, len);
_mav_put_uint8_t_array(buf, 2, data, 32);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA32, buf, MAVLINK_MSG_ID_DATA32_MIN_LEN, MAVLINK_MSG_ID_DATA32_LEN, MAVLINK_MSG_ID_DATA32_CRC);
#else
mavlink_data32_t packet;
packet.type = type;
packet.len = len;
mav_array_memcpy(packet.data, data, sizeof(uint8_t)*32);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA32, (const char *)&packet, MAVLINK_MSG_ID_DATA32_MIN_LEN, MAVLINK_MSG_ID_DATA32_LEN, MAVLINK_MSG_ID_DATA32_CRC);
#endif
}
/**
* @brief Send a data32 message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_data32_send_struct(mavlink_channel_t chan, const mavlink_data32_t* data32)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_data32_send(chan, data32->type, data32->len, data32->data);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA32, (const char *)data32, MAVLINK_MSG_ID_DATA32_MIN_LEN, MAVLINK_MSG_ID_DATA32_LEN, MAVLINK_MSG_ID_DATA32_CRC);
#endif
}
#if MAVLINK_MSG_ID_DATA32_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_data32_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t type, uint8_t len, const uint8_t *data)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint8_t(buf, 0, type);
_mav_put_uint8_t(buf, 1, len);
_mav_put_uint8_t_array(buf, 2, data, 32);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA32, buf, MAVLINK_MSG_ID_DATA32_MIN_LEN, MAVLINK_MSG_ID_DATA32_LEN, MAVLINK_MSG_ID_DATA32_CRC);
#else
mavlink_data32_t *packet = (mavlink_data32_t *)msgbuf;
packet->type = type;
packet->len = len;
mav_array_memcpy(packet->data, data, sizeof(uint8_t)*32);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA32, (const char *)packet, MAVLINK_MSG_ID_DATA32_MIN_LEN, MAVLINK_MSG_ID_DATA32_LEN, MAVLINK_MSG_ID_DATA32_CRC);
#endif
}
#endif
#endif
// MESSAGE DATA32 UNPACKING
/**
* @brief Get field type from data32 message
*
* @return Data type.
*/
static inline uint8_t mavlink_msg_data32_get_type(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 0);
}
/**
* @brief Get field len from data32 message
*
* @return [bytes] Data length.
*/
static inline uint8_t mavlink_msg_data32_get_len(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 1);
}
/**
* @brief Get field data from data32 message
*
* @return Raw data.
*/
static inline uint16_t mavlink_msg_data32_get_data(const mavlink_message_t* msg, uint8_t *data)
{
return _MAV_RETURN_uint8_t_array(msg, data, 32, 2);
}
/**
* @brief Decode a data32 message into a struct
*
* @param msg The message to decode
* @param data32 C-struct to decode the message contents into
*/
static inline void mavlink_msg_data32_decode(const mavlink_message_t* msg, mavlink_data32_t* data32)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
data32->type = mavlink_msg_data32_get_type(msg);
data32->len = mavlink_msg_data32_get_len(msg);
mavlink_msg_data32_get_data(msg, data32->data);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_DATA32_LEN? msg->len : MAVLINK_MSG_ID_DATA32_LEN;
memset(data32, 0, MAVLINK_MSG_ID_DATA32_LEN);
memcpy(data32, _MAV_PAYLOAD(msg), len);
#endif
}

View File

@@ -0,0 +1,255 @@
#pragma once
// MESSAGE DATA64 PACKING
#define MAVLINK_MSG_ID_DATA64 171
MAVPACKED(
typedef struct __mavlink_data64_t {
uint8_t type; /*< Data type.*/
uint8_t len; /*< [bytes] Data length.*/
uint8_t data[64]; /*< Raw data.*/
}) mavlink_data64_t;
#define MAVLINK_MSG_ID_DATA64_LEN 66
#define MAVLINK_MSG_ID_DATA64_MIN_LEN 66
#define MAVLINK_MSG_ID_171_LEN 66
#define MAVLINK_MSG_ID_171_MIN_LEN 66
#define MAVLINK_MSG_ID_DATA64_CRC 181
#define MAVLINK_MSG_ID_171_CRC 181
#define MAVLINK_MSG_DATA64_FIELD_DATA_LEN 64
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_DATA64 { \
171, \
"DATA64", \
3, \
{ { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_data64_t, type) }, \
{ "len", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_data64_t, len) }, \
{ "data", NULL, MAVLINK_TYPE_UINT8_T, 64, 2, offsetof(mavlink_data64_t, data) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_DATA64 { \
"DATA64", \
3, \
{ { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_data64_t, type) }, \
{ "len", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_data64_t, len) }, \
{ "data", NULL, MAVLINK_TYPE_UINT8_T, 64, 2, offsetof(mavlink_data64_t, data) }, \
} \
}
#endif
/**
* @brief Pack a data64 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 Data type.
* @param len [bytes] Data length.
* @param data Raw data.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_data64_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t type, uint8_t len, const uint8_t *data)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_DATA64_LEN];
_mav_put_uint8_t(buf, 0, type);
_mav_put_uint8_t(buf, 1, len);
_mav_put_uint8_t_array(buf, 2, data, 64);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DATA64_LEN);
#else
mavlink_data64_t packet;
packet.type = type;
packet.len = len;
mav_array_memcpy(packet.data, data, sizeof(uint8_t)*64);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DATA64_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_DATA64;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DATA64_MIN_LEN, MAVLINK_MSG_ID_DATA64_LEN, MAVLINK_MSG_ID_DATA64_CRC);
}
/**
* @brief Pack a data64 message on a channel
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param type Data type.
* @param len [bytes] Data length.
* @param data Raw data.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_data64_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint8_t type,uint8_t len,const uint8_t *data)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_DATA64_LEN];
_mav_put_uint8_t(buf, 0, type);
_mav_put_uint8_t(buf, 1, len);
_mav_put_uint8_t_array(buf, 2, data, 64);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DATA64_LEN);
#else
mavlink_data64_t packet;
packet.type = type;
packet.len = len;
mav_array_memcpy(packet.data, data, sizeof(uint8_t)*64);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DATA64_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_DATA64;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DATA64_MIN_LEN, MAVLINK_MSG_ID_DATA64_LEN, MAVLINK_MSG_ID_DATA64_CRC);
}
/**
* @brief Encode a data64 struct
*
* @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 data64 C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_data64_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_data64_t* data64)
{
return mavlink_msg_data64_pack(system_id, component_id, msg, data64->type, data64->len, data64->data);
}
/**
* @brief Encode a data64 struct on a channel
*
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param data64 C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_data64_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_data64_t* data64)
{
return mavlink_msg_data64_pack_chan(system_id, component_id, chan, msg, data64->type, data64->len, data64->data);
}
/**
* @brief Send a data64 message
* @param chan MAVLink channel to send the message
*
* @param type Data type.
* @param len [bytes] Data length.
* @param data Raw data.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_data64_send(mavlink_channel_t chan, uint8_t type, uint8_t len, const uint8_t *data)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_DATA64_LEN];
_mav_put_uint8_t(buf, 0, type);
_mav_put_uint8_t(buf, 1, len);
_mav_put_uint8_t_array(buf, 2, data, 64);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA64, buf, MAVLINK_MSG_ID_DATA64_MIN_LEN, MAVLINK_MSG_ID_DATA64_LEN, MAVLINK_MSG_ID_DATA64_CRC);
#else
mavlink_data64_t packet;
packet.type = type;
packet.len = len;
mav_array_memcpy(packet.data, data, sizeof(uint8_t)*64);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA64, (const char *)&packet, MAVLINK_MSG_ID_DATA64_MIN_LEN, MAVLINK_MSG_ID_DATA64_LEN, MAVLINK_MSG_ID_DATA64_CRC);
#endif
}
/**
* @brief Send a data64 message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_data64_send_struct(mavlink_channel_t chan, const mavlink_data64_t* data64)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_data64_send(chan, data64->type, data64->len, data64->data);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA64, (const char *)data64, MAVLINK_MSG_ID_DATA64_MIN_LEN, MAVLINK_MSG_ID_DATA64_LEN, MAVLINK_MSG_ID_DATA64_CRC);
#endif
}
#if MAVLINK_MSG_ID_DATA64_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_data64_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t type, uint8_t len, const uint8_t *data)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint8_t(buf, 0, type);
_mav_put_uint8_t(buf, 1, len);
_mav_put_uint8_t_array(buf, 2, data, 64);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA64, buf, MAVLINK_MSG_ID_DATA64_MIN_LEN, MAVLINK_MSG_ID_DATA64_LEN, MAVLINK_MSG_ID_DATA64_CRC);
#else
mavlink_data64_t *packet = (mavlink_data64_t *)msgbuf;
packet->type = type;
packet->len = len;
mav_array_memcpy(packet->data, data, sizeof(uint8_t)*64);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA64, (const char *)packet, MAVLINK_MSG_ID_DATA64_MIN_LEN, MAVLINK_MSG_ID_DATA64_LEN, MAVLINK_MSG_ID_DATA64_CRC);
#endif
}
#endif
#endif
// MESSAGE DATA64 UNPACKING
/**
* @brief Get field type from data64 message
*
* @return Data type.
*/
static inline uint8_t mavlink_msg_data64_get_type(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 0);
}
/**
* @brief Get field len from data64 message
*
* @return [bytes] Data length.
*/
static inline uint8_t mavlink_msg_data64_get_len(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 1);
}
/**
* @brief Get field data from data64 message
*
* @return Raw data.
*/
static inline uint16_t mavlink_msg_data64_get_data(const mavlink_message_t* msg, uint8_t *data)
{
return _MAV_RETURN_uint8_t_array(msg, data, 64, 2);
}
/**
* @brief Decode a data64 message into a struct
*
* @param msg The message to decode
* @param data64 C-struct to decode the message contents into
*/
static inline void mavlink_msg_data64_decode(const mavlink_message_t* msg, mavlink_data64_t* data64)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
data64->type = mavlink_msg_data64_get_type(msg);
data64->len = mavlink_msg_data64_get_len(msg);
mavlink_msg_data64_get_data(msg, data64->data);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_DATA64_LEN? msg->len : MAVLINK_MSG_ID_DATA64_LEN;
memset(data64, 0, MAVLINK_MSG_ID_DATA64_LEN);
memcpy(data64, _MAV_PAYLOAD(msg), len);
#endif
}

View File

@@ -0,0 +1,255 @@
#pragma once
// MESSAGE DATA96 PACKING
#define MAVLINK_MSG_ID_DATA96 172
MAVPACKED(
typedef struct __mavlink_data96_t {
uint8_t type; /*< Data type.*/
uint8_t len; /*< [bytes] Data length.*/
uint8_t data[96]; /*< Raw data.*/
}) mavlink_data96_t;
#define MAVLINK_MSG_ID_DATA96_LEN 98
#define MAVLINK_MSG_ID_DATA96_MIN_LEN 98
#define MAVLINK_MSG_ID_172_LEN 98
#define MAVLINK_MSG_ID_172_MIN_LEN 98
#define MAVLINK_MSG_ID_DATA96_CRC 22
#define MAVLINK_MSG_ID_172_CRC 22
#define MAVLINK_MSG_DATA96_FIELD_DATA_LEN 96
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_DATA96 { \
172, \
"DATA96", \
3, \
{ { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_data96_t, type) }, \
{ "len", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_data96_t, len) }, \
{ "data", NULL, MAVLINK_TYPE_UINT8_T, 96, 2, offsetof(mavlink_data96_t, data) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_DATA96 { \
"DATA96", \
3, \
{ { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_data96_t, type) }, \
{ "len", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_data96_t, len) }, \
{ "data", NULL, MAVLINK_TYPE_UINT8_T, 96, 2, offsetof(mavlink_data96_t, data) }, \
} \
}
#endif
/**
* @brief Pack a data96 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 Data type.
* @param len [bytes] Data length.
* @param data Raw data.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_data96_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t type, uint8_t len, const uint8_t *data)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_DATA96_LEN];
_mav_put_uint8_t(buf, 0, type);
_mav_put_uint8_t(buf, 1, len);
_mav_put_uint8_t_array(buf, 2, data, 96);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DATA96_LEN);
#else
mavlink_data96_t packet;
packet.type = type;
packet.len = len;
mav_array_memcpy(packet.data, data, sizeof(uint8_t)*96);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DATA96_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_DATA96;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DATA96_MIN_LEN, MAVLINK_MSG_ID_DATA96_LEN, MAVLINK_MSG_ID_DATA96_CRC);
}
/**
* @brief Pack a data96 message on a channel
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param type Data type.
* @param len [bytes] Data length.
* @param data Raw data.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_data96_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint8_t type,uint8_t len,const uint8_t *data)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_DATA96_LEN];
_mav_put_uint8_t(buf, 0, type);
_mav_put_uint8_t(buf, 1, len);
_mav_put_uint8_t_array(buf, 2, data, 96);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DATA96_LEN);
#else
mavlink_data96_t packet;
packet.type = type;
packet.len = len;
mav_array_memcpy(packet.data, data, sizeof(uint8_t)*96);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DATA96_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_DATA96;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DATA96_MIN_LEN, MAVLINK_MSG_ID_DATA96_LEN, MAVLINK_MSG_ID_DATA96_CRC);
}
/**
* @brief Encode a data96 struct
*
* @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 data96 C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_data96_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_data96_t* data96)
{
return mavlink_msg_data96_pack(system_id, component_id, msg, data96->type, data96->len, data96->data);
}
/**
* @brief Encode a data96 struct on a channel
*
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param data96 C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_data96_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_data96_t* data96)
{
return mavlink_msg_data96_pack_chan(system_id, component_id, chan, msg, data96->type, data96->len, data96->data);
}
/**
* @brief Send a data96 message
* @param chan MAVLink channel to send the message
*
* @param type Data type.
* @param len [bytes] Data length.
* @param data Raw data.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_data96_send(mavlink_channel_t chan, uint8_t type, uint8_t len, const uint8_t *data)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_DATA96_LEN];
_mav_put_uint8_t(buf, 0, type);
_mav_put_uint8_t(buf, 1, len);
_mav_put_uint8_t_array(buf, 2, data, 96);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA96, buf, MAVLINK_MSG_ID_DATA96_MIN_LEN, MAVLINK_MSG_ID_DATA96_LEN, MAVLINK_MSG_ID_DATA96_CRC);
#else
mavlink_data96_t packet;
packet.type = type;
packet.len = len;
mav_array_memcpy(packet.data, data, sizeof(uint8_t)*96);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA96, (const char *)&packet, MAVLINK_MSG_ID_DATA96_MIN_LEN, MAVLINK_MSG_ID_DATA96_LEN, MAVLINK_MSG_ID_DATA96_CRC);
#endif
}
/**
* @brief Send a data96 message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_data96_send_struct(mavlink_channel_t chan, const mavlink_data96_t* data96)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_data96_send(chan, data96->type, data96->len, data96->data);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA96, (const char *)data96, MAVLINK_MSG_ID_DATA96_MIN_LEN, MAVLINK_MSG_ID_DATA96_LEN, MAVLINK_MSG_ID_DATA96_CRC);
#endif
}
#if MAVLINK_MSG_ID_DATA96_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_data96_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t type, uint8_t len, const uint8_t *data)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint8_t(buf, 0, type);
_mav_put_uint8_t(buf, 1, len);
_mav_put_uint8_t_array(buf, 2, data, 96);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA96, buf, MAVLINK_MSG_ID_DATA96_MIN_LEN, MAVLINK_MSG_ID_DATA96_LEN, MAVLINK_MSG_ID_DATA96_CRC);
#else
mavlink_data96_t *packet = (mavlink_data96_t *)msgbuf;
packet->type = type;
packet->len = len;
mav_array_memcpy(packet->data, data, sizeof(uint8_t)*96);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA96, (const char *)packet, MAVLINK_MSG_ID_DATA96_MIN_LEN, MAVLINK_MSG_ID_DATA96_LEN, MAVLINK_MSG_ID_DATA96_CRC);
#endif
}
#endif
#endif
// MESSAGE DATA96 UNPACKING
/**
* @brief Get field type from data96 message
*
* @return Data type.
*/
static inline uint8_t mavlink_msg_data96_get_type(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 0);
}
/**
* @brief Get field len from data96 message
*
* @return [bytes] Data length.
*/
static inline uint8_t mavlink_msg_data96_get_len(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 1);
}
/**
* @brief Get field data from data96 message
*
* @return Raw data.
*/
static inline uint16_t mavlink_msg_data96_get_data(const mavlink_message_t* msg, uint8_t *data)
{
return _MAV_RETURN_uint8_t_array(msg, data, 96, 2);
}
/**
* @brief Decode a data96 message into a struct
*
* @param msg The message to decode
* @param data96 C-struct to decode the message contents into
*/
static inline void mavlink_msg_data96_decode(const mavlink_message_t* msg, mavlink_data96_t* data96)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
data96->type = mavlink_msg_data96_get_type(msg);
data96->len = mavlink_msg_data96_get_len(msg);
mavlink_msg_data96_get_data(msg, data96->data);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_DATA96_LEN? msg->len : MAVLINK_MSG_ID_DATA96_LEN;
memset(data96, 0, MAVLINK_MSG_ID_DATA96_LEN);
memcpy(data96, _MAV_PAYLOAD(msg), len);
#endif
}

View File

@@ -0,0 +1,438 @@
#pragma once
// MESSAGE DEEPSTALL PACKING
#define MAVLINK_MSG_ID_DEEPSTALL 195
MAVPACKED(
typedef struct __mavlink_deepstall_t {
int32_t landing_lat; /*< [degE7] Landing latitude.*/
int32_t landing_lon; /*< [degE7] Landing longitude.*/
int32_t path_lat; /*< [degE7] Final heading start point, latitude.*/
int32_t path_lon; /*< [degE7] Final heading start point, longitude.*/
int32_t arc_entry_lat; /*< [degE7] Arc entry point, latitude.*/
int32_t arc_entry_lon; /*< [degE7] Arc entry point, longitude.*/
float altitude; /*< [m] Altitude.*/
float expected_travel_distance; /*< [m] Distance the aircraft expects to travel during the deepstall.*/
float cross_track_error; /*< [m] Deepstall cross track error (only valid when in DEEPSTALL_STAGE_LAND).*/
uint8_t stage; /*< Deepstall stage.*/
}) mavlink_deepstall_t;
#define MAVLINK_MSG_ID_DEEPSTALL_LEN 37
#define MAVLINK_MSG_ID_DEEPSTALL_MIN_LEN 37
#define MAVLINK_MSG_ID_195_LEN 37
#define MAVLINK_MSG_ID_195_MIN_LEN 37
#define MAVLINK_MSG_ID_DEEPSTALL_CRC 120
#define MAVLINK_MSG_ID_195_CRC 120
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_DEEPSTALL { \
195, \
"DEEPSTALL", \
10, \
{ { "landing_lat", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_deepstall_t, landing_lat) }, \
{ "landing_lon", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_deepstall_t, landing_lon) }, \
{ "path_lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_deepstall_t, path_lat) }, \
{ "path_lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_deepstall_t, path_lon) }, \
{ "arc_entry_lat", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_deepstall_t, arc_entry_lat) }, \
{ "arc_entry_lon", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_deepstall_t, arc_entry_lon) }, \
{ "altitude", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_deepstall_t, altitude) }, \
{ "expected_travel_distance", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_deepstall_t, expected_travel_distance) }, \
{ "cross_track_error", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_deepstall_t, cross_track_error) }, \
{ "stage", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_deepstall_t, stage) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_DEEPSTALL { \
"DEEPSTALL", \
10, \
{ { "landing_lat", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_deepstall_t, landing_lat) }, \
{ "landing_lon", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_deepstall_t, landing_lon) }, \
{ "path_lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_deepstall_t, path_lat) }, \
{ "path_lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_deepstall_t, path_lon) }, \
{ "arc_entry_lat", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_deepstall_t, arc_entry_lat) }, \
{ "arc_entry_lon", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_deepstall_t, arc_entry_lon) }, \
{ "altitude", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_deepstall_t, altitude) }, \
{ "expected_travel_distance", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_deepstall_t, expected_travel_distance) }, \
{ "cross_track_error", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_deepstall_t, cross_track_error) }, \
{ "stage", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_deepstall_t, stage) }, \
} \
}
#endif
/**
* @brief Pack a deepstall 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 landing_lat [degE7] Landing latitude.
* @param landing_lon [degE7] Landing longitude.
* @param path_lat [degE7] Final heading start point, latitude.
* @param path_lon [degE7] Final heading start point, longitude.
* @param arc_entry_lat [degE7] Arc entry point, latitude.
* @param arc_entry_lon [degE7] Arc entry point, longitude.
* @param altitude [m] Altitude.
* @param expected_travel_distance [m] Distance the aircraft expects to travel during the deepstall.
* @param cross_track_error [m] Deepstall cross track error (only valid when in DEEPSTALL_STAGE_LAND).
* @param stage Deepstall stage.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_deepstall_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
int32_t landing_lat, int32_t landing_lon, int32_t path_lat, int32_t path_lon, int32_t arc_entry_lat, int32_t arc_entry_lon, float altitude, float expected_travel_distance, float cross_track_error, uint8_t stage)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_DEEPSTALL_LEN];
_mav_put_int32_t(buf, 0, landing_lat);
_mav_put_int32_t(buf, 4, landing_lon);
_mav_put_int32_t(buf, 8, path_lat);
_mav_put_int32_t(buf, 12, path_lon);
_mav_put_int32_t(buf, 16, arc_entry_lat);
_mav_put_int32_t(buf, 20, arc_entry_lon);
_mav_put_float(buf, 24, altitude);
_mav_put_float(buf, 28, expected_travel_distance);
_mav_put_float(buf, 32, cross_track_error);
_mav_put_uint8_t(buf, 36, stage);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DEEPSTALL_LEN);
#else
mavlink_deepstall_t packet;
packet.landing_lat = landing_lat;
packet.landing_lon = landing_lon;
packet.path_lat = path_lat;
packet.path_lon = path_lon;
packet.arc_entry_lat = arc_entry_lat;
packet.arc_entry_lon = arc_entry_lon;
packet.altitude = altitude;
packet.expected_travel_distance = expected_travel_distance;
packet.cross_track_error = cross_track_error;
packet.stage = stage;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DEEPSTALL_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_DEEPSTALL;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DEEPSTALL_MIN_LEN, MAVLINK_MSG_ID_DEEPSTALL_LEN, MAVLINK_MSG_ID_DEEPSTALL_CRC);
}
/**
* @brief Pack a deepstall message on a channel
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param landing_lat [degE7] Landing latitude.
* @param landing_lon [degE7] Landing longitude.
* @param path_lat [degE7] Final heading start point, latitude.
* @param path_lon [degE7] Final heading start point, longitude.
* @param arc_entry_lat [degE7] Arc entry point, latitude.
* @param arc_entry_lon [degE7] Arc entry point, longitude.
* @param altitude [m] Altitude.
* @param expected_travel_distance [m] Distance the aircraft expects to travel during the deepstall.
* @param cross_track_error [m] Deepstall cross track error (only valid when in DEEPSTALL_STAGE_LAND).
* @param stage Deepstall stage.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_deepstall_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
int32_t landing_lat,int32_t landing_lon,int32_t path_lat,int32_t path_lon,int32_t arc_entry_lat,int32_t arc_entry_lon,float altitude,float expected_travel_distance,float cross_track_error,uint8_t stage)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_DEEPSTALL_LEN];
_mav_put_int32_t(buf, 0, landing_lat);
_mav_put_int32_t(buf, 4, landing_lon);
_mav_put_int32_t(buf, 8, path_lat);
_mav_put_int32_t(buf, 12, path_lon);
_mav_put_int32_t(buf, 16, arc_entry_lat);
_mav_put_int32_t(buf, 20, arc_entry_lon);
_mav_put_float(buf, 24, altitude);
_mav_put_float(buf, 28, expected_travel_distance);
_mav_put_float(buf, 32, cross_track_error);
_mav_put_uint8_t(buf, 36, stage);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DEEPSTALL_LEN);
#else
mavlink_deepstall_t packet;
packet.landing_lat = landing_lat;
packet.landing_lon = landing_lon;
packet.path_lat = path_lat;
packet.path_lon = path_lon;
packet.arc_entry_lat = arc_entry_lat;
packet.arc_entry_lon = arc_entry_lon;
packet.altitude = altitude;
packet.expected_travel_distance = expected_travel_distance;
packet.cross_track_error = cross_track_error;
packet.stage = stage;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DEEPSTALL_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_DEEPSTALL;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DEEPSTALL_MIN_LEN, MAVLINK_MSG_ID_DEEPSTALL_LEN, MAVLINK_MSG_ID_DEEPSTALL_CRC);
}
/**
* @brief Encode a deepstall struct
*
* @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 deepstall C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_deepstall_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_deepstall_t* deepstall)
{
return mavlink_msg_deepstall_pack(system_id, component_id, msg, deepstall->landing_lat, deepstall->landing_lon, deepstall->path_lat, deepstall->path_lon, deepstall->arc_entry_lat, deepstall->arc_entry_lon, deepstall->altitude, deepstall->expected_travel_distance, deepstall->cross_track_error, deepstall->stage);
}
/**
* @brief Encode a deepstall struct on a channel
*
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param deepstall C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_deepstall_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_deepstall_t* deepstall)
{
return mavlink_msg_deepstall_pack_chan(system_id, component_id, chan, msg, deepstall->landing_lat, deepstall->landing_lon, deepstall->path_lat, deepstall->path_lon, deepstall->arc_entry_lat, deepstall->arc_entry_lon, deepstall->altitude, deepstall->expected_travel_distance, deepstall->cross_track_error, deepstall->stage);
}
/**
* @brief Send a deepstall message
* @param chan MAVLink channel to send the message
*
* @param landing_lat [degE7] Landing latitude.
* @param landing_lon [degE7] Landing longitude.
* @param path_lat [degE7] Final heading start point, latitude.
* @param path_lon [degE7] Final heading start point, longitude.
* @param arc_entry_lat [degE7] Arc entry point, latitude.
* @param arc_entry_lon [degE7] Arc entry point, longitude.
* @param altitude [m] Altitude.
* @param expected_travel_distance [m] Distance the aircraft expects to travel during the deepstall.
* @param cross_track_error [m] Deepstall cross track error (only valid when in DEEPSTALL_STAGE_LAND).
* @param stage Deepstall stage.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_deepstall_send(mavlink_channel_t chan, int32_t landing_lat, int32_t landing_lon, int32_t path_lat, int32_t path_lon, int32_t arc_entry_lat, int32_t arc_entry_lon, float altitude, float expected_travel_distance, float cross_track_error, uint8_t stage)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_DEEPSTALL_LEN];
_mav_put_int32_t(buf, 0, landing_lat);
_mav_put_int32_t(buf, 4, landing_lon);
_mav_put_int32_t(buf, 8, path_lat);
_mav_put_int32_t(buf, 12, path_lon);
_mav_put_int32_t(buf, 16, arc_entry_lat);
_mav_put_int32_t(buf, 20, arc_entry_lon);
_mav_put_float(buf, 24, altitude);
_mav_put_float(buf, 28, expected_travel_distance);
_mav_put_float(buf, 32, cross_track_error);
_mav_put_uint8_t(buf, 36, stage);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEEPSTALL, buf, MAVLINK_MSG_ID_DEEPSTALL_MIN_LEN, MAVLINK_MSG_ID_DEEPSTALL_LEN, MAVLINK_MSG_ID_DEEPSTALL_CRC);
#else
mavlink_deepstall_t packet;
packet.landing_lat = landing_lat;
packet.landing_lon = landing_lon;
packet.path_lat = path_lat;
packet.path_lon = path_lon;
packet.arc_entry_lat = arc_entry_lat;
packet.arc_entry_lon = arc_entry_lon;
packet.altitude = altitude;
packet.expected_travel_distance = expected_travel_distance;
packet.cross_track_error = cross_track_error;
packet.stage = stage;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEEPSTALL, (const char *)&packet, MAVLINK_MSG_ID_DEEPSTALL_MIN_LEN, MAVLINK_MSG_ID_DEEPSTALL_LEN, MAVLINK_MSG_ID_DEEPSTALL_CRC);
#endif
}
/**
* @brief Send a deepstall message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_deepstall_send_struct(mavlink_channel_t chan, const mavlink_deepstall_t* deepstall)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_deepstall_send(chan, deepstall->landing_lat, deepstall->landing_lon, deepstall->path_lat, deepstall->path_lon, deepstall->arc_entry_lat, deepstall->arc_entry_lon, deepstall->altitude, deepstall->expected_travel_distance, deepstall->cross_track_error, deepstall->stage);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEEPSTALL, (const char *)deepstall, MAVLINK_MSG_ID_DEEPSTALL_MIN_LEN, MAVLINK_MSG_ID_DEEPSTALL_LEN, MAVLINK_MSG_ID_DEEPSTALL_CRC);
#endif
}
#if MAVLINK_MSG_ID_DEEPSTALL_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_deepstall_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, int32_t landing_lat, int32_t landing_lon, int32_t path_lat, int32_t path_lon, int32_t arc_entry_lat, int32_t arc_entry_lon, float altitude, float expected_travel_distance, float cross_track_error, uint8_t stage)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_int32_t(buf, 0, landing_lat);
_mav_put_int32_t(buf, 4, landing_lon);
_mav_put_int32_t(buf, 8, path_lat);
_mav_put_int32_t(buf, 12, path_lon);
_mav_put_int32_t(buf, 16, arc_entry_lat);
_mav_put_int32_t(buf, 20, arc_entry_lon);
_mav_put_float(buf, 24, altitude);
_mav_put_float(buf, 28, expected_travel_distance);
_mav_put_float(buf, 32, cross_track_error);
_mav_put_uint8_t(buf, 36, stage);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEEPSTALL, buf, MAVLINK_MSG_ID_DEEPSTALL_MIN_LEN, MAVLINK_MSG_ID_DEEPSTALL_LEN, MAVLINK_MSG_ID_DEEPSTALL_CRC);
#else
mavlink_deepstall_t *packet = (mavlink_deepstall_t *)msgbuf;
packet->landing_lat = landing_lat;
packet->landing_lon = landing_lon;
packet->path_lat = path_lat;
packet->path_lon = path_lon;
packet->arc_entry_lat = arc_entry_lat;
packet->arc_entry_lon = arc_entry_lon;
packet->altitude = altitude;
packet->expected_travel_distance = expected_travel_distance;
packet->cross_track_error = cross_track_error;
packet->stage = stage;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEEPSTALL, (const char *)packet, MAVLINK_MSG_ID_DEEPSTALL_MIN_LEN, MAVLINK_MSG_ID_DEEPSTALL_LEN, MAVLINK_MSG_ID_DEEPSTALL_CRC);
#endif
}
#endif
#endif
// MESSAGE DEEPSTALL UNPACKING
/**
* @brief Get field landing_lat from deepstall message
*
* @return [degE7] Landing latitude.
*/
static inline int32_t mavlink_msg_deepstall_get_landing_lat(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 0);
}
/**
* @brief Get field landing_lon from deepstall message
*
* @return [degE7] Landing longitude.
*/
static inline int32_t mavlink_msg_deepstall_get_landing_lon(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 4);
}
/**
* @brief Get field path_lat from deepstall message
*
* @return [degE7] Final heading start point, latitude.
*/
static inline int32_t mavlink_msg_deepstall_get_path_lat(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 8);
}
/**
* @brief Get field path_lon from deepstall message
*
* @return [degE7] Final heading start point, longitude.
*/
static inline int32_t mavlink_msg_deepstall_get_path_lon(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 12);
}
/**
* @brief Get field arc_entry_lat from deepstall message
*
* @return [degE7] Arc entry point, latitude.
*/
static inline int32_t mavlink_msg_deepstall_get_arc_entry_lat(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 16);
}
/**
* @brief Get field arc_entry_lon from deepstall message
*
* @return [degE7] Arc entry point, longitude.
*/
static inline int32_t mavlink_msg_deepstall_get_arc_entry_lon(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 20);
}
/**
* @brief Get field altitude from deepstall message
*
* @return [m] Altitude.
*/
static inline float mavlink_msg_deepstall_get_altitude(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 24);
}
/**
* @brief Get field expected_travel_distance from deepstall message
*
* @return [m] Distance the aircraft expects to travel during the deepstall.
*/
static inline float mavlink_msg_deepstall_get_expected_travel_distance(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 28);
}
/**
* @brief Get field cross_track_error from deepstall message
*
* @return [m] Deepstall cross track error (only valid when in DEEPSTALL_STAGE_LAND).
*/
static inline float mavlink_msg_deepstall_get_cross_track_error(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 32);
}
/**
* @brief Get field stage from deepstall message
*
* @return Deepstall stage.
*/
static inline uint8_t mavlink_msg_deepstall_get_stage(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 36);
}
/**
* @brief Decode a deepstall message into a struct
*
* @param msg The message to decode
* @param deepstall C-struct to decode the message contents into
*/
static inline void mavlink_msg_deepstall_decode(const mavlink_message_t* msg, mavlink_deepstall_t* deepstall)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
deepstall->landing_lat = mavlink_msg_deepstall_get_landing_lat(msg);
deepstall->landing_lon = mavlink_msg_deepstall_get_landing_lon(msg);
deepstall->path_lat = mavlink_msg_deepstall_get_path_lat(msg);
deepstall->path_lon = mavlink_msg_deepstall_get_path_lon(msg);
deepstall->arc_entry_lat = mavlink_msg_deepstall_get_arc_entry_lat(msg);
deepstall->arc_entry_lon = mavlink_msg_deepstall_get_arc_entry_lon(msg);
deepstall->altitude = mavlink_msg_deepstall_get_altitude(msg);
deepstall->expected_travel_distance = mavlink_msg_deepstall_get_expected_travel_distance(msg);
deepstall->cross_track_error = mavlink_msg_deepstall_get_cross_track_error(msg);
deepstall->stage = mavlink_msg_deepstall_get_stage(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_DEEPSTALL_LEN? msg->len : MAVLINK_MSG_ID_DEEPSTALL_LEN;
memset(deepstall, 0, MAVLINK_MSG_ID_DEEPSTALL_LEN);
memcpy(deepstall, _MAV_PAYLOAD(msg), len);
#endif
}

View File

@@ -0,0 +1,405 @@
#pragma once
// MESSAGE DEVICE_OP_READ PACKING
#define MAVLINK_MSG_ID_DEVICE_OP_READ 11000
MAVPACKED(
typedef struct __mavlink_device_op_read_t {
uint32_t request_id; /*< Request ID - copied to reply.*/
uint8_t target_system; /*< System ID.*/
uint8_t target_component; /*< Component ID.*/
uint8_t bustype; /*< The bus type.*/
uint8_t bus; /*< Bus number.*/
uint8_t address; /*< Bus address.*/
char busname[40]; /*< Name of device on bus (for SPI).*/
uint8_t regstart; /*< First register to read.*/
uint8_t count; /*< Count of registers to read.*/
}) mavlink_device_op_read_t;
#define MAVLINK_MSG_ID_DEVICE_OP_READ_LEN 51
#define MAVLINK_MSG_ID_DEVICE_OP_READ_MIN_LEN 51
#define MAVLINK_MSG_ID_11000_LEN 51
#define MAVLINK_MSG_ID_11000_MIN_LEN 51
#define MAVLINK_MSG_ID_DEVICE_OP_READ_CRC 134
#define MAVLINK_MSG_ID_11000_CRC 134
#define MAVLINK_MSG_DEVICE_OP_READ_FIELD_BUSNAME_LEN 40
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_DEVICE_OP_READ { \
11000, \
"DEVICE_OP_READ", \
9, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_device_op_read_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_device_op_read_t, target_component) }, \
{ "request_id", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_device_op_read_t, request_id) }, \
{ "bustype", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_device_op_read_t, bustype) }, \
{ "bus", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_device_op_read_t, bus) }, \
{ "address", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_device_op_read_t, address) }, \
{ "busname", NULL, MAVLINK_TYPE_CHAR, 40, 9, offsetof(mavlink_device_op_read_t, busname) }, \
{ "regstart", NULL, MAVLINK_TYPE_UINT8_T, 0, 49, offsetof(mavlink_device_op_read_t, regstart) }, \
{ "count", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_device_op_read_t, count) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_DEVICE_OP_READ { \
"DEVICE_OP_READ", \
9, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_device_op_read_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_device_op_read_t, target_component) }, \
{ "request_id", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_device_op_read_t, request_id) }, \
{ "bustype", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_device_op_read_t, bustype) }, \
{ "bus", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_device_op_read_t, bus) }, \
{ "address", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_device_op_read_t, address) }, \
{ "busname", NULL, MAVLINK_TYPE_CHAR, 40, 9, offsetof(mavlink_device_op_read_t, busname) }, \
{ "regstart", NULL, MAVLINK_TYPE_UINT8_T, 0, 49, offsetof(mavlink_device_op_read_t, regstart) }, \
{ "count", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_device_op_read_t, count) }, \
} \
}
#endif
/**
* @brief Pack a device_op_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.
* @param request_id Request ID - copied to reply.
* @param bustype The bus type.
* @param bus Bus number.
* @param address Bus address.
* @param busname Name of device on bus (for SPI).
* @param regstart First register to read.
* @param count Count of registers to read.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_device_op_read_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, uint32_t request_id, uint8_t bustype, uint8_t bus, uint8_t address, const char *busname, uint8_t regstart, uint8_t count)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_DEVICE_OP_READ_LEN];
_mav_put_uint32_t(buf, 0, request_id);
_mav_put_uint8_t(buf, 4, target_system);
_mav_put_uint8_t(buf, 5, target_component);
_mav_put_uint8_t(buf, 6, bustype);
_mav_put_uint8_t(buf, 7, bus);
_mav_put_uint8_t(buf, 8, address);
_mav_put_uint8_t(buf, 49, regstart);
_mav_put_uint8_t(buf, 50, count);
_mav_put_char_array(buf, 9, busname, 40);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DEVICE_OP_READ_LEN);
#else
mavlink_device_op_read_t packet;
packet.request_id = request_id;
packet.target_system = target_system;
packet.target_component = target_component;
packet.bustype = bustype;
packet.bus = bus;
packet.address = address;
packet.regstart = regstart;
packet.count = count;
mav_array_memcpy(packet.busname, busname, sizeof(char)*40);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DEVICE_OP_READ_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_DEVICE_OP_READ;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DEVICE_OP_READ_MIN_LEN, MAVLINK_MSG_ID_DEVICE_OP_READ_LEN, MAVLINK_MSG_ID_DEVICE_OP_READ_CRC);
}
/**
* @brief Pack a device_op_read message on a channel
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID.
* @param target_component Component ID.
* @param request_id Request ID - copied to reply.
* @param bustype The bus type.
* @param bus Bus number.
* @param address Bus address.
* @param busname Name of device on bus (for SPI).
* @param regstart First register to read.
* @param count Count of registers to read.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_device_op_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,uint32_t request_id,uint8_t bustype,uint8_t bus,uint8_t address,const char *busname,uint8_t regstart,uint8_t count)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_DEVICE_OP_READ_LEN];
_mav_put_uint32_t(buf, 0, request_id);
_mav_put_uint8_t(buf, 4, target_system);
_mav_put_uint8_t(buf, 5, target_component);
_mav_put_uint8_t(buf, 6, bustype);
_mav_put_uint8_t(buf, 7, bus);
_mav_put_uint8_t(buf, 8, address);
_mav_put_uint8_t(buf, 49, regstart);
_mav_put_uint8_t(buf, 50, count);
_mav_put_char_array(buf, 9, busname, 40);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DEVICE_OP_READ_LEN);
#else
mavlink_device_op_read_t packet;
packet.request_id = request_id;
packet.target_system = target_system;
packet.target_component = target_component;
packet.bustype = bustype;
packet.bus = bus;
packet.address = address;
packet.regstart = regstart;
packet.count = count;
mav_array_memcpy(packet.busname, busname, sizeof(char)*40);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DEVICE_OP_READ_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_DEVICE_OP_READ;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DEVICE_OP_READ_MIN_LEN, MAVLINK_MSG_ID_DEVICE_OP_READ_LEN, MAVLINK_MSG_ID_DEVICE_OP_READ_CRC);
}
/**
* @brief Encode a device_op_read struct
*
* @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 device_op_read C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_device_op_read_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_device_op_read_t* device_op_read)
{
return mavlink_msg_device_op_read_pack(system_id, component_id, msg, device_op_read->target_system, device_op_read->target_component, device_op_read->request_id, device_op_read->bustype, device_op_read->bus, device_op_read->address, device_op_read->busname, device_op_read->regstart, device_op_read->count);
}
/**
* @brief Encode a device_op_read struct on a channel
*
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param device_op_read C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_device_op_read_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_device_op_read_t* device_op_read)
{
return mavlink_msg_device_op_read_pack_chan(system_id, component_id, chan, msg, device_op_read->target_system, device_op_read->target_component, device_op_read->request_id, device_op_read->bustype, device_op_read->bus, device_op_read->address, device_op_read->busname, device_op_read->regstart, device_op_read->count);
}
/**
* @brief Send a device_op_read message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID.
* @param target_component Component ID.
* @param request_id Request ID - copied to reply.
* @param bustype The bus type.
* @param bus Bus number.
* @param address Bus address.
* @param busname Name of device on bus (for SPI).
* @param regstart First register to read.
* @param count Count of registers to read.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_device_op_read_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint32_t request_id, uint8_t bustype, uint8_t bus, uint8_t address, const char *busname, uint8_t regstart, uint8_t count)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_DEVICE_OP_READ_LEN];
_mav_put_uint32_t(buf, 0, request_id);
_mav_put_uint8_t(buf, 4, target_system);
_mav_put_uint8_t(buf, 5, target_component);
_mav_put_uint8_t(buf, 6, bustype);
_mav_put_uint8_t(buf, 7, bus);
_mav_put_uint8_t(buf, 8, address);
_mav_put_uint8_t(buf, 49, regstart);
_mav_put_uint8_t(buf, 50, count);
_mav_put_char_array(buf, 9, busname, 40);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEVICE_OP_READ, buf, MAVLINK_MSG_ID_DEVICE_OP_READ_MIN_LEN, MAVLINK_MSG_ID_DEVICE_OP_READ_LEN, MAVLINK_MSG_ID_DEVICE_OP_READ_CRC);
#else
mavlink_device_op_read_t packet;
packet.request_id = request_id;
packet.target_system = target_system;
packet.target_component = target_component;
packet.bustype = bustype;
packet.bus = bus;
packet.address = address;
packet.regstart = regstart;
packet.count = count;
mav_array_memcpy(packet.busname, busname, sizeof(char)*40);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEVICE_OP_READ, (const char *)&packet, MAVLINK_MSG_ID_DEVICE_OP_READ_MIN_LEN, MAVLINK_MSG_ID_DEVICE_OP_READ_LEN, MAVLINK_MSG_ID_DEVICE_OP_READ_CRC);
#endif
}
/**
* @brief Send a device_op_read message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_device_op_read_send_struct(mavlink_channel_t chan, const mavlink_device_op_read_t* device_op_read)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_device_op_read_send(chan, device_op_read->target_system, device_op_read->target_component, device_op_read->request_id, device_op_read->bustype, device_op_read->bus, device_op_read->address, device_op_read->busname, device_op_read->regstart, device_op_read->count);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEVICE_OP_READ, (const char *)device_op_read, MAVLINK_MSG_ID_DEVICE_OP_READ_MIN_LEN, MAVLINK_MSG_ID_DEVICE_OP_READ_LEN, MAVLINK_MSG_ID_DEVICE_OP_READ_CRC);
#endif
}
#if MAVLINK_MSG_ID_DEVICE_OP_READ_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_device_op_read_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint32_t request_id, uint8_t bustype, uint8_t bus, uint8_t address, const char *busname, uint8_t regstart, uint8_t count)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint32_t(buf, 0, request_id);
_mav_put_uint8_t(buf, 4, target_system);
_mav_put_uint8_t(buf, 5, target_component);
_mav_put_uint8_t(buf, 6, bustype);
_mav_put_uint8_t(buf, 7, bus);
_mav_put_uint8_t(buf, 8, address);
_mav_put_uint8_t(buf, 49, regstart);
_mav_put_uint8_t(buf, 50, count);
_mav_put_char_array(buf, 9, busname, 40);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEVICE_OP_READ, buf, MAVLINK_MSG_ID_DEVICE_OP_READ_MIN_LEN, MAVLINK_MSG_ID_DEVICE_OP_READ_LEN, MAVLINK_MSG_ID_DEVICE_OP_READ_CRC);
#else
mavlink_device_op_read_t *packet = (mavlink_device_op_read_t *)msgbuf;
packet->request_id = request_id;
packet->target_system = target_system;
packet->target_component = target_component;
packet->bustype = bustype;
packet->bus = bus;
packet->address = address;
packet->regstart = regstart;
packet->count = count;
mav_array_memcpy(packet->busname, busname, sizeof(char)*40);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEVICE_OP_READ, (const char *)packet, MAVLINK_MSG_ID_DEVICE_OP_READ_MIN_LEN, MAVLINK_MSG_ID_DEVICE_OP_READ_LEN, MAVLINK_MSG_ID_DEVICE_OP_READ_CRC);
#endif
}
#endif
#endif
// MESSAGE DEVICE_OP_READ UNPACKING
/**
* @brief Get field target_system from device_op_read message
*
* @return System ID.
*/
static inline uint8_t mavlink_msg_device_op_read_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 4);
}
/**
* @brief Get field target_component from device_op_read message
*
* @return Component ID.
*/
static inline uint8_t mavlink_msg_device_op_read_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 5);
}
/**
* @brief Get field request_id from device_op_read message
*
* @return Request ID - copied to reply.
*/
static inline uint32_t mavlink_msg_device_op_read_get_request_id(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 0);
}
/**
* @brief Get field bustype from device_op_read message
*
* @return The bus type.
*/
static inline uint8_t mavlink_msg_device_op_read_get_bustype(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 6);
}
/**
* @brief Get field bus from device_op_read message
*
* @return Bus number.
*/
static inline uint8_t mavlink_msg_device_op_read_get_bus(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 7);
}
/**
* @brief Get field address from device_op_read message
*
* @return Bus address.
*/
static inline uint8_t mavlink_msg_device_op_read_get_address(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 8);
}
/**
* @brief Get field busname from device_op_read message
*
* @return Name of device on bus (for SPI).
*/
static inline uint16_t mavlink_msg_device_op_read_get_busname(const mavlink_message_t* msg, char *busname)
{
return _MAV_RETURN_char_array(msg, busname, 40, 9);
}
/**
* @brief Get field regstart from device_op_read message
*
* @return First register to read.
*/
static inline uint8_t mavlink_msg_device_op_read_get_regstart(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 49);
}
/**
* @brief Get field count from device_op_read message
*
* @return Count of registers to read.
*/
static inline uint8_t mavlink_msg_device_op_read_get_count(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 50);
}
/**
* @brief Decode a device_op_read message into a struct
*
* @param msg The message to decode
* @param device_op_read C-struct to decode the message contents into
*/
static inline void mavlink_msg_device_op_read_decode(const mavlink_message_t* msg, mavlink_device_op_read_t* device_op_read)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
device_op_read->request_id = mavlink_msg_device_op_read_get_request_id(msg);
device_op_read->target_system = mavlink_msg_device_op_read_get_target_system(msg);
device_op_read->target_component = mavlink_msg_device_op_read_get_target_component(msg);
device_op_read->bustype = mavlink_msg_device_op_read_get_bustype(msg);
device_op_read->bus = mavlink_msg_device_op_read_get_bus(msg);
device_op_read->address = mavlink_msg_device_op_read_get_address(msg);
mavlink_msg_device_op_read_get_busname(msg, device_op_read->busname);
device_op_read->regstart = mavlink_msg_device_op_read_get_regstart(msg);
device_op_read->count = mavlink_msg_device_op_read_get_count(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_DEVICE_OP_READ_LEN? msg->len : MAVLINK_MSG_ID_DEVICE_OP_READ_LEN;
memset(device_op_read, 0, MAVLINK_MSG_ID_DEVICE_OP_READ_LEN);
memcpy(device_op_read, _MAV_PAYLOAD(msg), len);
#endif
}

View File

@@ -0,0 +1,305 @@
#pragma once
// MESSAGE DEVICE_OP_READ_REPLY PACKING
#define MAVLINK_MSG_ID_DEVICE_OP_READ_REPLY 11001
MAVPACKED(
typedef struct __mavlink_device_op_read_reply_t {
uint32_t request_id; /*< Request ID - copied from request.*/
uint8_t result; /*< 0 for success, anything else is failure code.*/
uint8_t regstart; /*< Starting register.*/
uint8_t count; /*< Count of bytes read.*/
uint8_t data[128]; /*< Reply data.*/
}) mavlink_device_op_read_reply_t;
#define MAVLINK_MSG_ID_DEVICE_OP_READ_REPLY_LEN 135
#define MAVLINK_MSG_ID_DEVICE_OP_READ_REPLY_MIN_LEN 135
#define MAVLINK_MSG_ID_11001_LEN 135
#define MAVLINK_MSG_ID_11001_MIN_LEN 135
#define MAVLINK_MSG_ID_DEVICE_OP_READ_REPLY_CRC 15
#define MAVLINK_MSG_ID_11001_CRC 15
#define MAVLINK_MSG_DEVICE_OP_READ_REPLY_FIELD_DATA_LEN 128
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_DEVICE_OP_READ_REPLY { \
11001, \
"DEVICE_OP_READ_REPLY", \
5, \
{ { "request_id", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_device_op_read_reply_t, request_id) }, \
{ "result", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_device_op_read_reply_t, result) }, \
{ "regstart", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_device_op_read_reply_t, regstart) }, \
{ "count", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_device_op_read_reply_t, count) }, \
{ "data", NULL, MAVLINK_TYPE_UINT8_T, 128, 7, offsetof(mavlink_device_op_read_reply_t, data) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_DEVICE_OP_READ_REPLY { \
"DEVICE_OP_READ_REPLY", \
5, \
{ { "request_id", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_device_op_read_reply_t, request_id) }, \
{ "result", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_device_op_read_reply_t, result) }, \
{ "regstart", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_device_op_read_reply_t, regstart) }, \
{ "count", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_device_op_read_reply_t, count) }, \
{ "data", NULL, MAVLINK_TYPE_UINT8_T, 128, 7, offsetof(mavlink_device_op_read_reply_t, data) }, \
} \
}
#endif
/**
* @brief Pack a device_op_read_reply 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_id Request ID - copied from request.
* @param result 0 for success, anything else is failure code.
* @param regstart Starting register.
* @param count Count of bytes read.
* @param data Reply data.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_device_op_read_reply_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint32_t request_id, uint8_t result, uint8_t regstart, uint8_t count, const uint8_t *data)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_DEVICE_OP_READ_REPLY_LEN];
_mav_put_uint32_t(buf, 0, request_id);
_mav_put_uint8_t(buf, 4, result);
_mav_put_uint8_t(buf, 5, regstart);
_mav_put_uint8_t(buf, 6, count);
_mav_put_uint8_t_array(buf, 7, data, 128);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DEVICE_OP_READ_REPLY_LEN);
#else
mavlink_device_op_read_reply_t packet;
packet.request_id = request_id;
packet.result = result;
packet.regstart = regstart;
packet.count = count;
mav_array_memcpy(packet.data, data, sizeof(uint8_t)*128);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DEVICE_OP_READ_REPLY_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_DEVICE_OP_READ_REPLY;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DEVICE_OP_READ_REPLY_MIN_LEN, MAVLINK_MSG_ID_DEVICE_OP_READ_REPLY_LEN, MAVLINK_MSG_ID_DEVICE_OP_READ_REPLY_CRC);
}
/**
* @brief Pack a device_op_read_reply message on a channel
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param request_id Request ID - copied from request.
* @param result 0 for success, anything else is failure code.
* @param regstart Starting register.
* @param count Count of bytes read.
* @param data Reply data.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_device_op_read_reply_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint32_t request_id,uint8_t result,uint8_t regstart,uint8_t count,const uint8_t *data)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_DEVICE_OP_READ_REPLY_LEN];
_mav_put_uint32_t(buf, 0, request_id);
_mav_put_uint8_t(buf, 4, result);
_mav_put_uint8_t(buf, 5, regstart);
_mav_put_uint8_t(buf, 6, count);
_mav_put_uint8_t_array(buf, 7, data, 128);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DEVICE_OP_READ_REPLY_LEN);
#else
mavlink_device_op_read_reply_t packet;
packet.request_id = request_id;
packet.result = result;
packet.regstart = regstart;
packet.count = count;
mav_array_memcpy(packet.data, data, sizeof(uint8_t)*128);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DEVICE_OP_READ_REPLY_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_DEVICE_OP_READ_REPLY;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DEVICE_OP_READ_REPLY_MIN_LEN, MAVLINK_MSG_ID_DEVICE_OP_READ_REPLY_LEN, MAVLINK_MSG_ID_DEVICE_OP_READ_REPLY_CRC);
}
/**
* @brief Encode a device_op_read_reply struct
*
* @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 device_op_read_reply C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_device_op_read_reply_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_device_op_read_reply_t* device_op_read_reply)
{
return mavlink_msg_device_op_read_reply_pack(system_id, component_id, msg, device_op_read_reply->request_id, device_op_read_reply->result, device_op_read_reply->regstart, device_op_read_reply->count, device_op_read_reply->data);
}
/**
* @brief Encode a device_op_read_reply struct on a channel
*
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param device_op_read_reply C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_device_op_read_reply_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_device_op_read_reply_t* device_op_read_reply)
{
return mavlink_msg_device_op_read_reply_pack_chan(system_id, component_id, chan, msg, device_op_read_reply->request_id, device_op_read_reply->result, device_op_read_reply->regstart, device_op_read_reply->count, device_op_read_reply->data);
}
/**
* @brief Send a device_op_read_reply message
* @param chan MAVLink channel to send the message
*
* @param request_id Request ID - copied from request.
* @param result 0 for success, anything else is failure code.
* @param regstart Starting register.
* @param count Count of bytes read.
* @param data Reply data.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_device_op_read_reply_send(mavlink_channel_t chan, uint32_t request_id, uint8_t result, uint8_t regstart, uint8_t count, const uint8_t *data)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_DEVICE_OP_READ_REPLY_LEN];
_mav_put_uint32_t(buf, 0, request_id);
_mav_put_uint8_t(buf, 4, result);
_mav_put_uint8_t(buf, 5, regstart);
_mav_put_uint8_t(buf, 6, count);
_mav_put_uint8_t_array(buf, 7, data, 128);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEVICE_OP_READ_REPLY, buf, MAVLINK_MSG_ID_DEVICE_OP_READ_REPLY_MIN_LEN, MAVLINK_MSG_ID_DEVICE_OP_READ_REPLY_LEN, MAVLINK_MSG_ID_DEVICE_OP_READ_REPLY_CRC);
#else
mavlink_device_op_read_reply_t packet;
packet.request_id = request_id;
packet.result = result;
packet.regstart = regstart;
packet.count = count;
mav_array_memcpy(packet.data, data, sizeof(uint8_t)*128);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEVICE_OP_READ_REPLY, (const char *)&packet, MAVLINK_MSG_ID_DEVICE_OP_READ_REPLY_MIN_LEN, MAVLINK_MSG_ID_DEVICE_OP_READ_REPLY_LEN, MAVLINK_MSG_ID_DEVICE_OP_READ_REPLY_CRC);
#endif
}
/**
* @brief Send a device_op_read_reply message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_device_op_read_reply_send_struct(mavlink_channel_t chan, const mavlink_device_op_read_reply_t* device_op_read_reply)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_device_op_read_reply_send(chan, device_op_read_reply->request_id, device_op_read_reply->result, device_op_read_reply->regstart, device_op_read_reply->count, device_op_read_reply->data);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEVICE_OP_READ_REPLY, (const char *)device_op_read_reply, MAVLINK_MSG_ID_DEVICE_OP_READ_REPLY_MIN_LEN, MAVLINK_MSG_ID_DEVICE_OP_READ_REPLY_LEN, MAVLINK_MSG_ID_DEVICE_OP_READ_REPLY_CRC);
#endif
}
#if MAVLINK_MSG_ID_DEVICE_OP_READ_REPLY_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_device_op_read_reply_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t request_id, uint8_t result, uint8_t regstart, uint8_t count, const uint8_t *data)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint32_t(buf, 0, request_id);
_mav_put_uint8_t(buf, 4, result);
_mav_put_uint8_t(buf, 5, regstart);
_mav_put_uint8_t(buf, 6, count);
_mav_put_uint8_t_array(buf, 7, data, 128);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEVICE_OP_READ_REPLY, buf, MAVLINK_MSG_ID_DEVICE_OP_READ_REPLY_MIN_LEN, MAVLINK_MSG_ID_DEVICE_OP_READ_REPLY_LEN, MAVLINK_MSG_ID_DEVICE_OP_READ_REPLY_CRC);
#else
mavlink_device_op_read_reply_t *packet = (mavlink_device_op_read_reply_t *)msgbuf;
packet->request_id = request_id;
packet->result = result;
packet->regstart = regstart;
packet->count = count;
mav_array_memcpy(packet->data, data, sizeof(uint8_t)*128);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEVICE_OP_READ_REPLY, (const char *)packet, MAVLINK_MSG_ID_DEVICE_OP_READ_REPLY_MIN_LEN, MAVLINK_MSG_ID_DEVICE_OP_READ_REPLY_LEN, MAVLINK_MSG_ID_DEVICE_OP_READ_REPLY_CRC);
#endif
}
#endif
#endif
// MESSAGE DEVICE_OP_READ_REPLY UNPACKING
/**
* @brief Get field request_id from device_op_read_reply message
*
* @return Request ID - copied from request.
*/
static inline uint32_t mavlink_msg_device_op_read_reply_get_request_id(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 0);
}
/**
* @brief Get field result from device_op_read_reply message
*
* @return 0 for success, anything else is failure code.
*/
static inline uint8_t mavlink_msg_device_op_read_reply_get_result(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 4);
}
/**
* @brief Get field regstart from device_op_read_reply message
*
* @return Starting register.
*/
static inline uint8_t mavlink_msg_device_op_read_reply_get_regstart(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 5);
}
/**
* @brief Get field count from device_op_read_reply message
*
* @return Count of bytes read.
*/
static inline uint8_t mavlink_msg_device_op_read_reply_get_count(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 6);
}
/**
* @brief Get field data from device_op_read_reply message
*
* @return Reply data.
*/
static inline uint16_t mavlink_msg_device_op_read_reply_get_data(const mavlink_message_t* msg, uint8_t *data)
{
return _MAV_RETURN_uint8_t_array(msg, data, 128, 7);
}
/**
* @brief Decode a device_op_read_reply message into a struct
*
* @param msg The message to decode
* @param device_op_read_reply C-struct to decode the message contents into
*/
static inline void mavlink_msg_device_op_read_reply_decode(const mavlink_message_t* msg, mavlink_device_op_read_reply_t* device_op_read_reply)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
device_op_read_reply->request_id = mavlink_msg_device_op_read_reply_get_request_id(msg);
device_op_read_reply->result = mavlink_msg_device_op_read_reply_get_result(msg);
device_op_read_reply->regstart = mavlink_msg_device_op_read_reply_get_regstart(msg);
device_op_read_reply->count = mavlink_msg_device_op_read_reply_get_count(msg);
mavlink_msg_device_op_read_reply_get_data(msg, device_op_read_reply->data);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_DEVICE_OP_READ_REPLY_LEN? msg->len : MAVLINK_MSG_ID_DEVICE_OP_READ_REPLY_LEN;
memset(device_op_read_reply, 0, MAVLINK_MSG_ID_DEVICE_OP_READ_REPLY_LEN);
memcpy(device_op_read_reply, _MAV_PAYLOAD(msg), len);
#endif
}

View File

@@ -0,0 +1,431 @@
#pragma once
// MESSAGE DEVICE_OP_WRITE PACKING
#define MAVLINK_MSG_ID_DEVICE_OP_WRITE 11002
MAVPACKED(
typedef struct __mavlink_device_op_write_t {
uint32_t request_id; /*< Request ID - copied to reply.*/
uint8_t target_system; /*< System ID.*/
uint8_t target_component; /*< Component ID.*/
uint8_t bustype; /*< The bus type.*/
uint8_t bus; /*< Bus number.*/
uint8_t address; /*< Bus address.*/
char busname[40]; /*< Name of device on bus (for SPI).*/
uint8_t regstart; /*< First register to write.*/
uint8_t count; /*< Count of registers to write.*/
uint8_t data[128]; /*< Write data.*/
}) mavlink_device_op_write_t;
#define MAVLINK_MSG_ID_DEVICE_OP_WRITE_LEN 179
#define MAVLINK_MSG_ID_DEVICE_OP_WRITE_MIN_LEN 179
#define MAVLINK_MSG_ID_11002_LEN 179
#define MAVLINK_MSG_ID_11002_MIN_LEN 179
#define MAVLINK_MSG_ID_DEVICE_OP_WRITE_CRC 234
#define MAVLINK_MSG_ID_11002_CRC 234
#define MAVLINK_MSG_DEVICE_OP_WRITE_FIELD_BUSNAME_LEN 40
#define MAVLINK_MSG_DEVICE_OP_WRITE_FIELD_DATA_LEN 128
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_DEVICE_OP_WRITE { \
11002, \
"DEVICE_OP_WRITE", \
10, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_device_op_write_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_device_op_write_t, target_component) }, \
{ "request_id", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_device_op_write_t, request_id) }, \
{ "bustype", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_device_op_write_t, bustype) }, \
{ "bus", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_device_op_write_t, bus) }, \
{ "address", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_device_op_write_t, address) }, \
{ "busname", NULL, MAVLINK_TYPE_CHAR, 40, 9, offsetof(mavlink_device_op_write_t, busname) }, \
{ "regstart", NULL, MAVLINK_TYPE_UINT8_T, 0, 49, offsetof(mavlink_device_op_write_t, regstart) }, \
{ "count", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_device_op_write_t, count) }, \
{ "data", NULL, MAVLINK_TYPE_UINT8_T, 128, 51, offsetof(mavlink_device_op_write_t, data) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_DEVICE_OP_WRITE { \
"DEVICE_OP_WRITE", \
10, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_device_op_write_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_device_op_write_t, target_component) }, \
{ "request_id", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_device_op_write_t, request_id) }, \
{ "bustype", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_device_op_write_t, bustype) }, \
{ "bus", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_device_op_write_t, bus) }, \
{ "address", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_device_op_write_t, address) }, \
{ "busname", NULL, MAVLINK_TYPE_CHAR, 40, 9, offsetof(mavlink_device_op_write_t, busname) }, \
{ "regstart", NULL, MAVLINK_TYPE_UINT8_T, 0, 49, offsetof(mavlink_device_op_write_t, regstart) }, \
{ "count", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_device_op_write_t, count) }, \
{ "data", NULL, MAVLINK_TYPE_UINT8_T, 128, 51, offsetof(mavlink_device_op_write_t, data) }, \
} \
}
#endif
/**
* @brief Pack a device_op_write 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.
* @param request_id Request ID - copied to reply.
* @param bustype The bus type.
* @param bus Bus number.
* @param address Bus address.
* @param busname Name of device on bus (for SPI).
* @param regstart First register to write.
* @param count Count of registers to write.
* @param data Write data.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_device_op_write_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, uint32_t request_id, uint8_t bustype, uint8_t bus, uint8_t address, const char *busname, uint8_t regstart, uint8_t count, const uint8_t *data)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_DEVICE_OP_WRITE_LEN];
_mav_put_uint32_t(buf, 0, request_id);
_mav_put_uint8_t(buf, 4, target_system);
_mav_put_uint8_t(buf, 5, target_component);
_mav_put_uint8_t(buf, 6, bustype);
_mav_put_uint8_t(buf, 7, bus);
_mav_put_uint8_t(buf, 8, address);
_mav_put_uint8_t(buf, 49, regstart);
_mav_put_uint8_t(buf, 50, count);
_mav_put_char_array(buf, 9, busname, 40);
_mav_put_uint8_t_array(buf, 51, data, 128);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DEVICE_OP_WRITE_LEN);
#else
mavlink_device_op_write_t packet;
packet.request_id = request_id;
packet.target_system = target_system;
packet.target_component = target_component;
packet.bustype = bustype;
packet.bus = bus;
packet.address = address;
packet.regstart = regstart;
packet.count = count;
mav_array_memcpy(packet.busname, busname, sizeof(char)*40);
mav_array_memcpy(packet.data, data, sizeof(uint8_t)*128);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DEVICE_OP_WRITE_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_DEVICE_OP_WRITE;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DEVICE_OP_WRITE_MIN_LEN, MAVLINK_MSG_ID_DEVICE_OP_WRITE_LEN, MAVLINK_MSG_ID_DEVICE_OP_WRITE_CRC);
}
/**
* @brief Pack a device_op_write message on a channel
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID.
* @param target_component Component ID.
* @param request_id Request ID - copied to reply.
* @param bustype The bus type.
* @param bus Bus number.
* @param address Bus address.
* @param busname Name of device on bus (for SPI).
* @param regstart First register to write.
* @param count Count of registers to write.
* @param data Write data.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_device_op_write_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,uint32_t request_id,uint8_t bustype,uint8_t bus,uint8_t address,const char *busname,uint8_t regstart,uint8_t count,const uint8_t *data)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_DEVICE_OP_WRITE_LEN];
_mav_put_uint32_t(buf, 0, request_id);
_mav_put_uint8_t(buf, 4, target_system);
_mav_put_uint8_t(buf, 5, target_component);
_mav_put_uint8_t(buf, 6, bustype);
_mav_put_uint8_t(buf, 7, bus);
_mav_put_uint8_t(buf, 8, address);
_mav_put_uint8_t(buf, 49, regstart);
_mav_put_uint8_t(buf, 50, count);
_mav_put_char_array(buf, 9, busname, 40);
_mav_put_uint8_t_array(buf, 51, data, 128);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DEVICE_OP_WRITE_LEN);
#else
mavlink_device_op_write_t packet;
packet.request_id = request_id;
packet.target_system = target_system;
packet.target_component = target_component;
packet.bustype = bustype;
packet.bus = bus;
packet.address = address;
packet.regstart = regstart;
packet.count = count;
mav_array_memcpy(packet.busname, busname, sizeof(char)*40);
mav_array_memcpy(packet.data, data, sizeof(uint8_t)*128);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DEVICE_OP_WRITE_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_DEVICE_OP_WRITE;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DEVICE_OP_WRITE_MIN_LEN, MAVLINK_MSG_ID_DEVICE_OP_WRITE_LEN, MAVLINK_MSG_ID_DEVICE_OP_WRITE_CRC);
}
/**
* @brief Encode a device_op_write struct
*
* @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 device_op_write C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_device_op_write_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_device_op_write_t* device_op_write)
{
return mavlink_msg_device_op_write_pack(system_id, component_id, msg, device_op_write->target_system, device_op_write->target_component, device_op_write->request_id, device_op_write->bustype, device_op_write->bus, device_op_write->address, device_op_write->busname, device_op_write->regstart, device_op_write->count, device_op_write->data);
}
/**
* @brief Encode a device_op_write struct on a channel
*
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param device_op_write C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_device_op_write_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_device_op_write_t* device_op_write)
{
return mavlink_msg_device_op_write_pack_chan(system_id, component_id, chan, msg, device_op_write->target_system, device_op_write->target_component, device_op_write->request_id, device_op_write->bustype, device_op_write->bus, device_op_write->address, device_op_write->busname, device_op_write->regstart, device_op_write->count, device_op_write->data);
}
/**
* @brief Send a device_op_write message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID.
* @param target_component Component ID.
* @param request_id Request ID - copied to reply.
* @param bustype The bus type.
* @param bus Bus number.
* @param address Bus address.
* @param busname Name of device on bus (for SPI).
* @param regstart First register to write.
* @param count Count of registers to write.
* @param data Write data.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_device_op_write_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint32_t request_id, uint8_t bustype, uint8_t bus, uint8_t address, const char *busname, uint8_t regstart, uint8_t count, const uint8_t *data)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_DEVICE_OP_WRITE_LEN];
_mav_put_uint32_t(buf, 0, request_id);
_mav_put_uint8_t(buf, 4, target_system);
_mav_put_uint8_t(buf, 5, target_component);
_mav_put_uint8_t(buf, 6, bustype);
_mav_put_uint8_t(buf, 7, bus);
_mav_put_uint8_t(buf, 8, address);
_mav_put_uint8_t(buf, 49, regstart);
_mav_put_uint8_t(buf, 50, count);
_mav_put_char_array(buf, 9, busname, 40);
_mav_put_uint8_t_array(buf, 51, data, 128);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEVICE_OP_WRITE, buf, MAVLINK_MSG_ID_DEVICE_OP_WRITE_MIN_LEN, MAVLINK_MSG_ID_DEVICE_OP_WRITE_LEN, MAVLINK_MSG_ID_DEVICE_OP_WRITE_CRC);
#else
mavlink_device_op_write_t packet;
packet.request_id = request_id;
packet.target_system = target_system;
packet.target_component = target_component;
packet.bustype = bustype;
packet.bus = bus;
packet.address = address;
packet.regstart = regstart;
packet.count = count;
mav_array_memcpy(packet.busname, busname, sizeof(char)*40);
mav_array_memcpy(packet.data, data, sizeof(uint8_t)*128);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEVICE_OP_WRITE, (const char *)&packet, MAVLINK_MSG_ID_DEVICE_OP_WRITE_MIN_LEN, MAVLINK_MSG_ID_DEVICE_OP_WRITE_LEN, MAVLINK_MSG_ID_DEVICE_OP_WRITE_CRC);
#endif
}
/**
* @brief Send a device_op_write message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_device_op_write_send_struct(mavlink_channel_t chan, const mavlink_device_op_write_t* device_op_write)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_device_op_write_send(chan, device_op_write->target_system, device_op_write->target_component, device_op_write->request_id, device_op_write->bustype, device_op_write->bus, device_op_write->address, device_op_write->busname, device_op_write->regstart, device_op_write->count, device_op_write->data);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEVICE_OP_WRITE, (const char *)device_op_write, MAVLINK_MSG_ID_DEVICE_OP_WRITE_MIN_LEN, MAVLINK_MSG_ID_DEVICE_OP_WRITE_LEN, MAVLINK_MSG_ID_DEVICE_OP_WRITE_CRC);
#endif
}
#if MAVLINK_MSG_ID_DEVICE_OP_WRITE_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_device_op_write_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint32_t request_id, uint8_t bustype, uint8_t bus, uint8_t address, const char *busname, uint8_t regstart, uint8_t count, const uint8_t *data)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint32_t(buf, 0, request_id);
_mav_put_uint8_t(buf, 4, target_system);
_mav_put_uint8_t(buf, 5, target_component);
_mav_put_uint8_t(buf, 6, bustype);
_mav_put_uint8_t(buf, 7, bus);
_mav_put_uint8_t(buf, 8, address);
_mav_put_uint8_t(buf, 49, regstart);
_mav_put_uint8_t(buf, 50, count);
_mav_put_char_array(buf, 9, busname, 40);
_mav_put_uint8_t_array(buf, 51, data, 128);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEVICE_OP_WRITE, buf, MAVLINK_MSG_ID_DEVICE_OP_WRITE_MIN_LEN, MAVLINK_MSG_ID_DEVICE_OP_WRITE_LEN, MAVLINK_MSG_ID_DEVICE_OP_WRITE_CRC);
#else
mavlink_device_op_write_t *packet = (mavlink_device_op_write_t *)msgbuf;
packet->request_id = request_id;
packet->target_system = target_system;
packet->target_component = target_component;
packet->bustype = bustype;
packet->bus = bus;
packet->address = address;
packet->regstart = regstart;
packet->count = count;
mav_array_memcpy(packet->busname, busname, sizeof(char)*40);
mav_array_memcpy(packet->data, data, sizeof(uint8_t)*128);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEVICE_OP_WRITE, (const char *)packet, MAVLINK_MSG_ID_DEVICE_OP_WRITE_MIN_LEN, MAVLINK_MSG_ID_DEVICE_OP_WRITE_LEN, MAVLINK_MSG_ID_DEVICE_OP_WRITE_CRC);
#endif
}
#endif
#endif
// MESSAGE DEVICE_OP_WRITE UNPACKING
/**
* @brief Get field target_system from device_op_write message
*
* @return System ID.
*/
static inline uint8_t mavlink_msg_device_op_write_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 4);
}
/**
* @brief Get field target_component from device_op_write message
*
* @return Component ID.
*/
static inline uint8_t mavlink_msg_device_op_write_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 5);
}
/**
* @brief Get field request_id from device_op_write message
*
* @return Request ID - copied to reply.
*/
static inline uint32_t mavlink_msg_device_op_write_get_request_id(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 0);
}
/**
* @brief Get field bustype from device_op_write message
*
* @return The bus type.
*/
static inline uint8_t mavlink_msg_device_op_write_get_bustype(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 6);
}
/**
* @brief Get field bus from device_op_write message
*
* @return Bus number.
*/
static inline uint8_t mavlink_msg_device_op_write_get_bus(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 7);
}
/**
* @brief Get field address from device_op_write message
*
* @return Bus address.
*/
static inline uint8_t mavlink_msg_device_op_write_get_address(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 8);
}
/**
* @brief Get field busname from device_op_write message
*
* @return Name of device on bus (for SPI).
*/
static inline uint16_t mavlink_msg_device_op_write_get_busname(const mavlink_message_t* msg, char *busname)
{
return _MAV_RETURN_char_array(msg, busname, 40, 9);
}
/**
* @brief Get field regstart from device_op_write message
*
* @return First register to write.
*/
static inline uint8_t mavlink_msg_device_op_write_get_regstart(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 49);
}
/**
* @brief Get field count from device_op_write message
*
* @return Count of registers to write.
*/
static inline uint8_t mavlink_msg_device_op_write_get_count(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 50);
}
/**
* @brief Get field data from device_op_write message
*
* @return Write data.
*/
static inline uint16_t mavlink_msg_device_op_write_get_data(const mavlink_message_t* msg, uint8_t *data)
{
return _MAV_RETURN_uint8_t_array(msg, data, 128, 51);
}
/**
* @brief Decode a device_op_write message into a struct
*
* @param msg The message to decode
* @param device_op_write C-struct to decode the message contents into
*/
static inline void mavlink_msg_device_op_write_decode(const mavlink_message_t* msg, mavlink_device_op_write_t* device_op_write)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
device_op_write->request_id = mavlink_msg_device_op_write_get_request_id(msg);
device_op_write->target_system = mavlink_msg_device_op_write_get_target_system(msg);
device_op_write->target_component = mavlink_msg_device_op_write_get_target_component(msg);
device_op_write->bustype = mavlink_msg_device_op_write_get_bustype(msg);
device_op_write->bus = mavlink_msg_device_op_write_get_bus(msg);
device_op_write->address = mavlink_msg_device_op_write_get_address(msg);
mavlink_msg_device_op_write_get_busname(msg, device_op_write->busname);
device_op_write->regstart = mavlink_msg_device_op_write_get_regstart(msg);
device_op_write->count = mavlink_msg_device_op_write_get_count(msg);
mavlink_msg_device_op_write_get_data(msg, device_op_write->data);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_DEVICE_OP_WRITE_LEN? msg->len : MAVLINK_MSG_ID_DEVICE_OP_WRITE_LEN;
memset(device_op_write, 0, MAVLINK_MSG_ID_DEVICE_OP_WRITE_LEN);
memcpy(device_op_write, _MAV_PAYLOAD(msg), len);
#endif
}

View File

@@ -0,0 +1,238 @@
#pragma once
// MESSAGE DEVICE_OP_WRITE_REPLY PACKING
#define MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY 11003
MAVPACKED(
typedef struct __mavlink_device_op_write_reply_t {
uint32_t request_id; /*< Request ID - copied from request.*/
uint8_t result; /*< 0 for success, anything else is failure code.*/
}) mavlink_device_op_write_reply_t;
#define MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY_LEN 5
#define MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY_MIN_LEN 5
#define MAVLINK_MSG_ID_11003_LEN 5
#define MAVLINK_MSG_ID_11003_MIN_LEN 5
#define MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY_CRC 64
#define MAVLINK_MSG_ID_11003_CRC 64
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_DEVICE_OP_WRITE_REPLY { \
11003, \
"DEVICE_OP_WRITE_REPLY", \
2, \
{ { "request_id", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_device_op_write_reply_t, request_id) }, \
{ "result", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_device_op_write_reply_t, result) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_DEVICE_OP_WRITE_REPLY { \
"DEVICE_OP_WRITE_REPLY", \
2, \
{ { "request_id", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_device_op_write_reply_t, request_id) }, \
{ "result", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_device_op_write_reply_t, result) }, \
} \
}
#endif
/**
* @brief Pack a device_op_write_reply 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_id Request ID - copied from request.
* @param result 0 for success, anything else is failure code.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_device_op_write_reply_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint32_t request_id, uint8_t result)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY_LEN];
_mav_put_uint32_t(buf, 0, request_id);
_mav_put_uint8_t(buf, 4, result);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY_LEN);
#else
mavlink_device_op_write_reply_t packet;
packet.request_id = request_id;
packet.result = result;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY_MIN_LEN, MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY_LEN, MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY_CRC);
}
/**
* @brief Pack a device_op_write_reply message on a channel
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param request_id Request ID - copied from request.
* @param result 0 for success, anything else is failure code.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_device_op_write_reply_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint32_t request_id,uint8_t result)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY_LEN];
_mav_put_uint32_t(buf, 0, request_id);
_mav_put_uint8_t(buf, 4, result);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY_LEN);
#else
mavlink_device_op_write_reply_t packet;
packet.request_id = request_id;
packet.result = result;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY_MIN_LEN, MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY_LEN, MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY_CRC);
}
/**
* @brief Encode a device_op_write_reply struct
*
* @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 device_op_write_reply C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_device_op_write_reply_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_device_op_write_reply_t* device_op_write_reply)
{
return mavlink_msg_device_op_write_reply_pack(system_id, component_id, msg, device_op_write_reply->request_id, device_op_write_reply->result);
}
/**
* @brief Encode a device_op_write_reply struct on a channel
*
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param device_op_write_reply C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_device_op_write_reply_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_device_op_write_reply_t* device_op_write_reply)
{
return mavlink_msg_device_op_write_reply_pack_chan(system_id, component_id, chan, msg, device_op_write_reply->request_id, device_op_write_reply->result);
}
/**
* @brief Send a device_op_write_reply message
* @param chan MAVLink channel to send the message
*
* @param request_id Request ID - copied from request.
* @param result 0 for success, anything else is failure code.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_device_op_write_reply_send(mavlink_channel_t chan, uint32_t request_id, uint8_t result)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY_LEN];
_mav_put_uint32_t(buf, 0, request_id);
_mav_put_uint8_t(buf, 4, result);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY, buf, MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY_MIN_LEN, MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY_LEN, MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY_CRC);
#else
mavlink_device_op_write_reply_t packet;
packet.request_id = request_id;
packet.result = result;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY, (const char *)&packet, MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY_MIN_LEN, MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY_LEN, MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY_CRC);
#endif
}
/**
* @brief Send a device_op_write_reply message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_device_op_write_reply_send_struct(mavlink_channel_t chan, const mavlink_device_op_write_reply_t* device_op_write_reply)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_device_op_write_reply_send(chan, device_op_write_reply->request_id, device_op_write_reply->result);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY, (const char *)device_op_write_reply, MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY_MIN_LEN, MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY_LEN, MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY_CRC);
#endif
}
#if MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_device_op_write_reply_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t request_id, uint8_t result)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint32_t(buf, 0, request_id);
_mav_put_uint8_t(buf, 4, result);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY, buf, MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY_MIN_LEN, MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY_LEN, MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY_CRC);
#else
mavlink_device_op_write_reply_t *packet = (mavlink_device_op_write_reply_t *)msgbuf;
packet->request_id = request_id;
packet->result = result;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY, (const char *)packet, MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY_MIN_LEN, MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY_LEN, MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY_CRC);
#endif
}
#endif
#endif
// MESSAGE DEVICE_OP_WRITE_REPLY UNPACKING
/**
* @brief Get field request_id from device_op_write_reply message
*
* @return Request ID - copied from request.
*/
static inline uint32_t mavlink_msg_device_op_write_reply_get_request_id(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 0);
}
/**
* @brief Get field result from device_op_write_reply message
*
* @return 0 for success, anything else is failure code.
*/
static inline uint8_t mavlink_msg_device_op_write_reply_get_result(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 4);
}
/**
* @brief Decode a device_op_write_reply message into a struct
*
* @param msg The message to decode
* @param device_op_write_reply C-struct to decode the message contents into
*/
static inline void mavlink_msg_device_op_write_reply_decode(const mavlink_message_t* msg, mavlink_device_op_write_reply_t* device_op_write_reply)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
device_op_write_reply->request_id = mavlink_msg_device_op_write_reply_get_request_id(msg);
device_op_write_reply->result = mavlink_msg_device_op_write_reply_get_result(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY_LEN? msg->len : MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY_LEN;
memset(device_op_write_reply, 0, MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY_LEN);
memcpy(device_op_write_reply, _MAV_PAYLOAD(msg), len);
#endif
}

View File

@@ -0,0 +1,463 @@
#pragma once
// MESSAGE DIGICAM_CONFIGURE PACKING
#define MAVLINK_MSG_ID_DIGICAM_CONFIGURE 154
MAVPACKED(
typedef struct __mavlink_digicam_configure_t {
float extra_value; /*< Correspondent value to given extra_param.*/
uint16_t shutter_speed; /*< Divisor number //e.g. 1000 means 1/1000 (0 means ignore).*/
uint8_t target_system; /*< System ID.*/
uint8_t target_component; /*< Component ID.*/
uint8_t mode; /*< Mode enumeration from 1 to N //P, TV, AV, M, etc. (0 means ignore).*/
uint8_t aperture; /*< F stop number x 10 //e.g. 28 means 2.8 (0 means ignore).*/
uint8_t iso; /*< ISO enumeration from 1 to N //e.g. 80, 100, 200, Etc (0 means ignore).*/
uint8_t exposure_type; /*< Exposure type enumeration from 1 to N (0 means ignore).*/
uint8_t command_id; /*< Command Identity (incremental loop: 0 to 255). //A command sent multiple times will be executed or pooled just once.*/
uint8_t engine_cut_off; /*< [ds] Main engine cut-off time before camera trigger (0 means no cut-off).*/
uint8_t extra_param; /*< Extra parameters enumeration (0 means ignore).*/
}) mavlink_digicam_configure_t;
#define MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN 15
#define MAVLINK_MSG_ID_DIGICAM_CONFIGURE_MIN_LEN 15
#define MAVLINK_MSG_ID_154_LEN 15
#define MAVLINK_MSG_ID_154_MIN_LEN 15
#define MAVLINK_MSG_ID_DIGICAM_CONFIGURE_CRC 84
#define MAVLINK_MSG_ID_154_CRC 84
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_DIGICAM_CONFIGURE { \
154, \
"DIGICAM_CONFIGURE", \
11, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_digicam_configure_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_digicam_configure_t, target_component) }, \
{ "mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_digicam_configure_t, mode) }, \
{ "shutter_speed", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_digicam_configure_t, shutter_speed) }, \
{ "aperture", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_digicam_configure_t, aperture) }, \
{ "iso", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_digicam_configure_t, iso) }, \
{ "exposure_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_digicam_configure_t, exposure_type) }, \
{ "command_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_digicam_configure_t, command_id) }, \
{ "engine_cut_off", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_digicam_configure_t, engine_cut_off) }, \
{ "extra_param", NULL, MAVLINK_TYPE_UINT8_T, 0, 14, offsetof(mavlink_digicam_configure_t, extra_param) }, \
{ "extra_value", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_digicam_configure_t, extra_value) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_DIGICAM_CONFIGURE { \
"DIGICAM_CONFIGURE", \
11, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_digicam_configure_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_digicam_configure_t, target_component) }, \
{ "mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_digicam_configure_t, mode) }, \
{ "shutter_speed", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_digicam_configure_t, shutter_speed) }, \
{ "aperture", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_digicam_configure_t, aperture) }, \
{ "iso", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_digicam_configure_t, iso) }, \
{ "exposure_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_digicam_configure_t, exposure_type) }, \
{ "command_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_digicam_configure_t, command_id) }, \
{ "engine_cut_off", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_digicam_configure_t, engine_cut_off) }, \
{ "extra_param", NULL, MAVLINK_TYPE_UINT8_T, 0, 14, offsetof(mavlink_digicam_configure_t, extra_param) }, \
{ "extra_value", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_digicam_configure_t, extra_value) }, \
} \
}
#endif
/**
* @brief Pack a digicam_configure 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.
* @param mode Mode enumeration from 1 to N //P, TV, AV, M, etc. (0 means ignore).
* @param shutter_speed Divisor number //e.g. 1000 means 1/1000 (0 means ignore).
* @param aperture F stop number x 10 //e.g. 28 means 2.8 (0 means ignore).
* @param iso ISO enumeration from 1 to N //e.g. 80, 100, 200, Etc (0 means ignore).
* @param exposure_type Exposure type enumeration from 1 to N (0 means ignore).
* @param command_id Command Identity (incremental loop: 0 to 255). //A command sent multiple times will be executed or pooled just once.
* @param engine_cut_off [ds] Main engine cut-off time before camera trigger (0 means no cut-off).
* @param extra_param Extra parameters enumeration (0 means ignore).
* @param extra_value Correspondent value to given extra_param.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_digicam_configure_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, uint8_t mode, uint16_t shutter_speed, uint8_t aperture, uint8_t iso, uint8_t exposure_type, uint8_t command_id, uint8_t engine_cut_off, uint8_t extra_param, float extra_value)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN];
_mav_put_float(buf, 0, extra_value);
_mav_put_uint16_t(buf, 4, shutter_speed);
_mav_put_uint8_t(buf, 6, target_system);
_mav_put_uint8_t(buf, 7, target_component);
_mav_put_uint8_t(buf, 8, mode);
_mav_put_uint8_t(buf, 9, aperture);
_mav_put_uint8_t(buf, 10, iso);
_mav_put_uint8_t(buf, 11, exposure_type);
_mav_put_uint8_t(buf, 12, command_id);
_mav_put_uint8_t(buf, 13, engine_cut_off);
_mav_put_uint8_t(buf, 14, extra_param);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN);
#else
mavlink_digicam_configure_t packet;
packet.extra_value = extra_value;
packet.shutter_speed = shutter_speed;
packet.target_system = target_system;
packet.target_component = target_component;
packet.mode = mode;
packet.aperture = aperture;
packet.iso = iso;
packet.exposure_type = exposure_type;
packet.command_id = command_id;
packet.engine_cut_off = engine_cut_off;
packet.extra_param = extra_param;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_DIGICAM_CONFIGURE;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_MIN_LEN, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_CRC);
}
/**
* @brief Pack a digicam_configure message on a channel
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID.
* @param target_component Component ID.
* @param mode Mode enumeration from 1 to N //P, TV, AV, M, etc. (0 means ignore).
* @param shutter_speed Divisor number //e.g. 1000 means 1/1000 (0 means ignore).
* @param aperture F stop number x 10 //e.g. 28 means 2.8 (0 means ignore).
* @param iso ISO enumeration from 1 to N //e.g. 80, 100, 200, Etc (0 means ignore).
* @param exposure_type Exposure type enumeration from 1 to N (0 means ignore).
* @param command_id Command Identity (incremental loop: 0 to 255). //A command sent multiple times will be executed or pooled just once.
* @param engine_cut_off [ds] Main engine cut-off time before camera trigger (0 means no cut-off).
* @param extra_param Extra parameters enumeration (0 means ignore).
* @param extra_value Correspondent value to given extra_param.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_digicam_configure_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 mode,uint16_t shutter_speed,uint8_t aperture,uint8_t iso,uint8_t exposure_type,uint8_t command_id,uint8_t engine_cut_off,uint8_t extra_param,float extra_value)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN];
_mav_put_float(buf, 0, extra_value);
_mav_put_uint16_t(buf, 4, shutter_speed);
_mav_put_uint8_t(buf, 6, target_system);
_mav_put_uint8_t(buf, 7, target_component);
_mav_put_uint8_t(buf, 8, mode);
_mav_put_uint8_t(buf, 9, aperture);
_mav_put_uint8_t(buf, 10, iso);
_mav_put_uint8_t(buf, 11, exposure_type);
_mav_put_uint8_t(buf, 12, command_id);
_mav_put_uint8_t(buf, 13, engine_cut_off);
_mav_put_uint8_t(buf, 14, extra_param);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN);
#else
mavlink_digicam_configure_t packet;
packet.extra_value = extra_value;
packet.shutter_speed = shutter_speed;
packet.target_system = target_system;
packet.target_component = target_component;
packet.mode = mode;
packet.aperture = aperture;
packet.iso = iso;
packet.exposure_type = exposure_type;
packet.command_id = command_id;
packet.engine_cut_off = engine_cut_off;
packet.extra_param = extra_param;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_DIGICAM_CONFIGURE;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_MIN_LEN, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_CRC);
}
/**
* @brief Encode a digicam_configure struct
*
* @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 digicam_configure C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_digicam_configure_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_digicam_configure_t* digicam_configure)
{
return mavlink_msg_digicam_configure_pack(system_id, component_id, msg, digicam_configure->target_system, digicam_configure->target_component, digicam_configure->mode, digicam_configure->shutter_speed, digicam_configure->aperture, digicam_configure->iso, digicam_configure->exposure_type, digicam_configure->command_id, digicam_configure->engine_cut_off, digicam_configure->extra_param, digicam_configure->extra_value);
}
/**
* @brief Encode a digicam_configure struct on a channel
*
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param digicam_configure C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_digicam_configure_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_digicam_configure_t* digicam_configure)
{
return mavlink_msg_digicam_configure_pack_chan(system_id, component_id, chan, msg, digicam_configure->target_system, digicam_configure->target_component, digicam_configure->mode, digicam_configure->shutter_speed, digicam_configure->aperture, digicam_configure->iso, digicam_configure->exposure_type, digicam_configure->command_id, digicam_configure->engine_cut_off, digicam_configure->extra_param, digicam_configure->extra_value);
}
/**
* @brief Send a digicam_configure message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID.
* @param target_component Component ID.
* @param mode Mode enumeration from 1 to N //P, TV, AV, M, etc. (0 means ignore).
* @param shutter_speed Divisor number //e.g. 1000 means 1/1000 (0 means ignore).
* @param aperture F stop number x 10 //e.g. 28 means 2.8 (0 means ignore).
* @param iso ISO enumeration from 1 to N //e.g. 80, 100, 200, Etc (0 means ignore).
* @param exposure_type Exposure type enumeration from 1 to N (0 means ignore).
* @param command_id Command Identity (incremental loop: 0 to 255). //A command sent multiple times will be executed or pooled just once.
* @param engine_cut_off [ds] Main engine cut-off time before camera trigger (0 means no cut-off).
* @param extra_param Extra parameters enumeration (0 means ignore).
* @param extra_value Correspondent value to given extra_param.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_digicam_configure_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t mode, uint16_t shutter_speed, uint8_t aperture, uint8_t iso, uint8_t exposure_type, uint8_t command_id, uint8_t engine_cut_off, uint8_t extra_param, float extra_value)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN];
_mav_put_float(buf, 0, extra_value);
_mav_put_uint16_t(buf, 4, shutter_speed);
_mav_put_uint8_t(buf, 6, target_system);
_mav_put_uint8_t(buf, 7, target_component);
_mav_put_uint8_t(buf, 8, mode);
_mav_put_uint8_t(buf, 9, aperture);
_mav_put_uint8_t(buf, 10, iso);
_mav_put_uint8_t(buf, 11, exposure_type);
_mav_put_uint8_t(buf, 12, command_id);
_mav_put_uint8_t(buf, 13, engine_cut_off);
_mav_put_uint8_t(buf, 14, extra_param);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DIGICAM_CONFIGURE, buf, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_MIN_LEN, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_CRC);
#else
mavlink_digicam_configure_t packet;
packet.extra_value = extra_value;
packet.shutter_speed = shutter_speed;
packet.target_system = target_system;
packet.target_component = target_component;
packet.mode = mode;
packet.aperture = aperture;
packet.iso = iso;
packet.exposure_type = exposure_type;
packet.command_id = command_id;
packet.engine_cut_off = engine_cut_off;
packet.extra_param = extra_param;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DIGICAM_CONFIGURE, (const char *)&packet, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_MIN_LEN, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_CRC);
#endif
}
/**
* @brief Send a digicam_configure message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_digicam_configure_send_struct(mavlink_channel_t chan, const mavlink_digicam_configure_t* digicam_configure)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_digicam_configure_send(chan, digicam_configure->target_system, digicam_configure->target_component, digicam_configure->mode, digicam_configure->shutter_speed, digicam_configure->aperture, digicam_configure->iso, digicam_configure->exposure_type, digicam_configure->command_id, digicam_configure->engine_cut_off, digicam_configure->extra_param, digicam_configure->extra_value);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DIGICAM_CONFIGURE, (const char *)digicam_configure, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_MIN_LEN, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_CRC);
#endif
}
#if MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_digicam_configure_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t mode, uint16_t shutter_speed, uint8_t aperture, uint8_t iso, uint8_t exposure_type, uint8_t command_id, uint8_t engine_cut_off, uint8_t extra_param, float extra_value)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_float(buf, 0, extra_value);
_mav_put_uint16_t(buf, 4, shutter_speed);
_mav_put_uint8_t(buf, 6, target_system);
_mav_put_uint8_t(buf, 7, target_component);
_mav_put_uint8_t(buf, 8, mode);
_mav_put_uint8_t(buf, 9, aperture);
_mav_put_uint8_t(buf, 10, iso);
_mav_put_uint8_t(buf, 11, exposure_type);
_mav_put_uint8_t(buf, 12, command_id);
_mav_put_uint8_t(buf, 13, engine_cut_off);
_mav_put_uint8_t(buf, 14, extra_param);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DIGICAM_CONFIGURE, buf, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_MIN_LEN, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_CRC);
#else
mavlink_digicam_configure_t *packet = (mavlink_digicam_configure_t *)msgbuf;
packet->extra_value = extra_value;
packet->shutter_speed = shutter_speed;
packet->target_system = target_system;
packet->target_component = target_component;
packet->mode = mode;
packet->aperture = aperture;
packet->iso = iso;
packet->exposure_type = exposure_type;
packet->command_id = command_id;
packet->engine_cut_off = engine_cut_off;
packet->extra_param = extra_param;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DIGICAM_CONFIGURE, (const char *)packet, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_MIN_LEN, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_CRC);
#endif
}
#endif
#endif
// MESSAGE DIGICAM_CONFIGURE UNPACKING
/**
* @brief Get field target_system from digicam_configure message
*
* @return System ID.
*/
static inline uint8_t mavlink_msg_digicam_configure_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 6);
}
/**
* @brief Get field target_component from digicam_configure message
*
* @return Component ID.
*/
static inline uint8_t mavlink_msg_digicam_configure_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 7);
}
/**
* @brief Get field mode from digicam_configure message
*
* @return Mode enumeration from 1 to N //P, TV, AV, M, etc. (0 means ignore).
*/
static inline uint8_t mavlink_msg_digicam_configure_get_mode(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 8);
}
/**
* @brief Get field shutter_speed from digicam_configure message
*
* @return Divisor number //e.g. 1000 means 1/1000 (0 means ignore).
*/
static inline uint16_t mavlink_msg_digicam_configure_get_shutter_speed(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 4);
}
/**
* @brief Get field aperture from digicam_configure message
*
* @return F stop number x 10 //e.g. 28 means 2.8 (0 means ignore).
*/
static inline uint8_t mavlink_msg_digicam_configure_get_aperture(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 9);
}
/**
* @brief Get field iso from digicam_configure message
*
* @return ISO enumeration from 1 to N //e.g. 80, 100, 200, Etc (0 means ignore).
*/
static inline uint8_t mavlink_msg_digicam_configure_get_iso(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 10);
}
/**
* @brief Get field exposure_type from digicam_configure message
*
* @return Exposure type enumeration from 1 to N (0 means ignore).
*/
static inline uint8_t mavlink_msg_digicam_configure_get_exposure_type(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 11);
}
/**
* @brief Get field command_id from digicam_configure message
*
* @return Command Identity (incremental loop: 0 to 255). //A command sent multiple times will be executed or pooled just once.
*/
static inline uint8_t mavlink_msg_digicam_configure_get_command_id(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 12);
}
/**
* @brief Get field engine_cut_off from digicam_configure message
*
* @return [ds] Main engine cut-off time before camera trigger (0 means no cut-off).
*/
static inline uint8_t mavlink_msg_digicam_configure_get_engine_cut_off(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 13);
}
/**
* @brief Get field extra_param from digicam_configure message
*
* @return Extra parameters enumeration (0 means ignore).
*/
static inline uint8_t mavlink_msg_digicam_configure_get_extra_param(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 14);
}
/**
* @brief Get field extra_value from digicam_configure message
*
* @return Correspondent value to given extra_param.
*/
static inline float mavlink_msg_digicam_configure_get_extra_value(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 0);
}
/**
* @brief Decode a digicam_configure message into a struct
*
* @param msg The message to decode
* @param digicam_configure C-struct to decode the message contents into
*/
static inline void mavlink_msg_digicam_configure_decode(const mavlink_message_t* msg, mavlink_digicam_configure_t* digicam_configure)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
digicam_configure->extra_value = mavlink_msg_digicam_configure_get_extra_value(msg);
digicam_configure->shutter_speed = mavlink_msg_digicam_configure_get_shutter_speed(msg);
digicam_configure->target_system = mavlink_msg_digicam_configure_get_target_system(msg);
digicam_configure->target_component = mavlink_msg_digicam_configure_get_target_component(msg);
digicam_configure->mode = mavlink_msg_digicam_configure_get_mode(msg);
digicam_configure->aperture = mavlink_msg_digicam_configure_get_aperture(msg);
digicam_configure->iso = mavlink_msg_digicam_configure_get_iso(msg);
digicam_configure->exposure_type = mavlink_msg_digicam_configure_get_exposure_type(msg);
digicam_configure->command_id = mavlink_msg_digicam_configure_get_command_id(msg);
digicam_configure->engine_cut_off = mavlink_msg_digicam_configure_get_engine_cut_off(msg);
digicam_configure->extra_param = mavlink_msg_digicam_configure_get_extra_param(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN? msg->len : MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN;
memset(digicam_configure, 0, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN);
memcpy(digicam_configure, _MAV_PAYLOAD(msg), len);
#endif
}

View File

@@ -0,0 +1,438 @@
#pragma once
// MESSAGE DIGICAM_CONTROL PACKING
#define MAVLINK_MSG_ID_DIGICAM_CONTROL 155
MAVPACKED(
typedef struct __mavlink_digicam_control_t {
float extra_value; /*< Correspondent value to given extra_param.*/
uint8_t target_system; /*< System ID.*/
uint8_t target_component; /*< Component ID.*/
uint8_t session; /*< 0: stop, 1: start or keep it up //Session control e.g. show/hide lens.*/
uint8_t zoom_pos; /*< 1 to N //Zoom's absolute position (0 means ignore).*/
int8_t zoom_step; /*< -100 to 100 //Zooming step value to offset zoom from the current position.*/
uint8_t focus_lock; /*< 0: unlock focus or keep unlocked, 1: lock focus or keep locked, 3: re-lock focus.*/
uint8_t shot; /*< 0: ignore, 1: shot or start filming.*/
uint8_t command_id; /*< Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once.*/
uint8_t extra_param; /*< Extra parameters enumeration (0 means ignore).*/
}) mavlink_digicam_control_t;
#define MAVLINK_MSG_ID_DIGICAM_CONTROL_LEN 13
#define MAVLINK_MSG_ID_DIGICAM_CONTROL_MIN_LEN 13
#define MAVLINK_MSG_ID_155_LEN 13
#define MAVLINK_MSG_ID_155_MIN_LEN 13
#define MAVLINK_MSG_ID_DIGICAM_CONTROL_CRC 22
#define MAVLINK_MSG_ID_155_CRC 22
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_DIGICAM_CONTROL { \
155, \
"DIGICAM_CONTROL", \
10, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_digicam_control_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_digicam_control_t, target_component) }, \
{ "session", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_digicam_control_t, session) }, \
{ "zoom_pos", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_digicam_control_t, zoom_pos) }, \
{ "zoom_step", NULL, MAVLINK_TYPE_INT8_T, 0, 8, offsetof(mavlink_digicam_control_t, zoom_step) }, \
{ "focus_lock", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_digicam_control_t, focus_lock) }, \
{ "shot", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_digicam_control_t, shot) }, \
{ "command_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_digicam_control_t, command_id) }, \
{ "extra_param", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_digicam_control_t, extra_param) }, \
{ "extra_value", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_digicam_control_t, extra_value) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_DIGICAM_CONTROL { \
"DIGICAM_CONTROL", \
10, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_digicam_control_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_digicam_control_t, target_component) }, \
{ "session", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_digicam_control_t, session) }, \
{ "zoom_pos", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_digicam_control_t, zoom_pos) }, \
{ "zoom_step", NULL, MAVLINK_TYPE_INT8_T, 0, 8, offsetof(mavlink_digicam_control_t, zoom_step) }, \
{ "focus_lock", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_digicam_control_t, focus_lock) }, \
{ "shot", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_digicam_control_t, shot) }, \
{ "command_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_digicam_control_t, command_id) }, \
{ "extra_param", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_digicam_control_t, extra_param) }, \
{ "extra_value", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_digicam_control_t, extra_value) }, \
} \
}
#endif
/**
* @brief Pack a digicam_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_system System ID.
* @param target_component Component ID.
* @param session 0: stop, 1: start or keep it up //Session control e.g. show/hide lens.
* @param zoom_pos 1 to N //Zoom's absolute position (0 means ignore).
* @param zoom_step -100 to 100 //Zooming step value to offset zoom from the current position.
* @param focus_lock 0: unlock focus or keep unlocked, 1: lock focus or keep locked, 3: re-lock focus.
* @param shot 0: ignore, 1: shot or start filming.
* @param command_id Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once.
* @param extra_param Extra parameters enumeration (0 means ignore).
* @param extra_value Correspondent value to given extra_param.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_digicam_control_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, uint8_t session, uint8_t zoom_pos, int8_t zoom_step, uint8_t focus_lock, uint8_t shot, uint8_t command_id, uint8_t extra_param, float extra_value)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_DIGICAM_CONTROL_LEN];
_mav_put_float(buf, 0, extra_value);
_mav_put_uint8_t(buf, 4, target_system);
_mav_put_uint8_t(buf, 5, target_component);
_mav_put_uint8_t(buf, 6, session);
_mav_put_uint8_t(buf, 7, zoom_pos);
_mav_put_int8_t(buf, 8, zoom_step);
_mav_put_uint8_t(buf, 9, focus_lock);
_mav_put_uint8_t(buf, 10, shot);
_mav_put_uint8_t(buf, 11, command_id);
_mav_put_uint8_t(buf, 12, extra_param);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DIGICAM_CONTROL_LEN);
#else
mavlink_digicam_control_t packet;
packet.extra_value = extra_value;
packet.target_system = target_system;
packet.target_component = target_component;
packet.session = session;
packet.zoom_pos = zoom_pos;
packet.zoom_step = zoom_step;
packet.focus_lock = focus_lock;
packet.shot = shot;
packet.command_id = command_id;
packet.extra_param = extra_param;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DIGICAM_CONTROL_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_DIGICAM_CONTROL;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DIGICAM_CONTROL_MIN_LEN, MAVLINK_MSG_ID_DIGICAM_CONTROL_LEN, MAVLINK_MSG_ID_DIGICAM_CONTROL_CRC);
}
/**
* @brief Pack a digicam_control message on a channel
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID.
* @param target_component Component ID.
* @param session 0: stop, 1: start or keep it up //Session control e.g. show/hide lens.
* @param zoom_pos 1 to N //Zoom's absolute position (0 means ignore).
* @param zoom_step -100 to 100 //Zooming step value to offset zoom from the current position.
* @param focus_lock 0: unlock focus or keep unlocked, 1: lock focus or keep locked, 3: re-lock focus.
* @param shot 0: ignore, 1: shot or start filming.
* @param command_id Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once.
* @param extra_param Extra parameters enumeration (0 means ignore).
* @param extra_value Correspondent value to given extra_param.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_digicam_control_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 session,uint8_t zoom_pos,int8_t zoom_step,uint8_t focus_lock,uint8_t shot,uint8_t command_id,uint8_t extra_param,float extra_value)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_DIGICAM_CONTROL_LEN];
_mav_put_float(buf, 0, extra_value);
_mav_put_uint8_t(buf, 4, target_system);
_mav_put_uint8_t(buf, 5, target_component);
_mav_put_uint8_t(buf, 6, session);
_mav_put_uint8_t(buf, 7, zoom_pos);
_mav_put_int8_t(buf, 8, zoom_step);
_mav_put_uint8_t(buf, 9, focus_lock);
_mav_put_uint8_t(buf, 10, shot);
_mav_put_uint8_t(buf, 11, command_id);
_mav_put_uint8_t(buf, 12, extra_param);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DIGICAM_CONTROL_LEN);
#else
mavlink_digicam_control_t packet;
packet.extra_value = extra_value;
packet.target_system = target_system;
packet.target_component = target_component;
packet.session = session;
packet.zoom_pos = zoom_pos;
packet.zoom_step = zoom_step;
packet.focus_lock = focus_lock;
packet.shot = shot;
packet.command_id = command_id;
packet.extra_param = extra_param;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DIGICAM_CONTROL_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_DIGICAM_CONTROL;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DIGICAM_CONTROL_MIN_LEN, MAVLINK_MSG_ID_DIGICAM_CONTROL_LEN, MAVLINK_MSG_ID_DIGICAM_CONTROL_CRC);
}
/**
* @brief Encode a digicam_control struct
*
* @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 digicam_control C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_digicam_control_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_digicam_control_t* digicam_control)
{
return mavlink_msg_digicam_control_pack(system_id, component_id, msg, digicam_control->target_system, digicam_control->target_component, digicam_control->session, digicam_control->zoom_pos, digicam_control->zoom_step, digicam_control->focus_lock, digicam_control->shot, digicam_control->command_id, digicam_control->extra_param, digicam_control->extra_value);
}
/**
* @brief Encode a digicam_control struct on a channel
*
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param digicam_control C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_digicam_control_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_digicam_control_t* digicam_control)
{
return mavlink_msg_digicam_control_pack_chan(system_id, component_id, chan, msg, digicam_control->target_system, digicam_control->target_component, digicam_control->session, digicam_control->zoom_pos, digicam_control->zoom_step, digicam_control->focus_lock, digicam_control->shot, digicam_control->command_id, digicam_control->extra_param, digicam_control->extra_value);
}
/**
* @brief Send a digicam_control message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID.
* @param target_component Component ID.
* @param session 0: stop, 1: start or keep it up //Session control e.g. show/hide lens.
* @param zoom_pos 1 to N //Zoom's absolute position (0 means ignore).
* @param zoom_step -100 to 100 //Zooming step value to offset zoom from the current position.
* @param focus_lock 0: unlock focus or keep unlocked, 1: lock focus or keep locked, 3: re-lock focus.
* @param shot 0: ignore, 1: shot or start filming.
* @param command_id Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once.
* @param extra_param Extra parameters enumeration (0 means ignore).
* @param extra_value Correspondent value to given extra_param.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_digicam_control_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t session, uint8_t zoom_pos, int8_t zoom_step, uint8_t focus_lock, uint8_t shot, uint8_t command_id, uint8_t extra_param, float extra_value)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_DIGICAM_CONTROL_LEN];
_mav_put_float(buf, 0, extra_value);
_mav_put_uint8_t(buf, 4, target_system);
_mav_put_uint8_t(buf, 5, target_component);
_mav_put_uint8_t(buf, 6, session);
_mav_put_uint8_t(buf, 7, zoom_pos);
_mav_put_int8_t(buf, 8, zoom_step);
_mav_put_uint8_t(buf, 9, focus_lock);
_mav_put_uint8_t(buf, 10, shot);
_mav_put_uint8_t(buf, 11, command_id);
_mav_put_uint8_t(buf, 12, extra_param);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DIGICAM_CONTROL, buf, MAVLINK_MSG_ID_DIGICAM_CONTROL_MIN_LEN, MAVLINK_MSG_ID_DIGICAM_CONTROL_LEN, MAVLINK_MSG_ID_DIGICAM_CONTROL_CRC);
#else
mavlink_digicam_control_t packet;
packet.extra_value = extra_value;
packet.target_system = target_system;
packet.target_component = target_component;
packet.session = session;
packet.zoom_pos = zoom_pos;
packet.zoom_step = zoom_step;
packet.focus_lock = focus_lock;
packet.shot = shot;
packet.command_id = command_id;
packet.extra_param = extra_param;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DIGICAM_CONTROL, (const char *)&packet, MAVLINK_MSG_ID_DIGICAM_CONTROL_MIN_LEN, MAVLINK_MSG_ID_DIGICAM_CONTROL_LEN, MAVLINK_MSG_ID_DIGICAM_CONTROL_CRC);
#endif
}
/**
* @brief Send a digicam_control message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_digicam_control_send_struct(mavlink_channel_t chan, const mavlink_digicam_control_t* digicam_control)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_digicam_control_send(chan, digicam_control->target_system, digicam_control->target_component, digicam_control->session, digicam_control->zoom_pos, digicam_control->zoom_step, digicam_control->focus_lock, digicam_control->shot, digicam_control->command_id, digicam_control->extra_param, digicam_control->extra_value);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DIGICAM_CONTROL, (const char *)digicam_control, MAVLINK_MSG_ID_DIGICAM_CONTROL_MIN_LEN, MAVLINK_MSG_ID_DIGICAM_CONTROL_LEN, MAVLINK_MSG_ID_DIGICAM_CONTROL_CRC);
#endif
}
#if MAVLINK_MSG_ID_DIGICAM_CONTROL_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_digicam_control_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t session, uint8_t zoom_pos, int8_t zoom_step, uint8_t focus_lock, uint8_t shot, uint8_t command_id, uint8_t extra_param, float extra_value)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_float(buf, 0, extra_value);
_mav_put_uint8_t(buf, 4, target_system);
_mav_put_uint8_t(buf, 5, target_component);
_mav_put_uint8_t(buf, 6, session);
_mav_put_uint8_t(buf, 7, zoom_pos);
_mav_put_int8_t(buf, 8, zoom_step);
_mav_put_uint8_t(buf, 9, focus_lock);
_mav_put_uint8_t(buf, 10, shot);
_mav_put_uint8_t(buf, 11, command_id);
_mav_put_uint8_t(buf, 12, extra_param);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DIGICAM_CONTROL, buf, MAVLINK_MSG_ID_DIGICAM_CONTROL_MIN_LEN, MAVLINK_MSG_ID_DIGICAM_CONTROL_LEN, MAVLINK_MSG_ID_DIGICAM_CONTROL_CRC);
#else
mavlink_digicam_control_t *packet = (mavlink_digicam_control_t *)msgbuf;
packet->extra_value = extra_value;
packet->target_system = target_system;
packet->target_component = target_component;
packet->session = session;
packet->zoom_pos = zoom_pos;
packet->zoom_step = zoom_step;
packet->focus_lock = focus_lock;
packet->shot = shot;
packet->command_id = command_id;
packet->extra_param = extra_param;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DIGICAM_CONTROL, (const char *)packet, MAVLINK_MSG_ID_DIGICAM_CONTROL_MIN_LEN, MAVLINK_MSG_ID_DIGICAM_CONTROL_LEN, MAVLINK_MSG_ID_DIGICAM_CONTROL_CRC);
#endif
}
#endif
#endif
// MESSAGE DIGICAM_CONTROL UNPACKING
/**
* @brief Get field target_system from digicam_control message
*
* @return System ID.
*/
static inline uint8_t mavlink_msg_digicam_control_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 4);
}
/**
* @brief Get field target_component from digicam_control message
*
* @return Component ID.
*/
static inline uint8_t mavlink_msg_digicam_control_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 5);
}
/**
* @brief Get field session from digicam_control message
*
* @return 0: stop, 1: start or keep it up //Session control e.g. show/hide lens.
*/
static inline uint8_t mavlink_msg_digicam_control_get_session(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 6);
}
/**
* @brief Get field zoom_pos from digicam_control message
*
* @return 1 to N //Zoom's absolute position (0 means ignore).
*/
static inline uint8_t mavlink_msg_digicam_control_get_zoom_pos(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 7);
}
/**
* @brief Get field zoom_step from digicam_control message
*
* @return -100 to 100 //Zooming step value to offset zoom from the current position.
*/
static inline int8_t mavlink_msg_digicam_control_get_zoom_step(const mavlink_message_t* msg)
{
return _MAV_RETURN_int8_t(msg, 8);
}
/**
* @brief Get field focus_lock from digicam_control message
*
* @return 0: unlock focus or keep unlocked, 1: lock focus or keep locked, 3: re-lock focus.
*/
static inline uint8_t mavlink_msg_digicam_control_get_focus_lock(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 9);
}
/**
* @brief Get field shot from digicam_control message
*
* @return 0: ignore, 1: shot or start filming.
*/
static inline uint8_t mavlink_msg_digicam_control_get_shot(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 10);
}
/**
* @brief Get field command_id from digicam_control message
*
* @return Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once.
*/
static inline uint8_t mavlink_msg_digicam_control_get_command_id(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 11);
}
/**
* @brief Get field extra_param from digicam_control message
*
* @return Extra parameters enumeration (0 means ignore).
*/
static inline uint8_t mavlink_msg_digicam_control_get_extra_param(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 12);
}
/**
* @brief Get field extra_value from digicam_control message
*
* @return Correspondent value to given extra_param.
*/
static inline float mavlink_msg_digicam_control_get_extra_value(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 0);
}
/**
* @brief Decode a digicam_control message into a struct
*
* @param msg The message to decode
* @param digicam_control C-struct to decode the message contents into
*/
static inline void mavlink_msg_digicam_control_decode(const mavlink_message_t* msg, mavlink_digicam_control_t* digicam_control)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
digicam_control->extra_value = mavlink_msg_digicam_control_get_extra_value(msg);
digicam_control->target_system = mavlink_msg_digicam_control_get_target_system(msg);
digicam_control->target_component = mavlink_msg_digicam_control_get_target_component(msg);
digicam_control->session = mavlink_msg_digicam_control_get_session(msg);
digicam_control->zoom_pos = mavlink_msg_digicam_control_get_zoom_pos(msg);
digicam_control->zoom_step = mavlink_msg_digicam_control_get_zoom_step(msg);
digicam_control->focus_lock = mavlink_msg_digicam_control_get_focus_lock(msg);
digicam_control->shot = mavlink_msg_digicam_control_get_shot(msg);
digicam_control->command_id = mavlink_msg_digicam_control_get_command_id(msg);
digicam_control->extra_param = mavlink_msg_digicam_control_get_extra_param(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_DIGICAM_CONTROL_LEN? msg->len : MAVLINK_MSG_ID_DIGICAM_CONTROL_LEN;
memset(digicam_control, 0, MAVLINK_MSG_ID_DIGICAM_CONTROL_LEN);
memcpy(digicam_control, _MAV_PAYLOAD(msg), len);
#endif
}

View File

@@ -0,0 +1,363 @@
#pragma once
// MESSAGE EKF_STATUS_REPORT PACKING
#define MAVLINK_MSG_ID_EKF_STATUS_REPORT 193
MAVPACKED(
typedef struct __mavlink_ekf_status_report_t {
float velocity_variance; /*< Velocity variance.*/
float pos_horiz_variance; /*< Horizontal Position variance.*/
float pos_vert_variance; /*< Vertical Position variance.*/
float compass_variance; /*< Compass variance.*/
float terrain_alt_variance; /*< Terrain Altitude variance.*/
uint16_t flags; /*< Flags.*/
float airspeed_variance; /*< Airspeed variance.*/
}) mavlink_ekf_status_report_t;
#define MAVLINK_MSG_ID_EKF_STATUS_REPORT_LEN 26
#define MAVLINK_MSG_ID_EKF_STATUS_REPORT_MIN_LEN 22
#define MAVLINK_MSG_ID_193_LEN 26
#define MAVLINK_MSG_ID_193_MIN_LEN 22
#define MAVLINK_MSG_ID_EKF_STATUS_REPORT_CRC 71
#define MAVLINK_MSG_ID_193_CRC 71
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_EKF_STATUS_REPORT { \
193, \
"EKF_STATUS_REPORT", \
7, \
{ { "flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_ekf_status_report_t, flags) }, \
{ "velocity_variance", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_ekf_status_report_t, velocity_variance) }, \
{ "pos_horiz_variance", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_ekf_status_report_t, pos_horiz_variance) }, \
{ "pos_vert_variance", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_ekf_status_report_t, pos_vert_variance) }, \
{ "compass_variance", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_ekf_status_report_t, compass_variance) }, \
{ "terrain_alt_variance", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_ekf_status_report_t, terrain_alt_variance) }, \
{ "airspeed_variance", NULL, MAVLINK_TYPE_FLOAT, 0, 22, offsetof(mavlink_ekf_status_report_t, airspeed_variance) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_EKF_STATUS_REPORT { \
"EKF_STATUS_REPORT", \
7, \
{ { "flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_ekf_status_report_t, flags) }, \
{ "velocity_variance", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_ekf_status_report_t, velocity_variance) }, \
{ "pos_horiz_variance", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_ekf_status_report_t, pos_horiz_variance) }, \
{ "pos_vert_variance", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_ekf_status_report_t, pos_vert_variance) }, \
{ "compass_variance", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_ekf_status_report_t, compass_variance) }, \
{ "terrain_alt_variance", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_ekf_status_report_t, terrain_alt_variance) }, \
{ "airspeed_variance", NULL, MAVLINK_TYPE_FLOAT, 0, 22, offsetof(mavlink_ekf_status_report_t, airspeed_variance) }, \
} \
}
#endif
/**
* @brief Pack a ekf_status_report 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 flags Flags.
* @param velocity_variance Velocity variance.
* @param pos_horiz_variance Horizontal Position variance.
* @param pos_vert_variance Vertical Position variance.
* @param compass_variance Compass variance.
* @param terrain_alt_variance Terrain Altitude variance.
* @param airspeed_variance Airspeed variance.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_ekf_status_report_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint16_t flags, float velocity_variance, float pos_horiz_variance, float pos_vert_variance, float compass_variance, float terrain_alt_variance, float airspeed_variance)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_EKF_STATUS_REPORT_LEN];
_mav_put_float(buf, 0, velocity_variance);
_mav_put_float(buf, 4, pos_horiz_variance);
_mav_put_float(buf, 8, pos_vert_variance);
_mav_put_float(buf, 12, compass_variance);
_mav_put_float(buf, 16, terrain_alt_variance);
_mav_put_uint16_t(buf, 20, flags);
_mav_put_float(buf, 22, airspeed_variance);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_EKF_STATUS_REPORT_LEN);
#else
mavlink_ekf_status_report_t packet;
packet.velocity_variance = velocity_variance;
packet.pos_horiz_variance = pos_horiz_variance;
packet.pos_vert_variance = pos_vert_variance;
packet.compass_variance = compass_variance;
packet.terrain_alt_variance = terrain_alt_variance;
packet.flags = flags;
packet.airspeed_variance = airspeed_variance;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_EKF_STATUS_REPORT_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_EKF_STATUS_REPORT;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_EKF_STATUS_REPORT_MIN_LEN, MAVLINK_MSG_ID_EKF_STATUS_REPORT_LEN, MAVLINK_MSG_ID_EKF_STATUS_REPORT_CRC);
}
/**
* @brief Pack a ekf_status_report message on a channel
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param flags Flags.
* @param velocity_variance Velocity variance.
* @param pos_horiz_variance Horizontal Position variance.
* @param pos_vert_variance Vertical Position variance.
* @param compass_variance Compass variance.
* @param terrain_alt_variance Terrain Altitude variance.
* @param airspeed_variance Airspeed variance.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_ekf_status_report_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint16_t flags,float velocity_variance,float pos_horiz_variance,float pos_vert_variance,float compass_variance,float terrain_alt_variance,float airspeed_variance)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_EKF_STATUS_REPORT_LEN];
_mav_put_float(buf, 0, velocity_variance);
_mav_put_float(buf, 4, pos_horiz_variance);
_mav_put_float(buf, 8, pos_vert_variance);
_mav_put_float(buf, 12, compass_variance);
_mav_put_float(buf, 16, terrain_alt_variance);
_mav_put_uint16_t(buf, 20, flags);
_mav_put_float(buf, 22, airspeed_variance);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_EKF_STATUS_REPORT_LEN);
#else
mavlink_ekf_status_report_t packet;
packet.velocity_variance = velocity_variance;
packet.pos_horiz_variance = pos_horiz_variance;
packet.pos_vert_variance = pos_vert_variance;
packet.compass_variance = compass_variance;
packet.terrain_alt_variance = terrain_alt_variance;
packet.flags = flags;
packet.airspeed_variance = airspeed_variance;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_EKF_STATUS_REPORT_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_EKF_STATUS_REPORT;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_EKF_STATUS_REPORT_MIN_LEN, MAVLINK_MSG_ID_EKF_STATUS_REPORT_LEN, MAVLINK_MSG_ID_EKF_STATUS_REPORT_CRC);
}
/**
* @brief Encode a ekf_status_report struct
*
* @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 ekf_status_report C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_ekf_status_report_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_ekf_status_report_t* ekf_status_report)
{
return mavlink_msg_ekf_status_report_pack(system_id, component_id, msg, ekf_status_report->flags, ekf_status_report->velocity_variance, ekf_status_report->pos_horiz_variance, ekf_status_report->pos_vert_variance, ekf_status_report->compass_variance, ekf_status_report->terrain_alt_variance, ekf_status_report->airspeed_variance);
}
/**
* @brief Encode a ekf_status_report struct on a channel
*
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param ekf_status_report C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_ekf_status_report_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_ekf_status_report_t* ekf_status_report)
{
return mavlink_msg_ekf_status_report_pack_chan(system_id, component_id, chan, msg, ekf_status_report->flags, ekf_status_report->velocity_variance, ekf_status_report->pos_horiz_variance, ekf_status_report->pos_vert_variance, ekf_status_report->compass_variance, ekf_status_report->terrain_alt_variance, ekf_status_report->airspeed_variance);
}
/**
* @brief Send a ekf_status_report message
* @param chan MAVLink channel to send the message
*
* @param flags Flags.
* @param velocity_variance Velocity variance.
* @param pos_horiz_variance Horizontal Position variance.
* @param pos_vert_variance Vertical Position variance.
* @param compass_variance Compass variance.
* @param terrain_alt_variance Terrain Altitude variance.
* @param airspeed_variance Airspeed variance.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_ekf_status_report_send(mavlink_channel_t chan, uint16_t flags, float velocity_variance, float pos_horiz_variance, float pos_vert_variance, float compass_variance, float terrain_alt_variance, float airspeed_variance)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_EKF_STATUS_REPORT_LEN];
_mav_put_float(buf, 0, velocity_variance);
_mav_put_float(buf, 4, pos_horiz_variance);
_mav_put_float(buf, 8, pos_vert_variance);
_mav_put_float(buf, 12, compass_variance);
_mav_put_float(buf, 16, terrain_alt_variance);
_mav_put_uint16_t(buf, 20, flags);
_mav_put_float(buf, 22, airspeed_variance);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_EKF_STATUS_REPORT, buf, MAVLINK_MSG_ID_EKF_STATUS_REPORT_MIN_LEN, MAVLINK_MSG_ID_EKF_STATUS_REPORT_LEN, MAVLINK_MSG_ID_EKF_STATUS_REPORT_CRC);
#else
mavlink_ekf_status_report_t packet;
packet.velocity_variance = velocity_variance;
packet.pos_horiz_variance = pos_horiz_variance;
packet.pos_vert_variance = pos_vert_variance;
packet.compass_variance = compass_variance;
packet.terrain_alt_variance = terrain_alt_variance;
packet.flags = flags;
packet.airspeed_variance = airspeed_variance;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_EKF_STATUS_REPORT, (const char *)&packet, MAVLINK_MSG_ID_EKF_STATUS_REPORT_MIN_LEN, MAVLINK_MSG_ID_EKF_STATUS_REPORT_LEN, MAVLINK_MSG_ID_EKF_STATUS_REPORT_CRC);
#endif
}
/**
* @brief Send a ekf_status_report message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_ekf_status_report_send_struct(mavlink_channel_t chan, const mavlink_ekf_status_report_t* ekf_status_report)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_ekf_status_report_send(chan, ekf_status_report->flags, ekf_status_report->velocity_variance, ekf_status_report->pos_horiz_variance, ekf_status_report->pos_vert_variance, ekf_status_report->compass_variance, ekf_status_report->terrain_alt_variance, ekf_status_report->airspeed_variance);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_EKF_STATUS_REPORT, (const char *)ekf_status_report, MAVLINK_MSG_ID_EKF_STATUS_REPORT_MIN_LEN, MAVLINK_MSG_ID_EKF_STATUS_REPORT_LEN, MAVLINK_MSG_ID_EKF_STATUS_REPORT_CRC);
#endif
}
#if MAVLINK_MSG_ID_EKF_STATUS_REPORT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_ekf_status_report_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t flags, float velocity_variance, float pos_horiz_variance, float pos_vert_variance, float compass_variance, float terrain_alt_variance, float airspeed_variance)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_float(buf, 0, velocity_variance);
_mav_put_float(buf, 4, pos_horiz_variance);
_mav_put_float(buf, 8, pos_vert_variance);
_mav_put_float(buf, 12, compass_variance);
_mav_put_float(buf, 16, terrain_alt_variance);
_mav_put_uint16_t(buf, 20, flags);
_mav_put_float(buf, 22, airspeed_variance);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_EKF_STATUS_REPORT, buf, MAVLINK_MSG_ID_EKF_STATUS_REPORT_MIN_LEN, MAVLINK_MSG_ID_EKF_STATUS_REPORT_LEN, MAVLINK_MSG_ID_EKF_STATUS_REPORT_CRC);
#else
mavlink_ekf_status_report_t *packet = (mavlink_ekf_status_report_t *)msgbuf;
packet->velocity_variance = velocity_variance;
packet->pos_horiz_variance = pos_horiz_variance;
packet->pos_vert_variance = pos_vert_variance;
packet->compass_variance = compass_variance;
packet->terrain_alt_variance = terrain_alt_variance;
packet->flags = flags;
packet->airspeed_variance = airspeed_variance;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_EKF_STATUS_REPORT, (const char *)packet, MAVLINK_MSG_ID_EKF_STATUS_REPORT_MIN_LEN, MAVLINK_MSG_ID_EKF_STATUS_REPORT_LEN, MAVLINK_MSG_ID_EKF_STATUS_REPORT_CRC);
#endif
}
#endif
#endif
// MESSAGE EKF_STATUS_REPORT UNPACKING
/**
* @brief Get field flags from ekf_status_report message
*
* @return Flags.
*/
static inline uint16_t mavlink_msg_ekf_status_report_get_flags(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 20);
}
/**
* @brief Get field velocity_variance from ekf_status_report message
*
* @return Velocity variance.
*/
static inline float mavlink_msg_ekf_status_report_get_velocity_variance(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 0);
}
/**
* @brief Get field pos_horiz_variance from ekf_status_report message
*
* @return Horizontal Position variance.
*/
static inline float mavlink_msg_ekf_status_report_get_pos_horiz_variance(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 4);
}
/**
* @brief Get field pos_vert_variance from ekf_status_report message
*
* @return Vertical Position variance.
*/
static inline float mavlink_msg_ekf_status_report_get_pos_vert_variance(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
/**
* @brief Get field compass_variance from ekf_status_report message
*
* @return Compass variance.
*/
static inline float mavlink_msg_ekf_status_report_get_compass_variance(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
/**
* @brief Get field terrain_alt_variance from ekf_status_report message
*
* @return Terrain Altitude variance.
*/
static inline float mavlink_msg_ekf_status_report_get_terrain_alt_variance(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 16);
}
/**
* @brief Get field airspeed_variance from ekf_status_report message
*
* @return Airspeed variance.
*/
static inline float mavlink_msg_ekf_status_report_get_airspeed_variance(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 22);
}
/**
* @brief Decode a ekf_status_report message into a struct
*
* @param msg The message to decode
* @param ekf_status_report C-struct to decode the message contents into
*/
static inline void mavlink_msg_ekf_status_report_decode(const mavlink_message_t* msg, mavlink_ekf_status_report_t* ekf_status_report)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
ekf_status_report->velocity_variance = mavlink_msg_ekf_status_report_get_velocity_variance(msg);
ekf_status_report->pos_horiz_variance = mavlink_msg_ekf_status_report_get_pos_horiz_variance(msg);
ekf_status_report->pos_vert_variance = mavlink_msg_ekf_status_report_get_pos_vert_variance(msg);
ekf_status_report->compass_variance = mavlink_msg_ekf_status_report_get_compass_variance(msg);
ekf_status_report->terrain_alt_variance = mavlink_msg_ekf_status_report_get_terrain_alt_variance(msg);
ekf_status_report->flags = mavlink_msg_ekf_status_report_get_flags(msg);
ekf_status_report->airspeed_variance = mavlink_msg_ekf_status_report_get_airspeed_variance(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_EKF_STATUS_REPORT_LEN? msg->len : MAVLINK_MSG_ID_EKF_STATUS_REPORT_LEN;
memset(ekf_status_report, 0, MAVLINK_MSG_ID_EKF_STATUS_REPORT_LEN);
memcpy(ekf_status_report, _MAV_PAYLOAD(msg), len);
#endif
}

View File

@@ -0,0 +1,343 @@
#pragma once
// MESSAGE ESC_TELEMETRY_1_TO_4 PACKING
#define MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4 11030
MAVPACKED(
typedef struct __mavlink_esc_telemetry_1_to_4_t {
uint16_t voltage[4]; /*< [cV] Voltage*/
uint16_t current[4]; /*< [cA] Current*/
uint16_t totalcurrent[4]; /*< [mAh] Total current*/
uint16_t rpm[4]; /*< [rpm] RPM (eRPM)*/
uint16_t count[4]; /*< count of telemetry packets received (wraps at 65535)*/
uint8_t temperature[4]; /*< [degC] Temperature*/
}) mavlink_esc_telemetry_1_to_4_t;
#define MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_LEN 44
#define MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_MIN_LEN 44
#define MAVLINK_MSG_ID_11030_LEN 44
#define MAVLINK_MSG_ID_11030_MIN_LEN 44
#define MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_CRC 144
#define MAVLINK_MSG_ID_11030_CRC 144
#define MAVLINK_MSG_ESC_TELEMETRY_1_TO_4_FIELD_VOLTAGE_LEN 4
#define MAVLINK_MSG_ESC_TELEMETRY_1_TO_4_FIELD_CURRENT_LEN 4
#define MAVLINK_MSG_ESC_TELEMETRY_1_TO_4_FIELD_TOTALCURRENT_LEN 4
#define MAVLINK_MSG_ESC_TELEMETRY_1_TO_4_FIELD_RPM_LEN 4
#define MAVLINK_MSG_ESC_TELEMETRY_1_TO_4_FIELD_COUNT_LEN 4
#define MAVLINK_MSG_ESC_TELEMETRY_1_TO_4_FIELD_TEMPERATURE_LEN 4
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_ESC_TELEMETRY_1_TO_4 { \
11030, \
"ESC_TELEMETRY_1_TO_4", \
6, \
{ { "temperature", NULL, MAVLINK_TYPE_UINT8_T, 4, 40, offsetof(mavlink_esc_telemetry_1_to_4_t, temperature) }, \
{ "voltage", NULL, MAVLINK_TYPE_UINT16_T, 4, 0, offsetof(mavlink_esc_telemetry_1_to_4_t, voltage) }, \
{ "current", NULL, MAVLINK_TYPE_UINT16_T, 4, 8, offsetof(mavlink_esc_telemetry_1_to_4_t, current) }, \
{ "totalcurrent", NULL, MAVLINK_TYPE_UINT16_T, 4, 16, offsetof(mavlink_esc_telemetry_1_to_4_t, totalcurrent) }, \
{ "rpm", NULL, MAVLINK_TYPE_UINT16_T, 4, 24, offsetof(mavlink_esc_telemetry_1_to_4_t, rpm) }, \
{ "count", NULL, MAVLINK_TYPE_UINT16_T, 4, 32, offsetof(mavlink_esc_telemetry_1_to_4_t, count) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_ESC_TELEMETRY_1_TO_4 { \
"ESC_TELEMETRY_1_TO_4", \
6, \
{ { "temperature", NULL, MAVLINK_TYPE_UINT8_T, 4, 40, offsetof(mavlink_esc_telemetry_1_to_4_t, temperature) }, \
{ "voltage", NULL, MAVLINK_TYPE_UINT16_T, 4, 0, offsetof(mavlink_esc_telemetry_1_to_4_t, voltage) }, \
{ "current", NULL, MAVLINK_TYPE_UINT16_T, 4, 8, offsetof(mavlink_esc_telemetry_1_to_4_t, current) }, \
{ "totalcurrent", NULL, MAVLINK_TYPE_UINT16_T, 4, 16, offsetof(mavlink_esc_telemetry_1_to_4_t, totalcurrent) }, \
{ "rpm", NULL, MAVLINK_TYPE_UINT16_T, 4, 24, offsetof(mavlink_esc_telemetry_1_to_4_t, rpm) }, \
{ "count", NULL, MAVLINK_TYPE_UINT16_T, 4, 32, offsetof(mavlink_esc_telemetry_1_to_4_t, count) }, \
} \
}
#endif
/**
* @brief Pack a esc_telemetry_1_to_4 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 temperature [degC] Temperature
* @param voltage [cV] Voltage
* @param current [cA] Current
* @param totalcurrent [mAh] Total current
* @param rpm [rpm] RPM (eRPM)
* @param count count of telemetry packets received (wraps at 65535)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_esc_telemetry_1_to_4_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
const uint8_t *temperature, const uint16_t *voltage, const uint16_t *current, const uint16_t *totalcurrent, const uint16_t *rpm, const uint16_t *count)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_LEN];
_mav_put_uint16_t_array(buf, 0, voltage, 4);
_mav_put_uint16_t_array(buf, 8, current, 4);
_mav_put_uint16_t_array(buf, 16, totalcurrent, 4);
_mav_put_uint16_t_array(buf, 24, rpm, 4);
_mav_put_uint16_t_array(buf, 32, count, 4);
_mav_put_uint8_t_array(buf, 40, temperature, 4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_LEN);
#else
mavlink_esc_telemetry_1_to_4_t packet;
mav_array_memcpy(packet.voltage, voltage, sizeof(uint16_t)*4);
mav_array_memcpy(packet.current, current, sizeof(uint16_t)*4);
mav_array_memcpy(packet.totalcurrent, totalcurrent, sizeof(uint16_t)*4);
mav_array_memcpy(packet.rpm, rpm, sizeof(uint16_t)*4);
mav_array_memcpy(packet.count, count, sizeof(uint16_t)*4);
mav_array_memcpy(packet.temperature, temperature, sizeof(uint8_t)*4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_MIN_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_CRC);
}
/**
* @brief Pack a esc_telemetry_1_to_4 message on a channel
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param temperature [degC] Temperature
* @param voltage [cV] Voltage
* @param current [cA] Current
* @param totalcurrent [mAh] Total current
* @param rpm [rpm] RPM (eRPM)
* @param count count of telemetry packets received (wraps at 65535)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_esc_telemetry_1_to_4_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
const uint8_t *temperature,const uint16_t *voltage,const uint16_t *current,const uint16_t *totalcurrent,const uint16_t *rpm,const uint16_t *count)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_LEN];
_mav_put_uint16_t_array(buf, 0, voltage, 4);
_mav_put_uint16_t_array(buf, 8, current, 4);
_mav_put_uint16_t_array(buf, 16, totalcurrent, 4);
_mav_put_uint16_t_array(buf, 24, rpm, 4);
_mav_put_uint16_t_array(buf, 32, count, 4);
_mav_put_uint8_t_array(buf, 40, temperature, 4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_LEN);
#else
mavlink_esc_telemetry_1_to_4_t packet;
mav_array_memcpy(packet.voltage, voltage, sizeof(uint16_t)*4);
mav_array_memcpy(packet.current, current, sizeof(uint16_t)*4);
mav_array_memcpy(packet.totalcurrent, totalcurrent, sizeof(uint16_t)*4);
mav_array_memcpy(packet.rpm, rpm, sizeof(uint16_t)*4);
mav_array_memcpy(packet.count, count, sizeof(uint16_t)*4);
mav_array_memcpy(packet.temperature, temperature, sizeof(uint8_t)*4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_MIN_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_CRC);
}
/**
* @brief Encode a esc_telemetry_1_to_4 struct
*
* @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 esc_telemetry_1_to_4 C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_esc_telemetry_1_to_4_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_esc_telemetry_1_to_4_t* esc_telemetry_1_to_4)
{
return mavlink_msg_esc_telemetry_1_to_4_pack(system_id, component_id, msg, esc_telemetry_1_to_4->temperature, esc_telemetry_1_to_4->voltage, esc_telemetry_1_to_4->current, esc_telemetry_1_to_4->totalcurrent, esc_telemetry_1_to_4->rpm, esc_telemetry_1_to_4->count);
}
/**
* @brief Encode a esc_telemetry_1_to_4 struct on a channel
*
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param esc_telemetry_1_to_4 C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_esc_telemetry_1_to_4_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_esc_telemetry_1_to_4_t* esc_telemetry_1_to_4)
{
return mavlink_msg_esc_telemetry_1_to_4_pack_chan(system_id, component_id, chan, msg, esc_telemetry_1_to_4->temperature, esc_telemetry_1_to_4->voltage, esc_telemetry_1_to_4->current, esc_telemetry_1_to_4->totalcurrent, esc_telemetry_1_to_4->rpm, esc_telemetry_1_to_4->count);
}
/**
* @brief Send a esc_telemetry_1_to_4 message
* @param chan MAVLink channel to send the message
*
* @param temperature [degC] Temperature
* @param voltage [cV] Voltage
* @param current [cA] Current
* @param totalcurrent [mAh] Total current
* @param rpm [rpm] RPM (eRPM)
* @param count count of telemetry packets received (wraps at 65535)
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_esc_telemetry_1_to_4_send(mavlink_channel_t chan, const uint8_t *temperature, const uint16_t *voltage, const uint16_t *current, const uint16_t *totalcurrent, const uint16_t *rpm, const uint16_t *count)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_LEN];
_mav_put_uint16_t_array(buf, 0, voltage, 4);
_mav_put_uint16_t_array(buf, 8, current, 4);
_mav_put_uint16_t_array(buf, 16, totalcurrent, 4);
_mav_put_uint16_t_array(buf, 24, rpm, 4);
_mav_put_uint16_t_array(buf, 32, count, 4);
_mav_put_uint8_t_array(buf, 40, temperature, 4);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4, buf, MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_MIN_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_CRC);
#else
mavlink_esc_telemetry_1_to_4_t packet;
mav_array_memcpy(packet.voltage, voltage, sizeof(uint16_t)*4);
mav_array_memcpy(packet.current, current, sizeof(uint16_t)*4);
mav_array_memcpy(packet.totalcurrent, totalcurrent, sizeof(uint16_t)*4);
mav_array_memcpy(packet.rpm, rpm, sizeof(uint16_t)*4);
mav_array_memcpy(packet.count, count, sizeof(uint16_t)*4);
mav_array_memcpy(packet.temperature, temperature, sizeof(uint8_t)*4);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4, (const char *)&packet, MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_MIN_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_CRC);
#endif
}
/**
* @brief Send a esc_telemetry_1_to_4 message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_esc_telemetry_1_to_4_send_struct(mavlink_channel_t chan, const mavlink_esc_telemetry_1_to_4_t* esc_telemetry_1_to_4)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_esc_telemetry_1_to_4_send(chan, esc_telemetry_1_to_4->temperature, esc_telemetry_1_to_4->voltage, esc_telemetry_1_to_4->current, esc_telemetry_1_to_4->totalcurrent, esc_telemetry_1_to_4->rpm, esc_telemetry_1_to_4->count);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4, (const char *)esc_telemetry_1_to_4, MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_MIN_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_CRC);
#endif
}
#if MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_esc_telemetry_1_to_4_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, const uint8_t *temperature, const uint16_t *voltage, const uint16_t *current, const uint16_t *totalcurrent, const uint16_t *rpm, const uint16_t *count)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint16_t_array(buf, 0, voltage, 4);
_mav_put_uint16_t_array(buf, 8, current, 4);
_mav_put_uint16_t_array(buf, 16, totalcurrent, 4);
_mav_put_uint16_t_array(buf, 24, rpm, 4);
_mav_put_uint16_t_array(buf, 32, count, 4);
_mav_put_uint8_t_array(buf, 40, temperature, 4);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4, buf, MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_MIN_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_CRC);
#else
mavlink_esc_telemetry_1_to_4_t *packet = (mavlink_esc_telemetry_1_to_4_t *)msgbuf;
mav_array_memcpy(packet->voltage, voltage, sizeof(uint16_t)*4);
mav_array_memcpy(packet->current, current, sizeof(uint16_t)*4);
mav_array_memcpy(packet->totalcurrent, totalcurrent, sizeof(uint16_t)*4);
mav_array_memcpy(packet->rpm, rpm, sizeof(uint16_t)*4);
mav_array_memcpy(packet->count, count, sizeof(uint16_t)*4);
mav_array_memcpy(packet->temperature, temperature, sizeof(uint8_t)*4);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4, (const char *)packet, MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_MIN_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_CRC);
#endif
}
#endif
#endif
// MESSAGE ESC_TELEMETRY_1_TO_4 UNPACKING
/**
* @brief Get field temperature from esc_telemetry_1_to_4 message
*
* @return [degC] Temperature
*/
static inline uint16_t mavlink_msg_esc_telemetry_1_to_4_get_temperature(const mavlink_message_t* msg, uint8_t *temperature)
{
return _MAV_RETURN_uint8_t_array(msg, temperature, 4, 40);
}
/**
* @brief Get field voltage from esc_telemetry_1_to_4 message
*
* @return [cV] Voltage
*/
static inline uint16_t mavlink_msg_esc_telemetry_1_to_4_get_voltage(const mavlink_message_t* msg, uint16_t *voltage)
{
return _MAV_RETURN_uint16_t_array(msg, voltage, 4, 0);
}
/**
* @brief Get field current from esc_telemetry_1_to_4 message
*
* @return [cA] Current
*/
static inline uint16_t mavlink_msg_esc_telemetry_1_to_4_get_current(const mavlink_message_t* msg, uint16_t *current)
{
return _MAV_RETURN_uint16_t_array(msg, current, 4, 8);
}
/**
* @brief Get field totalcurrent from esc_telemetry_1_to_4 message
*
* @return [mAh] Total current
*/
static inline uint16_t mavlink_msg_esc_telemetry_1_to_4_get_totalcurrent(const mavlink_message_t* msg, uint16_t *totalcurrent)
{
return _MAV_RETURN_uint16_t_array(msg, totalcurrent, 4, 16);
}
/**
* @brief Get field rpm from esc_telemetry_1_to_4 message
*
* @return [rpm] RPM (eRPM)
*/
static inline uint16_t mavlink_msg_esc_telemetry_1_to_4_get_rpm(const mavlink_message_t* msg, uint16_t *rpm)
{
return _MAV_RETURN_uint16_t_array(msg, rpm, 4, 24);
}
/**
* @brief Get field count from esc_telemetry_1_to_4 message
*
* @return count of telemetry packets received (wraps at 65535)
*/
static inline uint16_t mavlink_msg_esc_telemetry_1_to_4_get_count(const mavlink_message_t* msg, uint16_t *count)
{
return _MAV_RETURN_uint16_t_array(msg, count, 4, 32);
}
/**
* @brief Decode a esc_telemetry_1_to_4 message into a struct
*
* @param msg The message to decode
* @param esc_telemetry_1_to_4 C-struct to decode the message contents into
*/
static inline void mavlink_msg_esc_telemetry_1_to_4_decode(const mavlink_message_t* msg, mavlink_esc_telemetry_1_to_4_t* esc_telemetry_1_to_4)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_esc_telemetry_1_to_4_get_voltage(msg, esc_telemetry_1_to_4->voltage);
mavlink_msg_esc_telemetry_1_to_4_get_current(msg, esc_telemetry_1_to_4->current);
mavlink_msg_esc_telemetry_1_to_4_get_totalcurrent(msg, esc_telemetry_1_to_4->totalcurrent);
mavlink_msg_esc_telemetry_1_to_4_get_rpm(msg, esc_telemetry_1_to_4->rpm);
mavlink_msg_esc_telemetry_1_to_4_get_count(msg, esc_telemetry_1_to_4->count);
mavlink_msg_esc_telemetry_1_to_4_get_temperature(msg, esc_telemetry_1_to_4->temperature);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_LEN? msg->len : MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_LEN;
memset(esc_telemetry_1_to_4, 0, MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_LEN);
memcpy(esc_telemetry_1_to_4, _MAV_PAYLOAD(msg), len);
#endif
}

View File

@@ -0,0 +1,343 @@
#pragma once
// MESSAGE ESC_TELEMETRY_5_TO_8 PACKING
#define MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8 11031
MAVPACKED(
typedef struct __mavlink_esc_telemetry_5_to_8_t {
uint16_t voltage[4]; /*< [cV] Voltage*/
uint16_t current[4]; /*< [cA] Current*/
uint16_t totalcurrent[4]; /*< [mAh] Total current*/
uint16_t rpm[4]; /*< [rpm] RPM (eRPM)*/
uint16_t count[4]; /*< count of telemetry packets received (wraps at 65535)*/
uint8_t temperature[4]; /*< [degC] Temperature*/
}) mavlink_esc_telemetry_5_to_8_t;
#define MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8_LEN 44
#define MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8_MIN_LEN 44
#define MAVLINK_MSG_ID_11031_LEN 44
#define MAVLINK_MSG_ID_11031_MIN_LEN 44
#define MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8_CRC 133
#define MAVLINK_MSG_ID_11031_CRC 133
#define MAVLINK_MSG_ESC_TELEMETRY_5_TO_8_FIELD_VOLTAGE_LEN 4
#define MAVLINK_MSG_ESC_TELEMETRY_5_TO_8_FIELD_CURRENT_LEN 4
#define MAVLINK_MSG_ESC_TELEMETRY_5_TO_8_FIELD_TOTALCURRENT_LEN 4
#define MAVLINK_MSG_ESC_TELEMETRY_5_TO_8_FIELD_RPM_LEN 4
#define MAVLINK_MSG_ESC_TELEMETRY_5_TO_8_FIELD_COUNT_LEN 4
#define MAVLINK_MSG_ESC_TELEMETRY_5_TO_8_FIELD_TEMPERATURE_LEN 4
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_ESC_TELEMETRY_5_TO_8 { \
11031, \
"ESC_TELEMETRY_5_TO_8", \
6, \
{ { "temperature", NULL, MAVLINK_TYPE_UINT8_T, 4, 40, offsetof(mavlink_esc_telemetry_5_to_8_t, temperature) }, \
{ "voltage", NULL, MAVLINK_TYPE_UINT16_T, 4, 0, offsetof(mavlink_esc_telemetry_5_to_8_t, voltage) }, \
{ "current", NULL, MAVLINK_TYPE_UINT16_T, 4, 8, offsetof(mavlink_esc_telemetry_5_to_8_t, current) }, \
{ "totalcurrent", NULL, MAVLINK_TYPE_UINT16_T, 4, 16, offsetof(mavlink_esc_telemetry_5_to_8_t, totalcurrent) }, \
{ "rpm", NULL, MAVLINK_TYPE_UINT16_T, 4, 24, offsetof(mavlink_esc_telemetry_5_to_8_t, rpm) }, \
{ "count", NULL, MAVLINK_TYPE_UINT16_T, 4, 32, offsetof(mavlink_esc_telemetry_5_to_8_t, count) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_ESC_TELEMETRY_5_TO_8 { \
"ESC_TELEMETRY_5_TO_8", \
6, \
{ { "temperature", NULL, MAVLINK_TYPE_UINT8_T, 4, 40, offsetof(mavlink_esc_telemetry_5_to_8_t, temperature) }, \
{ "voltage", NULL, MAVLINK_TYPE_UINT16_T, 4, 0, offsetof(mavlink_esc_telemetry_5_to_8_t, voltage) }, \
{ "current", NULL, MAVLINK_TYPE_UINT16_T, 4, 8, offsetof(mavlink_esc_telemetry_5_to_8_t, current) }, \
{ "totalcurrent", NULL, MAVLINK_TYPE_UINT16_T, 4, 16, offsetof(mavlink_esc_telemetry_5_to_8_t, totalcurrent) }, \
{ "rpm", NULL, MAVLINK_TYPE_UINT16_T, 4, 24, offsetof(mavlink_esc_telemetry_5_to_8_t, rpm) }, \
{ "count", NULL, MAVLINK_TYPE_UINT16_T, 4, 32, offsetof(mavlink_esc_telemetry_5_to_8_t, count) }, \
} \
}
#endif
/**
* @brief Pack a esc_telemetry_5_to_8 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 temperature [degC] Temperature
* @param voltage [cV] Voltage
* @param current [cA] Current
* @param totalcurrent [mAh] Total current
* @param rpm [rpm] RPM (eRPM)
* @param count count of telemetry packets received (wraps at 65535)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_esc_telemetry_5_to_8_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
const uint8_t *temperature, const uint16_t *voltage, const uint16_t *current, const uint16_t *totalcurrent, const uint16_t *rpm, const uint16_t *count)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8_LEN];
_mav_put_uint16_t_array(buf, 0, voltage, 4);
_mav_put_uint16_t_array(buf, 8, current, 4);
_mav_put_uint16_t_array(buf, 16, totalcurrent, 4);
_mav_put_uint16_t_array(buf, 24, rpm, 4);
_mav_put_uint16_t_array(buf, 32, count, 4);
_mav_put_uint8_t_array(buf, 40, temperature, 4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8_LEN);
#else
mavlink_esc_telemetry_5_to_8_t packet;
mav_array_memcpy(packet.voltage, voltage, sizeof(uint16_t)*4);
mav_array_memcpy(packet.current, current, sizeof(uint16_t)*4);
mav_array_memcpy(packet.totalcurrent, totalcurrent, sizeof(uint16_t)*4);
mav_array_memcpy(packet.rpm, rpm, sizeof(uint16_t)*4);
mav_array_memcpy(packet.count, count, sizeof(uint16_t)*4);
mav_array_memcpy(packet.temperature, temperature, sizeof(uint8_t)*4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8_MIN_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8_CRC);
}
/**
* @brief Pack a esc_telemetry_5_to_8 message on a channel
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param temperature [degC] Temperature
* @param voltage [cV] Voltage
* @param current [cA] Current
* @param totalcurrent [mAh] Total current
* @param rpm [rpm] RPM (eRPM)
* @param count count of telemetry packets received (wraps at 65535)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_esc_telemetry_5_to_8_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
const uint8_t *temperature,const uint16_t *voltage,const uint16_t *current,const uint16_t *totalcurrent,const uint16_t *rpm,const uint16_t *count)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8_LEN];
_mav_put_uint16_t_array(buf, 0, voltage, 4);
_mav_put_uint16_t_array(buf, 8, current, 4);
_mav_put_uint16_t_array(buf, 16, totalcurrent, 4);
_mav_put_uint16_t_array(buf, 24, rpm, 4);
_mav_put_uint16_t_array(buf, 32, count, 4);
_mav_put_uint8_t_array(buf, 40, temperature, 4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8_LEN);
#else
mavlink_esc_telemetry_5_to_8_t packet;
mav_array_memcpy(packet.voltage, voltage, sizeof(uint16_t)*4);
mav_array_memcpy(packet.current, current, sizeof(uint16_t)*4);
mav_array_memcpy(packet.totalcurrent, totalcurrent, sizeof(uint16_t)*4);
mav_array_memcpy(packet.rpm, rpm, sizeof(uint16_t)*4);
mav_array_memcpy(packet.count, count, sizeof(uint16_t)*4);
mav_array_memcpy(packet.temperature, temperature, sizeof(uint8_t)*4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8_MIN_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8_CRC);
}
/**
* @brief Encode a esc_telemetry_5_to_8 struct
*
* @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 esc_telemetry_5_to_8 C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_esc_telemetry_5_to_8_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_esc_telemetry_5_to_8_t* esc_telemetry_5_to_8)
{
return mavlink_msg_esc_telemetry_5_to_8_pack(system_id, component_id, msg, esc_telemetry_5_to_8->temperature, esc_telemetry_5_to_8->voltage, esc_telemetry_5_to_8->current, esc_telemetry_5_to_8->totalcurrent, esc_telemetry_5_to_8->rpm, esc_telemetry_5_to_8->count);
}
/**
* @brief Encode a esc_telemetry_5_to_8 struct on a channel
*
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param esc_telemetry_5_to_8 C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_esc_telemetry_5_to_8_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_esc_telemetry_5_to_8_t* esc_telemetry_5_to_8)
{
return mavlink_msg_esc_telemetry_5_to_8_pack_chan(system_id, component_id, chan, msg, esc_telemetry_5_to_8->temperature, esc_telemetry_5_to_8->voltage, esc_telemetry_5_to_8->current, esc_telemetry_5_to_8->totalcurrent, esc_telemetry_5_to_8->rpm, esc_telemetry_5_to_8->count);
}
/**
* @brief Send a esc_telemetry_5_to_8 message
* @param chan MAVLink channel to send the message
*
* @param temperature [degC] Temperature
* @param voltage [cV] Voltage
* @param current [cA] Current
* @param totalcurrent [mAh] Total current
* @param rpm [rpm] RPM (eRPM)
* @param count count of telemetry packets received (wraps at 65535)
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_esc_telemetry_5_to_8_send(mavlink_channel_t chan, const uint8_t *temperature, const uint16_t *voltage, const uint16_t *current, const uint16_t *totalcurrent, const uint16_t *rpm, const uint16_t *count)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8_LEN];
_mav_put_uint16_t_array(buf, 0, voltage, 4);
_mav_put_uint16_t_array(buf, 8, current, 4);
_mav_put_uint16_t_array(buf, 16, totalcurrent, 4);
_mav_put_uint16_t_array(buf, 24, rpm, 4);
_mav_put_uint16_t_array(buf, 32, count, 4);
_mav_put_uint8_t_array(buf, 40, temperature, 4);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8, buf, MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8_MIN_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8_CRC);
#else
mavlink_esc_telemetry_5_to_8_t packet;
mav_array_memcpy(packet.voltage, voltage, sizeof(uint16_t)*4);
mav_array_memcpy(packet.current, current, sizeof(uint16_t)*4);
mav_array_memcpy(packet.totalcurrent, totalcurrent, sizeof(uint16_t)*4);
mav_array_memcpy(packet.rpm, rpm, sizeof(uint16_t)*4);
mav_array_memcpy(packet.count, count, sizeof(uint16_t)*4);
mav_array_memcpy(packet.temperature, temperature, sizeof(uint8_t)*4);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8, (const char *)&packet, MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8_MIN_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8_CRC);
#endif
}
/**
* @brief Send a esc_telemetry_5_to_8 message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_esc_telemetry_5_to_8_send_struct(mavlink_channel_t chan, const mavlink_esc_telemetry_5_to_8_t* esc_telemetry_5_to_8)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_esc_telemetry_5_to_8_send(chan, esc_telemetry_5_to_8->temperature, esc_telemetry_5_to_8->voltage, esc_telemetry_5_to_8->current, esc_telemetry_5_to_8->totalcurrent, esc_telemetry_5_to_8->rpm, esc_telemetry_5_to_8->count);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8, (const char *)esc_telemetry_5_to_8, MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8_MIN_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8_CRC);
#endif
}
#if MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_esc_telemetry_5_to_8_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, const uint8_t *temperature, const uint16_t *voltage, const uint16_t *current, const uint16_t *totalcurrent, const uint16_t *rpm, const uint16_t *count)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint16_t_array(buf, 0, voltage, 4);
_mav_put_uint16_t_array(buf, 8, current, 4);
_mav_put_uint16_t_array(buf, 16, totalcurrent, 4);
_mav_put_uint16_t_array(buf, 24, rpm, 4);
_mav_put_uint16_t_array(buf, 32, count, 4);
_mav_put_uint8_t_array(buf, 40, temperature, 4);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8, buf, MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8_MIN_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8_CRC);
#else
mavlink_esc_telemetry_5_to_8_t *packet = (mavlink_esc_telemetry_5_to_8_t *)msgbuf;
mav_array_memcpy(packet->voltage, voltage, sizeof(uint16_t)*4);
mav_array_memcpy(packet->current, current, sizeof(uint16_t)*4);
mav_array_memcpy(packet->totalcurrent, totalcurrent, sizeof(uint16_t)*4);
mav_array_memcpy(packet->rpm, rpm, sizeof(uint16_t)*4);
mav_array_memcpy(packet->count, count, sizeof(uint16_t)*4);
mav_array_memcpy(packet->temperature, temperature, sizeof(uint8_t)*4);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8, (const char *)packet, MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8_MIN_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8_CRC);
#endif
}
#endif
#endif
// MESSAGE ESC_TELEMETRY_5_TO_8 UNPACKING
/**
* @brief Get field temperature from esc_telemetry_5_to_8 message
*
* @return [degC] Temperature
*/
static inline uint16_t mavlink_msg_esc_telemetry_5_to_8_get_temperature(const mavlink_message_t* msg, uint8_t *temperature)
{
return _MAV_RETURN_uint8_t_array(msg, temperature, 4, 40);
}
/**
* @brief Get field voltage from esc_telemetry_5_to_8 message
*
* @return [cV] Voltage
*/
static inline uint16_t mavlink_msg_esc_telemetry_5_to_8_get_voltage(const mavlink_message_t* msg, uint16_t *voltage)
{
return _MAV_RETURN_uint16_t_array(msg, voltage, 4, 0);
}
/**
* @brief Get field current from esc_telemetry_5_to_8 message
*
* @return [cA] Current
*/
static inline uint16_t mavlink_msg_esc_telemetry_5_to_8_get_current(const mavlink_message_t* msg, uint16_t *current)
{
return _MAV_RETURN_uint16_t_array(msg, current, 4, 8);
}
/**
* @brief Get field totalcurrent from esc_telemetry_5_to_8 message
*
* @return [mAh] Total current
*/
static inline uint16_t mavlink_msg_esc_telemetry_5_to_8_get_totalcurrent(const mavlink_message_t* msg, uint16_t *totalcurrent)
{
return _MAV_RETURN_uint16_t_array(msg, totalcurrent, 4, 16);
}
/**
* @brief Get field rpm from esc_telemetry_5_to_8 message
*
* @return [rpm] RPM (eRPM)
*/
static inline uint16_t mavlink_msg_esc_telemetry_5_to_8_get_rpm(const mavlink_message_t* msg, uint16_t *rpm)
{
return _MAV_RETURN_uint16_t_array(msg, rpm, 4, 24);
}
/**
* @brief Get field count from esc_telemetry_5_to_8 message
*
* @return count of telemetry packets received (wraps at 65535)
*/
static inline uint16_t mavlink_msg_esc_telemetry_5_to_8_get_count(const mavlink_message_t* msg, uint16_t *count)
{
return _MAV_RETURN_uint16_t_array(msg, count, 4, 32);
}
/**
* @brief Decode a esc_telemetry_5_to_8 message into a struct
*
* @param msg The message to decode
* @param esc_telemetry_5_to_8 C-struct to decode the message contents into
*/
static inline void mavlink_msg_esc_telemetry_5_to_8_decode(const mavlink_message_t* msg, mavlink_esc_telemetry_5_to_8_t* esc_telemetry_5_to_8)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_esc_telemetry_5_to_8_get_voltage(msg, esc_telemetry_5_to_8->voltage);
mavlink_msg_esc_telemetry_5_to_8_get_current(msg, esc_telemetry_5_to_8->current);
mavlink_msg_esc_telemetry_5_to_8_get_totalcurrent(msg, esc_telemetry_5_to_8->totalcurrent);
mavlink_msg_esc_telemetry_5_to_8_get_rpm(msg, esc_telemetry_5_to_8->rpm);
mavlink_msg_esc_telemetry_5_to_8_get_count(msg, esc_telemetry_5_to_8->count);
mavlink_msg_esc_telemetry_5_to_8_get_temperature(msg, esc_telemetry_5_to_8->temperature);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8_LEN? msg->len : MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8_LEN;
memset(esc_telemetry_5_to_8, 0, MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8_LEN);
memcpy(esc_telemetry_5_to_8, _MAV_PAYLOAD(msg), len);
#endif
}

View File

@@ -0,0 +1,343 @@
#pragma once
// MESSAGE ESC_TELEMETRY_9_TO_12 PACKING
#define MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12 11032
MAVPACKED(
typedef struct __mavlink_esc_telemetry_9_to_12_t {
uint16_t voltage[4]; /*< [cV] Voltage*/
uint16_t current[4]; /*< [cA] Current*/
uint16_t totalcurrent[4]; /*< [mAh] Total current*/
uint16_t rpm[4]; /*< [rpm] RPM (eRPM)*/
uint16_t count[4]; /*< count of telemetry packets received (wraps at 65535)*/
uint8_t temperature[4]; /*< [degC] Temperature*/
}) mavlink_esc_telemetry_9_to_12_t;
#define MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12_LEN 44
#define MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12_MIN_LEN 44
#define MAVLINK_MSG_ID_11032_LEN 44
#define MAVLINK_MSG_ID_11032_MIN_LEN 44
#define MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12_CRC 85
#define MAVLINK_MSG_ID_11032_CRC 85
#define MAVLINK_MSG_ESC_TELEMETRY_9_TO_12_FIELD_VOLTAGE_LEN 4
#define MAVLINK_MSG_ESC_TELEMETRY_9_TO_12_FIELD_CURRENT_LEN 4
#define MAVLINK_MSG_ESC_TELEMETRY_9_TO_12_FIELD_TOTALCURRENT_LEN 4
#define MAVLINK_MSG_ESC_TELEMETRY_9_TO_12_FIELD_RPM_LEN 4
#define MAVLINK_MSG_ESC_TELEMETRY_9_TO_12_FIELD_COUNT_LEN 4
#define MAVLINK_MSG_ESC_TELEMETRY_9_TO_12_FIELD_TEMPERATURE_LEN 4
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_ESC_TELEMETRY_9_TO_12 { \
11032, \
"ESC_TELEMETRY_9_TO_12", \
6, \
{ { "temperature", NULL, MAVLINK_TYPE_UINT8_T, 4, 40, offsetof(mavlink_esc_telemetry_9_to_12_t, temperature) }, \
{ "voltage", NULL, MAVLINK_TYPE_UINT16_T, 4, 0, offsetof(mavlink_esc_telemetry_9_to_12_t, voltage) }, \
{ "current", NULL, MAVLINK_TYPE_UINT16_T, 4, 8, offsetof(mavlink_esc_telemetry_9_to_12_t, current) }, \
{ "totalcurrent", NULL, MAVLINK_TYPE_UINT16_T, 4, 16, offsetof(mavlink_esc_telemetry_9_to_12_t, totalcurrent) }, \
{ "rpm", NULL, MAVLINK_TYPE_UINT16_T, 4, 24, offsetof(mavlink_esc_telemetry_9_to_12_t, rpm) }, \
{ "count", NULL, MAVLINK_TYPE_UINT16_T, 4, 32, offsetof(mavlink_esc_telemetry_9_to_12_t, count) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_ESC_TELEMETRY_9_TO_12 { \
"ESC_TELEMETRY_9_TO_12", \
6, \
{ { "temperature", NULL, MAVLINK_TYPE_UINT8_T, 4, 40, offsetof(mavlink_esc_telemetry_9_to_12_t, temperature) }, \
{ "voltage", NULL, MAVLINK_TYPE_UINT16_T, 4, 0, offsetof(mavlink_esc_telemetry_9_to_12_t, voltage) }, \
{ "current", NULL, MAVLINK_TYPE_UINT16_T, 4, 8, offsetof(mavlink_esc_telemetry_9_to_12_t, current) }, \
{ "totalcurrent", NULL, MAVLINK_TYPE_UINT16_T, 4, 16, offsetof(mavlink_esc_telemetry_9_to_12_t, totalcurrent) }, \
{ "rpm", NULL, MAVLINK_TYPE_UINT16_T, 4, 24, offsetof(mavlink_esc_telemetry_9_to_12_t, rpm) }, \
{ "count", NULL, MAVLINK_TYPE_UINT16_T, 4, 32, offsetof(mavlink_esc_telemetry_9_to_12_t, count) }, \
} \
}
#endif
/**
* @brief Pack a esc_telemetry_9_to_12 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 temperature [degC] Temperature
* @param voltage [cV] Voltage
* @param current [cA] Current
* @param totalcurrent [mAh] Total current
* @param rpm [rpm] RPM (eRPM)
* @param count count of telemetry packets received (wraps at 65535)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_esc_telemetry_9_to_12_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
const uint8_t *temperature, const uint16_t *voltage, const uint16_t *current, const uint16_t *totalcurrent, const uint16_t *rpm, const uint16_t *count)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12_LEN];
_mav_put_uint16_t_array(buf, 0, voltage, 4);
_mav_put_uint16_t_array(buf, 8, current, 4);
_mav_put_uint16_t_array(buf, 16, totalcurrent, 4);
_mav_put_uint16_t_array(buf, 24, rpm, 4);
_mav_put_uint16_t_array(buf, 32, count, 4);
_mav_put_uint8_t_array(buf, 40, temperature, 4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12_LEN);
#else
mavlink_esc_telemetry_9_to_12_t packet;
mav_array_memcpy(packet.voltage, voltage, sizeof(uint16_t)*4);
mav_array_memcpy(packet.current, current, sizeof(uint16_t)*4);
mav_array_memcpy(packet.totalcurrent, totalcurrent, sizeof(uint16_t)*4);
mav_array_memcpy(packet.rpm, rpm, sizeof(uint16_t)*4);
mav_array_memcpy(packet.count, count, sizeof(uint16_t)*4);
mav_array_memcpy(packet.temperature, temperature, sizeof(uint8_t)*4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12_MIN_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12_CRC);
}
/**
* @brief Pack a esc_telemetry_9_to_12 message on a channel
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param temperature [degC] Temperature
* @param voltage [cV] Voltage
* @param current [cA] Current
* @param totalcurrent [mAh] Total current
* @param rpm [rpm] RPM (eRPM)
* @param count count of telemetry packets received (wraps at 65535)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_esc_telemetry_9_to_12_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
const uint8_t *temperature,const uint16_t *voltage,const uint16_t *current,const uint16_t *totalcurrent,const uint16_t *rpm,const uint16_t *count)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12_LEN];
_mav_put_uint16_t_array(buf, 0, voltage, 4);
_mav_put_uint16_t_array(buf, 8, current, 4);
_mav_put_uint16_t_array(buf, 16, totalcurrent, 4);
_mav_put_uint16_t_array(buf, 24, rpm, 4);
_mav_put_uint16_t_array(buf, 32, count, 4);
_mav_put_uint8_t_array(buf, 40, temperature, 4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12_LEN);
#else
mavlink_esc_telemetry_9_to_12_t packet;
mav_array_memcpy(packet.voltage, voltage, sizeof(uint16_t)*4);
mav_array_memcpy(packet.current, current, sizeof(uint16_t)*4);
mav_array_memcpy(packet.totalcurrent, totalcurrent, sizeof(uint16_t)*4);
mav_array_memcpy(packet.rpm, rpm, sizeof(uint16_t)*4);
mav_array_memcpy(packet.count, count, sizeof(uint16_t)*4);
mav_array_memcpy(packet.temperature, temperature, sizeof(uint8_t)*4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12_MIN_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12_CRC);
}
/**
* @brief Encode a esc_telemetry_9_to_12 struct
*
* @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 esc_telemetry_9_to_12 C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_esc_telemetry_9_to_12_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_esc_telemetry_9_to_12_t* esc_telemetry_9_to_12)
{
return mavlink_msg_esc_telemetry_9_to_12_pack(system_id, component_id, msg, esc_telemetry_9_to_12->temperature, esc_telemetry_9_to_12->voltage, esc_telemetry_9_to_12->current, esc_telemetry_9_to_12->totalcurrent, esc_telemetry_9_to_12->rpm, esc_telemetry_9_to_12->count);
}
/**
* @brief Encode a esc_telemetry_9_to_12 struct on a channel
*
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param esc_telemetry_9_to_12 C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_esc_telemetry_9_to_12_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_esc_telemetry_9_to_12_t* esc_telemetry_9_to_12)
{
return mavlink_msg_esc_telemetry_9_to_12_pack_chan(system_id, component_id, chan, msg, esc_telemetry_9_to_12->temperature, esc_telemetry_9_to_12->voltage, esc_telemetry_9_to_12->current, esc_telemetry_9_to_12->totalcurrent, esc_telemetry_9_to_12->rpm, esc_telemetry_9_to_12->count);
}
/**
* @brief Send a esc_telemetry_9_to_12 message
* @param chan MAVLink channel to send the message
*
* @param temperature [degC] Temperature
* @param voltage [cV] Voltage
* @param current [cA] Current
* @param totalcurrent [mAh] Total current
* @param rpm [rpm] RPM (eRPM)
* @param count count of telemetry packets received (wraps at 65535)
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_esc_telemetry_9_to_12_send(mavlink_channel_t chan, const uint8_t *temperature, const uint16_t *voltage, const uint16_t *current, const uint16_t *totalcurrent, const uint16_t *rpm, const uint16_t *count)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12_LEN];
_mav_put_uint16_t_array(buf, 0, voltage, 4);
_mav_put_uint16_t_array(buf, 8, current, 4);
_mav_put_uint16_t_array(buf, 16, totalcurrent, 4);
_mav_put_uint16_t_array(buf, 24, rpm, 4);
_mav_put_uint16_t_array(buf, 32, count, 4);
_mav_put_uint8_t_array(buf, 40, temperature, 4);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12, buf, MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12_MIN_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12_CRC);
#else
mavlink_esc_telemetry_9_to_12_t packet;
mav_array_memcpy(packet.voltage, voltage, sizeof(uint16_t)*4);
mav_array_memcpy(packet.current, current, sizeof(uint16_t)*4);
mav_array_memcpy(packet.totalcurrent, totalcurrent, sizeof(uint16_t)*4);
mav_array_memcpy(packet.rpm, rpm, sizeof(uint16_t)*4);
mav_array_memcpy(packet.count, count, sizeof(uint16_t)*4);
mav_array_memcpy(packet.temperature, temperature, sizeof(uint8_t)*4);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12, (const char *)&packet, MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12_MIN_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12_CRC);
#endif
}
/**
* @brief Send a esc_telemetry_9_to_12 message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_esc_telemetry_9_to_12_send_struct(mavlink_channel_t chan, const mavlink_esc_telemetry_9_to_12_t* esc_telemetry_9_to_12)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_esc_telemetry_9_to_12_send(chan, esc_telemetry_9_to_12->temperature, esc_telemetry_9_to_12->voltage, esc_telemetry_9_to_12->current, esc_telemetry_9_to_12->totalcurrent, esc_telemetry_9_to_12->rpm, esc_telemetry_9_to_12->count);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12, (const char *)esc_telemetry_9_to_12, MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12_MIN_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12_CRC);
#endif
}
#if MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_esc_telemetry_9_to_12_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, const uint8_t *temperature, const uint16_t *voltage, const uint16_t *current, const uint16_t *totalcurrent, const uint16_t *rpm, const uint16_t *count)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint16_t_array(buf, 0, voltage, 4);
_mav_put_uint16_t_array(buf, 8, current, 4);
_mav_put_uint16_t_array(buf, 16, totalcurrent, 4);
_mav_put_uint16_t_array(buf, 24, rpm, 4);
_mav_put_uint16_t_array(buf, 32, count, 4);
_mav_put_uint8_t_array(buf, 40, temperature, 4);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12, buf, MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12_MIN_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12_CRC);
#else
mavlink_esc_telemetry_9_to_12_t *packet = (mavlink_esc_telemetry_9_to_12_t *)msgbuf;
mav_array_memcpy(packet->voltage, voltage, sizeof(uint16_t)*4);
mav_array_memcpy(packet->current, current, sizeof(uint16_t)*4);
mav_array_memcpy(packet->totalcurrent, totalcurrent, sizeof(uint16_t)*4);
mav_array_memcpy(packet->rpm, rpm, sizeof(uint16_t)*4);
mav_array_memcpy(packet->count, count, sizeof(uint16_t)*4);
mav_array_memcpy(packet->temperature, temperature, sizeof(uint8_t)*4);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12, (const char *)packet, MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12_MIN_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12_CRC);
#endif
}
#endif
#endif
// MESSAGE ESC_TELEMETRY_9_TO_12 UNPACKING
/**
* @brief Get field temperature from esc_telemetry_9_to_12 message
*
* @return [degC] Temperature
*/
static inline uint16_t mavlink_msg_esc_telemetry_9_to_12_get_temperature(const mavlink_message_t* msg, uint8_t *temperature)
{
return _MAV_RETURN_uint8_t_array(msg, temperature, 4, 40);
}
/**
* @brief Get field voltage from esc_telemetry_9_to_12 message
*
* @return [cV] Voltage
*/
static inline uint16_t mavlink_msg_esc_telemetry_9_to_12_get_voltage(const mavlink_message_t* msg, uint16_t *voltage)
{
return _MAV_RETURN_uint16_t_array(msg, voltage, 4, 0);
}
/**
* @brief Get field current from esc_telemetry_9_to_12 message
*
* @return [cA] Current
*/
static inline uint16_t mavlink_msg_esc_telemetry_9_to_12_get_current(const mavlink_message_t* msg, uint16_t *current)
{
return _MAV_RETURN_uint16_t_array(msg, current, 4, 8);
}
/**
* @brief Get field totalcurrent from esc_telemetry_9_to_12 message
*
* @return [mAh] Total current
*/
static inline uint16_t mavlink_msg_esc_telemetry_9_to_12_get_totalcurrent(const mavlink_message_t* msg, uint16_t *totalcurrent)
{
return _MAV_RETURN_uint16_t_array(msg, totalcurrent, 4, 16);
}
/**
* @brief Get field rpm from esc_telemetry_9_to_12 message
*
* @return [rpm] RPM (eRPM)
*/
static inline uint16_t mavlink_msg_esc_telemetry_9_to_12_get_rpm(const mavlink_message_t* msg, uint16_t *rpm)
{
return _MAV_RETURN_uint16_t_array(msg, rpm, 4, 24);
}
/**
* @brief Get field count from esc_telemetry_9_to_12 message
*
* @return count of telemetry packets received (wraps at 65535)
*/
static inline uint16_t mavlink_msg_esc_telemetry_9_to_12_get_count(const mavlink_message_t* msg, uint16_t *count)
{
return _MAV_RETURN_uint16_t_array(msg, count, 4, 32);
}
/**
* @brief Decode a esc_telemetry_9_to_12 message into a struct
*
* @param msg The message to decode
* @param esc_telemetry_9_to_12 C-struct to decode the message contents into
*/
static inline void mavlink_msg_esc_telemetry_9_to_12_decode(const mavlink_message_t* msg, mavlink_esc_telemetry_9_to_12_t* esc_telemetry_9_to_12)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_esc_telemetry_9_to_12_get_voltage(msg, esc_telemetry_9_to_12->voltage);
mavlink_msg_esc_telemetry_9_to_12_get_current(msg, esc_telemetry_9_to_12->current);
mavlink_msg_esc_telemetry_9_to_12_get_totalcurrent(msg, esc_telemetry_9_to_12->totalcurrent);
mavlink_msg_esc_telemetry_9_to_12_get_rpm(msg, esc_telemetry_9_to_12->rpm);
mavlink_msg_esc_telemetry_9_to_12_get_count(msg, esc_telemetry_9_to_12->count);
mavlink_msg_esc_telemetry_9_to_12_get_temperature(msg, esc_telemetry_9_to_12->temperature);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12_LEN? msg->len : MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12_LEN;
memset(esc_telemetry_9_to_12, 0, MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12_LEN);
memcpy(esc_telemetry_9_to_12, _MAV_PAYLOAD(msg), len);
#endif
}

View File

@@ -0,0 +1,263 @@
#pragma once
// MESSAGE FENCE_FETCH_POINT PACKING
#define MAVLINK_MSG_ID_FENCE_FETCH_POINT 161
MAVPACKED(
typedef struct __mavlink_fence_fetch_point_t {
uint8_t target_system; /*< System ID.*/
uint8_t target_component; /*< Component ID.*/
uint8_t idx; /*< Point index (first point is 1, 0 is for return point).*/
}) mavlink_fence_fetch_point_t;
#define MAVLINK_MSG_ID_FENCE_FETCH_POINT_LEN 3
#define MAVLINK_MSG_ID_FENCE_FETCH_POINT_MIN_LEN 3
#define MAVLINK_MSG_ID_161_LEN 3
#define MAVLINK_MSG_ID_161_MIN_LEN 3
#define MAVLINK_MSG_ID_FENCE_FETCH_POINT_CRC 68
#define MAVLINK_MSG_ID_161_CRC 68
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_FENCE_FETCH_POINT { \
161, \
"FENCE_FETCH_POINT", \
3, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_fence_fetch_point_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_fence_fetch_point_t, target_component) }, \
{ "idx", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_fence_fetch_point_t, idx) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_FENCE_FETCH_POINT { \
"FENCE_FETCH_POINT", \
3, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_fence_fetch_point_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_fence_fetch_point_t, target_component) }, \
{ "idx", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_fence_fetch_point_t, idx) }, \
} \
}
#endif
/**
* @brief Pack a fence_fetch_point 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.
* @param idx Point index (first point is 1, 0 is for return point).
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_fence_fetch_point_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, uint8_t idx)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_FENCE_FETCH_POINT_LEN];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint8_t(buf, 2, idx);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FENCE_FETCH_POINT_LEN);
#else
mavlink_fence_fetch_point_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.idx = idx;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FENCE_FETCH_POINT_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_FENCE_FETCH_POINT;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FENCE_FETCH_POINT_MIN_LEN, MAVLINK_MSG_ID_FENCE_FETCH_POINT_LEN, MAVLINK_MSG_ID_FENCE_FETCH_POINT_CRC);
}
/**
* @brief Pack a fence_fetch_point message on a channel
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID.
* @param target_component Component ID.
* @param idx Point index (first point is 1, 0 is for return point).
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_fence_fetch_point_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 idx)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_FENCE_FETCH_POINT_LEN];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint8_t(buf, 2, idx);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FENCE_FETCH_POINT_LEN);
#else
mavlink_fence_fetch_point_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.idx = idx;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FENCE_FETCH_POINT_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_FENCE_FETCH_POINT;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FENCE_FETCH_POINT_MIN_LEN, MAVLINK_MSG_ID_FENCE_FETCH_POINT_LEN, MAVLINK_MSG_ID_FENCE_FETCH_POINT_CRC);
}
/**
* @brief Encode a fence_fetch_point struct
*
* @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 fence_fetch_point C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_fence_fetch_point_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_fence_fetch_point_t* fence_fetch_point)
{
return mavlink_msg_fence_fetch_point_pack(system_id, component_id, msg, fence_fetch_point->target_system, fence_fetch_point->target_component, fence_fetch_point->idx);
}
/**
* @brief Encode a fence_fetch_point struct on a channel
*
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param fence_fetch_point C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_fence_fetch_point_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_fence_fetch_point_t* fence_fetch_point)
{
return mavlink_msg_fence_fetch_point_pack_chan(system_id, component_id, chan, msg, fence_fetch_point->target_system, fence_fetch_point->target_component, fence_fetch_point->idx);
}
/**
* @brief Send a fence_fetch_point message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID.
* @param target_component Component ID.
* @param idx Point index (first point is 1, 0 is for return point).
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_fence_fetch_point_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t idx)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_FENCE_FETCH_POINT_LEN];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint8_t(buf, 2, idx);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_FETCH_POINT, buf, MAVLINK_MSG_ID_FENCE_FETCH_POINT_MIN_LEN, MAVLINK_MSG_ID_FENCE_FETCH_POINT_LEN, MAVLINK_MSG_ID_FENCE_FETCH_POINT_CRC);
#else
mavlink_fence_fetch_point_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.idx = idx;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_FETCH_POINT, (const char *)&packet, MAVLINK_MSG_ID_FENCE_FETCH_POINT_MIN_LEN, MAVLINK_MSG_ID_FENCE_FETCH_POINT_LEN, MAVLINK_MSG_ID_FENCE_FETCH_POINT_CRC);
#endif
}
/**
* @brief Send a fence_fetch_point message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_fence_fetch_point_send_struct(mavlink_channel_t chan, const mavlink_fence_fetch_point_t* fence_fetch_point)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_fence_fetch_point_send(chan, fence_fetch_point->target_system, fence_fetch_point->target_component, fence_fetch_point->idx);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_FETCH_POINT, (const char *)fence_fetch_point, MAVLINK_MSG_ID_FENCE_FETCH_POINT_MIN_LEN, MAVLINK_MSG_ID_FENCE_FETCH_POINT_LEN, MAVLINK_MSG_ID_FENCE_FETCH_POINT_CRC);
#endif
}
#if MAVLINK_MSG_ID_FENCE_FETCH_POINT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_fence_fetch_point_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t idx)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint8_t(buf, 2, idx);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_FETCH_POINT, buf, MAVLINK_MSG_ID_FENCE_FETCH_POINT_MIN_LEN, MAVLINK_MSG_ID_FENCE_FETCH_POINT_LEN, MAVLINK_MSG_ID_FENCE_FETCH_POINT_CRC);
#else
mavlink_fence_fetch_point_t *packet = (mavlink_fence_fetch_point_t *)msgbuf;
packet->target_system = target_system;
packet->target_component = target_component;
packet->idx = idx;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_FETCH_POINT, (const char *)packet, MAVLINK_MSG_ID_FENCE_FETCH_POINT_MIN_LEN, MAVLINK_MSG_ID_FENCE_FETCH_POINT_LEN, MAVLINK_MSG_ID_FENCE_FETCH_POINT_CRC);
#endif
}
#endif
#endif
// MESSAGE FENCE_FETCH_POINT UNPACKING
/**
* @brief Get field target_system from fence_fetch_point message
*
* @return System ID.
*/
static inline uint8_t mavlink_msg_fence_fetch_point_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 0);
}
/**
* @brief Get field target_component from fence_fetch_point message
*
* @return Component ID.
*/
static inline uint8_t mavlink_msg_fence_fetch_point_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 1);
}
/**
* @brief Get field idx from fence_fetch_point message
*
* @return Point index (first point is 1, 0 is for return point).
*/
static inline uint8_t mavlink_msg_fence_fetch_point_get_idx(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 2);
}
/**
* @brief Decode a fence_fetch_point message into a struct
*
* @param msg The message to decode
* @param fence_fetch_point C-struct to decode the message contents into
*/
static inline void mavlink_msg_fence_fetch_point_decode(const mavlink_message_t* msg, mavlink_fence_fetch_point_t* fence_fetch_point)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
fence_fetch_point->target_system = mavlink_msg_fence_fetch_point_get_target_system(msg);
fence_fetch_point->target_component = mavlink_msg_fence_fetch_point_get_target_component(msg);
fence_fetch_point->idx = mavlink_msg_fence_fetch_point_get_idx(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_FENCE_FETCH_POINT_LEN? msg->len : MAVLINK_MSG_ID_FENCE_FETCH_POINT_LEN;
memset(fence_fetch_point, 0, MAVLINK_MSG_ID_FENCE_FETCH_POINT_LEN);
memcpy(fence_fetch_point, _MAV_PAYLOAD(msg), len);
#endif
}

View File

@@ -0,0 +1,338 @@
#pragma once
// MESSAGE FENCE_POINT PACKING
#define MAVLINK_MSG_ID_FENCE_POINT 160
MAVPACKED(
typedef struct __mavlink_fence_point_t {
float lat; /*< [deg] Latitude of point.*/
float lng; /*< [deg] Longitude of point.*/
uint8_t target_system; /*< System ID.*/
uint8_t target_component; /*< Component ID.*/
uint8_t idx; /*< Point index (first point is 1, 0 is for return point).*/
uint8_t count; /*< Total number of points (for sanity checking).*/
}) mavlink_fence_point_t;
#define MAVLINK_MSG_ID_FENCE_POINT_LEN 12
#define MAVLINK_MSG_ID_FENCE_POINT_MIN_LEN 12
#define MAVLINK_MSG_ID_160_LEN 12
#define MAVLINK_MSG_ID_160_MIN_LEN 12
#define MAVLINK_MSG_ID_FENCE_POINT_CRC 78
#define MAVLINK_MSG_ID_160_CRC 78
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_FENCE_POINT { \
160, \
"FENCE_POINT", \
6, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_fence_point_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_fence_point_t, target_component) }, \
{ "idx", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_fence_point_t, idx) }, \
{ "count", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_fence_point_t, count) }, \
{ "lat", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_fence_point_t, lat) }, \
{ "lng", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_fence_point_t, lng) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_FENCE_POINT { \
"FENCE_POINT", \
6, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_fence_point_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_fence_point_t, target_component) }, \
{ "idx", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_fence_point_t, idx) }, \
{ "count", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_fence_point_t, count) }, \
{ "lat", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_fence_point_t, lat) }, \
{ "lng", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_fence_point_t, lng) }, \
} \
}
#endif
/**
* @brief Pack a fence_point 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.
* @param idx Point index (first point is 1, 0 is for return point).
* @param count Total number of points (for sanity checking).
* @param lat [deg] Latitude of point.
* @param lng [deg] Longitude of point.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_fence_point_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, uint8_t idx, uint8_t count, float lat, float lng)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_FENCE_POINT_LEN];
_mav_put_float(buf, 0, lat);
_mav_put_float(buf, 4, lng);
_mav_put_uint8_t(buf, 8, target_system);
_mav_put_uint8_t(buf, 9, target_component);
_mav_put_uint8_t(buf, 10, idx);
_mav_put_uint8_t(buf, 11, count);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FENCE_POINT_LEN);
#else
mavlink_fence_point_t packet;
packet.lat = lat;
packet.lng = lng;
packet.target_system = target_system;
packet.target_component = target_component;
packet.idx = idx;
packet.count = count;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FENCE_POINT_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_FENCE_POINT;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FENCE_POINT_MIN_LEN, MAVLINK_MSG_ID_FENCE_POINT_LEN, MAVLINK_MSG_ID_FENCE_POINT_CRC);
}
/**
* @brief Pack a fence_point message on a channel
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID.
* @param target_component Component ID.
* @param idx Point index (first point is 1, 0 is for return point).
* @param count Total number of points (for sanity checking).
* @param lat [deg] Latitude of point.
* @param lng [deg] Longitude of point.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_fence_point_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 idx,uint8_t count,float lat,float lng)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_FENCE_POINT_LEN];
_mav_put_float(buf, 0, lat);
_mav_put_float(buf, 4, lng);
_mav_put_uint8_t(buf, 8, target_system);
_mav_put_uint8_t(buf, 9, target_component);
_mav_put_uint8_t(buf, 10, idx);
_mav_put_uint8_t(buf, 11, count);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FENCE_POINT_LEN);
#else
mavlink_fence_point_t packet;
packet.lat = lat;
packet.lng = lng;
packet.target_system = target_system;
packet.target_component = target_component;
packet.idx = idx;
packet.count = count;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FENCE_POINT_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_FENCE_POINT;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FENCE_POINT_MIN_LEN, MAVLINK_MSG_ID_FENCE_POINT_LEN, MAVLINK_MSG_ID_FENCE_POINT_CRC);
}
/**
* @brief Encode a fence_point struct
*
* @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 fence_point C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_fence_point_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_fence_point_t* fence_point)
{
return mavlink_msg_fence_point_pack(system_id, component_id, msg, fence_point->target_system, fence_point->target_component, fence_point->idx, fence_point->count, fence_point->lat, fence_point->lng);
}
/**
* @brief Encode a fence_point struct on a channel
*
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param fence_point C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_fence_point_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_fence_point_t* fence_point)
{
return mavlink_msg_fence_point_pack_chan(system_id, component_id, chan, msg, fence_point->target_system, fence_point->target_component, fence_point->idx, fence_point->count, fence_point->lat, fence_point->lng);
}
/**
* @brief Send a fence_point message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID.
* @param target_component Component ID.
* @param idx Point index (first point is 1, 0 is for return point).
* @param count Total number of points (for sanity checking).
* @param lat [deg] Latitude of point.
* @param lng [deg] Longitude of point.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_fence_point_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t idx, uint8_t count, float lat, float lng)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_FENCE_POINT_LEN];
_mav_put_float(buf, 0, lat);
_mav_put_float(buf, 4, lng);
_mav_put_uint8_t(buf, 8, target_system);
_mav_put_uint8_t(buf, 9, target_component);
_mav_put_uint8_t(buf, 10, idx);
_mav_put_uint8_t(buf, 11, count);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_POINT, buf, MAVLINK_MSG_ID_FENCE_POINT_MIN_LEN, MAVLINK_MSG_ID_FENCE_POINT_LEN, MAVLINK_MSG_ID_FENCE_POINT_CRC);
#else
mavlink_fence_point_t packet;
packet.lat = lat;
packet.lng = lng;
packet.target_system = target_system;
packet.target_component = target_component;
packet.idx = idx;
packet.count = count;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_POINT, (const char *)&packet, MAVLINK_MSG_ID_FENCE_POINT_MIN_LEN, MAVLINK_MSG_ID_FENCE_POINT_LEN, MAVLINK_MSG_ID_FENCE_POINT_CRC);
#endif
}
/**
* @brief Send a fence_point message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_fence_point_send_struct(mavlink_channel_t chan, const mavlink_fence_point_t* fence_point)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_fence_point_send(chan, fence_point->target_system, fence_point->target_component, fence_point->idx, fence_point->count, fence_point->lat, fence_point->lng);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_POINT, (const char *)fence_point, MAVLINK_MSG_ID_FENCE_POINT_MIN_LEN, MAVLINK_MSG_ID_FENCE_POINT_LEN, MAVLINK_MSG_ID_FENCE_POINT_CRC);
#endif
}
#if MAVLINK_MSG_ID_FENCE_POINT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_fence_point_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t idx, uint8_t count, float lat, float lng)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_float(buf, 0, lat);
_mav_put_float(buf, 4, lng);
_mav_put_uint8_t(buf, 8, target_system);
_mav_put_uint8_t(buf, 9, target_component);
_mav_put_uint8_t(buf, 10, idx);
_mav_put_uint8_t(buf, 11, count);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_POINT, buf, MAVLINK_MSG_ID_FENCE_POINT_MIN_LEN, MAVLINK_MSG_ID_FENCE_POINT_LEN, MAVLINK_MSG_ID_FENCE_POINT_CRC);
#else
mavlink_fence_point_t *packet = (mavlink_fence_point_t *)msgbuf;
packet->lat = lat;
packet->lng = lng;
packet->target_system = target_system;
packet->target_component = target_component;
packet->idx = idx;
packet->count = count;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_POINT, (const char *)packet, MAVLINK_MSG_ID_FENCE_POINT_MIN_LEN, MAVLINK_MSG_ID_FENCE_POINT_LEN, MAVLINK_MSG_ID_FENCE_POINT_CRC);
#endif
}
#endif
#endif
// MESSAGE FENCE_POINT UNPACKING
/**
* @brief Get field target_system from fence_point message
*
* @return System ID.
*/
static inline uint8_t mavlink_msg_fence_point_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 8);
}
/**
* @brief Get field target_component from fence_point message
*
* @return Component ID.
*/
static inline uint8_t mavlink_msg_fence_point_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 9);
}
/**
* @brief Get field idx from fence_point message
*
* @return Point index (first point is 1, 0 is for return point).
*/
static inline uint8_t mavlink_msg_fence_point_get_idx(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 10);
}
/**
* @brief Get field count from fence_point message
*
* @return Total number of points (for sanity checking).
*/
static inline uint8_t mavlink_msg_fence_point_get_count(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 11);
}
/**
* @brief Get field lat from fence_point message
*
* @return [deg] Latitude of point.
*/
static inline float mavlink_msg_fence_point_get_lat(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 0);
}
/**
* @brief Get field lng from fence_point message
*
* @return [deg] Longitude of point.
*/
static inline float mavlink_msg_fence_point_get_lng(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 4);
}
/**
* @brief Decode a fence_point message into a struct
*
* @param msg The message to decode
* @param fence_point C-struct to decode the message contents into
*/
static inline void mavlink_msg_fence_point_decode(const mavlink_message_t* msg, mavlink_fence_point_t* fence_point)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
fence_point->lat = mavlink_msg_fence_point_get_lat(msg);
fence_point->lng = mavlink_msg_fence_point_get_lng(msg);
fence_point->target_system = mavlink_msg_fence_point_get_target_system(msg);
fence_point->target_component = mavlink_msg_fence_point_get_target_component(msg);
fence_point->idx = mavlink_msg_fence_point_get_idx(msg);
fence_point->count = mavlink_msg_fence_point_get_count(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_FENCE_POINT_LEN? msg->len : MAVLINK_MSG_ID_FENCE_POINT_LEN;
memset(fence_point, 0, MAVLINK_MSG_ID_FENCE_POINT_LEN);
memcpy(fence_point, _MAV_PAYLOAD(msg), len);
#endif
}

View File

@@ -0,0 +1,288 @@
#pragma once
// MESSAGE FENCE_STATUS PACKING
#define MAVLINK_MSG_ID_FENCE_STATUS 162
MAVPACKED(
typedef struct __mavlink_fence_status_t {
uint32_t breach_time; /*< [ms] Time (since boot) of last breach.*/
uint16_t breach_count; /*< Number of fence breaches.*/
uint8_t breach_status; /*< Breach status (0 if currently inside fence, 1 if outside).*/
uint8_t breach_type; /*< Last breach type.*/
}) mavlink_fence_status_t;
#define MAVLINK_MSG_ID_FENCE_STATUS_LEN 8
#define MAVLINK_MSG_ID_FENCE_STATUS_MIN_LEN 8
#define MAVLINK_MSG_ID_162_LEN 8
#define MAVLINK_MSG_ID_162_MIN_LEN 8
#define MAVLINK_MSG_ID_FENCE_STATUS_CRC 189
#define MAVLINK_MSG_ID_162_CRC 189
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_FENCE_STATUS { \
162, \
"FENCE_STATUS", \
4, \
{ { "breach_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_fence_status_t, breach_status) }, \
{ "breach_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_fence_status_t, breach_count) }, \
{ "breach_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_fence_status_t, breach_type) }, \
{ "breach_time", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_fence_status_t, breach_time) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_FENCE_STATUS { \
"FENCE_STATUS", \
4, \
{ { "breach_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_fence_status_t, breach_status) }, \
{ "breach_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_fence_status_t, breach_count) }, \
{ "breach_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_fence_status_t, breach_type) }, \
{ "breach_time", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_fence_status_t, breach_time) }, \
} \
}
#endif
/**
* @brief Pack a fence_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 breach_status Breach status (0 if currently inside fence, 1 if outside).
* @param breach_count Number of fence breaches.
* @param breach_type Last breach type.
* @param breach_time [ms] Time (since boot) of last breach.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_fence_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t breach_status, uint16_t breach_count, uint8_t breach_type, uint32_t breach_time)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_FENCE_STATUS_LEN];
_mav_put_uint32_t(buf, 0, breach_time);
_mav_put_uint16_t(buf, 4, breach_count);
_mav_put_uint8_t(buf, 6, breach_status);
_mav_put_uint8_t(buf, 7, breach_type);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FENCE_STATUS_LEN);
#else
mavlink_fence_status_t packet;
packet.breach_time = breach_time;
packet.breach_count = breach_count;
packet.breach_status = breach_status;
packet.breach_type = breach_type;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FENCE_STATUS_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_FENCE_STATUS;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FENCE_STATUS_MIN_LEN, MAVLINK_MSG_ID_FENCE_STATUS_LEN, MAVLINK_MSG_ID_FENCE_STATUS_CRC);
}
/**
* @brief Pack a fence_status message on a channel
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param breach_status Breach status (0 if currently inside fence, 1 if outside).
* @param breach_count Number of fence breaches.
* @param breach_type Last breach type.
* @param breach_time [ms] Time (since boot) of last breach.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_fence_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint8_t breach_status,uint16_t breach_count,uint8_t breach_type,uint32_t breach_time)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_FENCE_STATUS_LEN];
_mav_put_uint32_t(buf, 0, breach_time);
_mav_put_uint16_t(buf, 4, breach_count);
_mav_put_uint8_t(buf, 6, breach_status);
_mav_put_uint8_t(buf, 7, breach_type);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FENCE_STATUS_LEN);
#else
mavlink_fence_status_t packet;
packet.breach_time = breach_time;
packet.breach_count = breach_count;
packet.breach_status = breach_status;
packet.breach_type = breach_type;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FENCE_STATUS_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_FENCE_STATUS;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FENCE_STATUS_MIN_LEN, MAVLINK_MSG_ID_FENCE_STATUS_LEN, MAVLINK_MSG_ID_FENCE_STATUS_CRC);
}
/**
* @brief Encode a fence_status struct
*
* @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 fence_status C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_fence_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_fence_status_t* fence_status)
{
return mavlink_msg_fence_status_pack(system_id, component_id, msg, fence_status->breach_status, fence_status->breach_count, fence_status->breach_type, fence_status->breach_time);
}
/**
* @brief Encode a fence_status struct on a channel
*
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param fence_status C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_fence_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_fence_status_t* fence_status)
{
return mavlink_msg_fence_status_pack_chan(system_id, component_id, chan, msg, fence_status->breach_status, fence_status->breach_count, fence_status->breach_type, fence_status->breach_time);
}
/**
* @brief Send a fence_status message
* @param chan MAVLink channel to send the message
*
* @param breach_status Breach status (0 if currently inside fence, 1 if outside).
* @param breach_count Number of fence breaches.
* @param breach_type Last breach type.
* @param breach_time [ms] Time (since boot) of last breach.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_fence_status_send(mavlink_channel_t chan, uint8_t breach_status, uint16_t breach_count, uint8_t breach_type, uint32_t breach_time)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_FENCE_STATUS_LEN];
_mav_put_uint32_t(buf, 0, breach_time);
_mav_put_uint16_t(buf, 4, breach_count);
_mav_put_uint8_t(buf, 6, breach_status);
_mav_put_uint8_t(buf, 7, breach_type);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_STATUS, buf, MAVLINK_MSG_ID_FENCE_STATUS_MIN_LEN, MAVLINK_MSG_ID_FENCE_STATUS_LEN, MAVLINK_MSG_ID_FENCE_STATUS_CRC);
#else
mavlink_fence_status_t packet;
packet.breach_time = breach_time;
packet.breach_count = breach_count;
packet.breach_status = breach_status;
packet.breach_type = breach_type;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_STATUS, (const char *)&packet, MAVLINK_MSG_ID_FENCE_STATUS_MIN_LEN, MAVLINK_MSG_ID_FENCE_STATUS_LEN, MAVLINK_MSG_ID_FENCE_STATUS_CRC);
#endif
}
/**
* @brief Send a fence_status message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_fence_status_send_struct(mavlink_channel_t chan, const mavlink_fence_status_t* fence_status)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_fence_status_send(chan, fence_status->breach_status, fence_status->breach_count, fence_status->breach_type, fence_status->breach_time);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_STATUS, (const char *)fence_status, MAVLINK_MSG_ID_FENCE_STATUS_MIN_LEN, MAVLINK_MSG_ID_FENCE_STATUS_LEN, MAVLINK_MSG_ID_FENCE_STATUS_CRC);
#endif
}
#if MAVLINK_MSG_ID_FENCE_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_fence_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t breach_status, uint16_t breach_count, uint8_t breach_type, uint32_t breach_time)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint32_t(buf, 0, breach_time);
_mav_put_uint16_t(buf, 4, breach_count);
_mav_put_uint8_t(buf, 6, breach_status);
_mav_put_uint8_t(buf, 7, breach_type);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_STATUS, buf, MAVLINK_MSG_ID_FENCE_STATUS_MIN_LEN, MAVLINK_MSG_ID_FENCE_STATUS_LEN, MAVLINK_MSG_ID_FENCE_STATUS_CRC);
#else
mavlink_fence_status_t *packet = (mavlink_fence_status_t *)msgbuf;
packet->breach_time = breach_time;
packet->breach_count = breach_count;
packet->breach_status = breach_status;
packet->breach_type = breach_type;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_STATUS, (const char *)packet, MAVLINK_MSG_ID_FENCE_STATUS_MIN_LEN, MAVLINK_MSG_ID_FENCE_STATUS_LEN, MAVLINK_MSG_ID_FENCE_STATUS_CRC);
#endif
}
#endif
#endif
// MESSAGE FENCE_STATUS UNPACKING
/**
* @brief Get field breach_status from fence_status message
*
* @return Breach status (0 if currently inside fence, 1 if outside).
*/
static inline uint8_t mavlink_msg_fence_status_get_breach_status(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 6);
}
/**
* @brief Get field breach_count from fence_status message
*
* @return Number of fence breaches.
*/
static inline uint16_t mavlink_msg_fence_status_get_breach_count(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 4);
}
/**
* @brief Get field breach_type from fence_status message
*
* @return Last breach type.
*/
static inline uint8_t mavlink_msg_fence_status_get_breach_type(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 7);
}
/**
* @brief Get field breach_time from fence_status message
*
* @return [ms] Time (since boot) of last breach.
*/
static inline uint32_t mavlink_msg_fence_status_get_breach_time(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 0);
}
/**
* @brief Decode a fence_status message into a struct
*
* @param msg The message to decode
* @param fence_status C-struct to decode the message contents into
*/
static inline void mavlink_msg_fence_status_decode(const mavlink_message_t* msg, mavlink_fence_status_t* fence_status)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
fence_status->breach_time = mavlink_msg_fence_status_get_breach_time(msg);
fence_status->breach_count = mavlink_msg_fence_status_get_breach_count(msg);
fence_status->breach_status = mavlink_msg_fence_status_get_breach_status(msg);
fence_status->breach_type = mavlink_msg_fence_status_get_breach_type(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_FENCE_STATUS_LEN? msg->len : MAVLINK_MSG_ID_FENCE_STATUS_LEN;
memset(fence_status, 0, MAVLINK_MSG_ID_FENCE_STATUS_LEN);
memcpy(fence_status, _MAV_PAYLOAD(msg), len);
#endif
}

View File

@@ -0,0 +1,313 @@
#pragma once
// MESSAGE GIMBAL_CONTROL PACKING
#define MAVLINK_MSG_ID_GIMBAL_CONTROL 201
MAVPACKED(
typedef struct __mavlink_gimbal_control_t {
float demanded_rate_x; /*< [rad/s] Demanded angular rate X.*/
float demanded_rate_y; /*< [rad/s] Demanded angular rate Y.*/
float demanded_rate_z; /*< [rad/s] Demanded angular rate Z.*/
uint8_t target_system; /*< System ID.*/
uint8_t target_component; /*< Component ID.*/
}) mavlink_gimbal_control_t;
#define MAVLINK_MSG_ID_GIMBAL_CONTROL_LEN 14
#define MAVLINK_MSG_ID_GIMBAL_CONTROL_MIN_LEN 14
#define MAVLINK_MSG_ID_201_LEN 14
#define MAVLINK_MSG_ID_201_MIN_LEN 14
#define MAVLINK_MSG_ID_GIMBAL_CONTROL_CRC 205
#define MAVLINK_MSG_ID_201_CRC 205
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_GIMBAL_CONTROL { \
201, \
"GIMBAL_CONTROL", \
5, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_gimbal_control_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_gimbal_control_t, target_component) }, \
{ "demanded_rate_x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_gimbal_control_t, demanded_rate_x) }, \
{ "demanded_rate_y", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_gimbal_control_t, demanded_rate_y) }, \
{ "demanded_rate_z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_gimbal_control_t, demanded_rate_z) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_GIMBAL_CONTROL { \
"GIMBAL_CONTROL", \
5, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_gimbal_control_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_gimbal_control_t, target_component) }, \
{ "demanded_rate_x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_gimbal_control_t, demanded_rate_x) }, \
{ "demanded_rate_y", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_gimbal_control_t, demanded_rate_y) }, \
{ "demanded_rate_z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_gimbal_control_t, demanded_rate_z) }, \
} \
}
#endif
/**
* @brief Pack a gimbal_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_system System ID.
* @param target_component Component ID.
* @param demanded_rate_x [rad/s] Demanded angular rate X.
* @param demanded_rate_y [rad/s] Demanded angular rate Y.
* @param demanded_rate_z [rad/s] Demanded angular rate Z.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_gimbal_control_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, float demanded_rate_x, float demanded_rate_y, float demanded_rate_z)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_GIMBAL_CONTROL_LEN];
_mav_put_float(buf, 0, demanded_rate_x);
_mav_put_float(buf, 4, demanded_rate_y);
_mav_put_float(buf, 8, demanded_rate_z);
_mav_put_uint8_t(buf, 12, target_system);
_mav_put_uint8_t(buf, 13, target_component);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GIMBAL_CONTROL_LEN);
#else
mavlink_gimbal_control_t packet;
packet.demanded_rate_x = demanded_rate_x;
packet.demanded_rate_y = demanded_rate_y;
packet.demanded_rate_z = demanded_rate_z;
packet.target_system = target_system;
packet.target_component = target_component;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GIMBAL_CONTROL_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_GIMBAL_CONTROL;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GIMBAL_CONTROL_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_CONTROL_LEN, MAVLINK_MSG_ID_GIMBAL_CONTROL_CRC);
}
/**
* @brief Pack a gimbal_control message on a channel
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID.
* @param target_component Component ID.
* @param demanded_rate_x [rad/s] Demanded angular rate X.
* @param demanded_rate_y [rad/s] Demanded angular rate Y.
* @param demanded_rate_z [rad/s] Demanded angular rate Z.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_gimbal_control_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 demanded_rate_x,float demanded_rate_y,float demanded_rate_z)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_GIMBAL_CONTROL_LEN];
_mav_put_float(buf, 0, demanded_rate_x);
_mav_put_float(buf, 4, demanded_rate_y);
_mav_put_float(buf, 8, demanded_rate_z);
_mav_put_uint8_t(buf, 12, target_system);
_mav_put_uint8_t(buf, 13, target_component);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GIMBAL_CONTROL_LEN);
#else
mavlink_gimbal_control_t packet;
packet.demanded_rate_x = demanded_rate_x;
packet.demanded_rate_y = demanded_rate_y;
packet.demanded_rate_z = demanded_rate_z;
packet.target_system = target_system;
packet.target_component = target_component;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GIMBAL_CONTROL_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_GIMBAL_CONTROL;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GIMBAL_CONTROL_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_CONTROL_LEN, MAVLINK_MSG_ID_GIMBAL_CONTROL_CRC);
}
/**
* @brief Encode a gimbal_control struct
*
* @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 gimbal_control C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_gimbal_control_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gimbal_control_t* gimbal_control)
{
return mavlink_msg_gimbal_control_pack(system_id, component_id, msg, gimbal_control->target_system, gimbal_control->target_component, gimbal_control->demanded_rate_x, gimbal_control->demanded_rate_y, gimbal_control->demanded_rate_z);
}
/**
* @brief Encode a gimbal_control struct on a channel
*
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param gimbal_control C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_gimbal_control_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gimbal_control_t* gimbal_control)
{
return mavlink_msg_gimbal_control_pack_chan(system_id, component_id, chan, msg, gimbal_control->target_system, gimbal_control->target_component, gimbal_control->demanded_rate_x, gimbal_control->demanded_rate_y, gimbal_control->demanded_rate_z);
}
/**
* @brief Send a gimbal_control message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID.
* @param target_component Component ID.
* @param demanded_rate_x [rad/s] Demanded angular rate X.
* @param demanded_rate_y [rad/s] Demanded angular rate Y.
* @param demanded_rate_z [rad/s] Demanded angular rate Z.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_gimbal_control_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, float demanded_rate_x, float demanded_rate_y, float demanded_rate_z)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_GIMBAL_CONTROL_LEN];
_mav_put_float(buf, 0, demanded_rate_x);
_mav_put_float(buf, 4, demanded_rate_y);
_mav_put_float(buf, 8, demanded_rate_z);
_mav_put_uint8_t(buf, 12, target_system);
_mav_put_uint8_t(buf, 13, target_component);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_CONTROL, buf, MAVLINK_MSG_ID_GIMBAL_CONTROL_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_CONTROL_LEN, MAVLINK_MSG_ID_GIMBAL_CONTROL_CRC);
#else
mavlink_gimbal_control_t packet;
packet.demanded_rate_x = demanded_rate_x;
packet.demanded_rate_y = demanded_rate_y;
packet.demanded_rate_z = demanded_rate_z;
packet.target_system = target_system;
packet.target_component = target_component;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_CONTROL, (const char *)&packet, MAVLINK_MSG_ID_GIMBAL_CONTROL_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_CONTROL_LEN, MAVLINK_MSG_ID_GIMBAL_CONTROL_CRC);
#endif
}
/**
* @brief Send a gimbal_control message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_gimbal_control_send_struct(mavlink_channel_t chan, const mavlink_gimbal_control_t* gimbal_control)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_gimbal_control_send(chan, gimbal_control->target_system, gimbal_control->target_component, gimbal_control->demanded_rate_x, gimbal_control->demanded_rate_y, gimbal_control->demanded_rate_z);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_CONTROL, (const char *)gimbal_control, MAVLINK_MSG_ID_GIMBAL_CONTROL_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_CONTROL_LEN, MAVLINK_MSG_ID_GIMBAL_CONTROL_CRC);
#endif
}
#if MAVLINK_MSG_ID_GIMBAL_CONTROL_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_gimbal_control_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, float demanded_rate_x, float demanded_rate_y, float demanded_rate_z)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_float(buf, 0, demanded_rate_x);
_mav_put_float(buf, 4, demanded_rate_y);
_mav_put_float(buf, 8, demanded_rate_z);
_mav_put_uint8_t(buf, 12, target_system);
_mav_put_uint8_t(buf, 13, target_component);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_CONTROL, buf, MAVLINK_MSG_ID_GIMBAL_CONTROL_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_CONTROL_LEN, MAVLINK_MSG_ID_GIMBAL_CONTROL_CRC);
#else
mavlink_gimbal_control_t *packet = (mavlink_gimbal_control_t *)msgbuf;
packet->demanded_rate_x = demanded_rate_x;
packet->demanded_rate_y = demanded_rate_y;
packet->demanded_rate_z = demanded_rate_z;
packet->target_system = target_system;
packet->target_component = target_component;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_CONTROL, (const char *)packet, MAVLINK_MSG_ID_GIMBAL_CONTROL_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_CONTROL_LEN, MAVLINK_MSG_ID_GIMBAL_CONTROL_CRC);
#endif
}
#endif
#endif
// MESSAGE GIMBAL_CONTROL UNPACKING
/**
* @brief Get field target_system from gimbal_control message
*
* @return System ID.
*/
static inline uint8_t mavlink_msg_gimbal_control_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 12);
}
/**
* @brief Get field target_component from gimbal_control message
*
* @return Component ID.
*/
static inline uint8_t mavlink_msg_gimbal_control_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 13);
}
/**
* @brief Get field demanded_rate_x from gimbal_control message
*
* @return [rad/s] Demanded angular rate X.
*/
static inline float mavlink_msg_gimbal_control_get_demanded_rate_x(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 0);
}
/**
* @brief Get field demanded_rate_y from gimbal_control message
*
* @return [rad/s] Demanded angular rate Y.
*/
static inline float mavlink_msg_gimbal_control_get_demanded_rate_y(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 4);
}
/**
* @brief Get field demanded_rate_z from gimbal_control message
*
* @return [rad/s] Demanded angular rate Z.
*/
static inline float mavlink_msg_gimbal_control_get_demanded_rate_z(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
/**
* @brief Decode a gimbal_control message into a struct
*
* @param msg The message to decode
* @param gimbal_control C-struct to decode the message contents into
*/
static inline void mavlink_msg_gimbal_control_decode(const mavlink_message_t* msg, mavlink_gimbal_control_t* gimbal_control)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
gimbal_control->demanded_rate_x = mavlink_msg_gimbal_control_get_demanded_rate_x(msg);
gimbal_control->demanded_rate_y = mavlink_msg_gimbal_control_get_demanded_rate_y(msg);
gimbal_control->demanded_rate_z = mavlink_msg_gimbal_control_get_demanded_rate_z(msg);
gimbal_control->target_system = mavlink_msg_gimbal_control_get_target_system(msg);
gimbal_control->target_component = mavlink_msg_gimbal_control_get_target_component(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_GIMBAL_CONTROL_LEN? msg->len : MAVLINK_MSG_ID_GIMBAL_CONTROL_LEN;
memset(gimbal_control, 0, MAVLINK_MSG_ID_GIMBAL_CONTROL_LEN);
memcpy(gimbal_control, _MAV_PAYLOAD(msg), len);
#endif
}

View File

@@ -0,0 +1,488 @@
#pragma once
// MESSAGE GIMBAL_REPORT PACKING
#define MAVLINK_MSG_ID_GIMBAL_REPORT 200
MAVPACKED(
typedef struct __mavlink_gimbal_report_t {
float delta_time; /*< [s] Time since last update.*/
float delta_angle_x; /*< [rad] Delta angle X.*/
float delta_angle_y; /*< [rad] Delta angle Y.*/
float delta_angle_z; /*< [rad] Delta angle X.*/
float delta_velocity_x; /*< [m/s] Delta velocity X.*/
float delta_velocity_y; /*< [m/s] Delta velocity Y.*/
float delta_velocity_z; /*< [m/s] Delta velocity Z.*/
float joint_roll; /*< [rad] Joint ROLL.*/
float joint_el; /*< [rad] Joint EL.*/
float joint_az; /*< [rad] Joint AZ.*/
uint8_t target_system; /*< System ID.*/
uint8_t target_component; /*< Component ID.*/
}) mavlink_gimbal_report_t;
#define MAVLINK_MSG_ID_GIMBAL_REPORT_LEN 42
#define MAVLINK_MSG_ID_GIMBAL_REPORT_MIN_LEN 42
#define MAVLINK_MSG_ID_200_LEN 42
#define MAVLINK_MSG_ID_200_MIN_LEN 42
#define MAVLINK_MSG_ID_GIMBAL_REPORT_CRC 134
#define MAVLINK_MSG_ID_200_CRC 134
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_GIMBAL_REPORT { \
200, \
"GIMBAL_REPORT", \
12, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 40, offsetof(mavlink_gimbal_report_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 41, offsetof(mavlink_gimbal_report_t, target_component) }, \
{ "delta_time", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_gimbal_report_t, delta_time) }, \
{ "delta_angle_x", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_gimbal_report_t, delta_angle_x) }, \
{ "delta_angle_y", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_gimbal_report_t, delta_angle_y) }, \
{ "delta_angle_z", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_gimbal_report_t, delta_angle_z) }, \
{ "delta_velocity_x", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_gimbal_report_t, delta_velocity_x) }, \
{ "delta_velocity_y", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_gimbal_report_t, delta_velocity_y) }, \
{ "delta_velocity_z", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_gimbal_report_t, delta_velocity_z) }, \
{ "joint_roll", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_gimbal_report_t, joint_roll) }, \
{ "joint_el", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_gimbal_report_t, joint_el) }, \
{ "joint_az", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_gimbal_report_t, joint_az) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_GIMBAL_REPORT { \
"GIMBAL_REPORT", \
12, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 40, offsetof(mavlink_gimbal_report_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 41, offsetof(mavlink_gimbal_report_t, target_component) }, \
{ "delta_time", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_gimbal_report_t, delta_time) }, \
{ "delta_angle_x", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_gimbal_report_t, delta_angle_x) }, \
{ "delta_angle_y", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_gimbal_report_t, delta_angle_y) }, \
{ "delta_angle_z", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_gimbal_report_t, delta_angle_z) }, \
{ "delta_velocity_x", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_gimbal_report_t, delta_velocity_x) }, \
{ "delta_velocity_y", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_gimbal_report_t, delta_velocity_y) }, \
{ "delta_velocity_z", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_gimbal_report_t, delta_velocity_z) }, \
{ "joint_roll", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_gimbal_report_t, joint_roll) }, \
{ "joint_el", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_gimbal_report_t, joint_el) }, \
{ "joint_az", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_gimbal_report_t, joint_az) }, \
} \
}
#endif
/**
* @brief Pack a gimbal_report 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.
* @param delta_time [s] Time since last update.
* @param delta_angle_x [rad] Delta angle X.
* @param delta_angle_y [rad] Delta angle Y.
* @param delta_angle_z [rad] Delta angle X.
* @param delta_velocity_x [m/s] Delta velocity X.
* @param delta_velocity_y [m/s] Delta velocity Y.
* @param delta_velocity_z [m/s] Delta velocity Z.
* @param joint_roll [rad] Joint ROLL.
* @param joint_el [rad] Joint EL.
* @param joint_az [rad] Joint AZ.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_gimbal_report_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, float delta_time, float delta_angle_x, float delta_angle_y, float delta_angle_z, float delta_velocity_x, float delta_velocity_y, float delta_velocity_z, float joint_roll, float joint_el, float joint_az)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_GIMBAL_REPORT_LEN];
_mav_put_float(buf, 0, delta_time);
_mav_put_float(buf, 4, delta_angle_x);
_mav_put_float(buf, 8, delta_angle_y);
_mav_put_float(buf, 12, delta_angle_z);
_mav_put_float(buf, 16, delta_velocity_x);
_mav_put_float(buf, 20, delta_velocity_y);
_mav_put_float(buf, 24, delta_velocity_z);
_mav_put_float(buf, 28, joint_roll);
_mav_put_float(buf, 32, joint_el);
_mav_put_float(buf, 36, joint_az);
_mav_put_uint8_t(buf, 40, target_system);
_mav_put_uint8_t(buf, 41, target_component);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GIMBAL_REPORT_LEN);
#else
mavlink_gimbal_report_t packet;
packet.delta_time = delta_time;
packet.delta_angle_x = delta_angle_x;
packet.delta_angle_y = delta_angle_y;
packet.delta_angle_z = delta_angle_z;
packet.delta_velocity_x = delta_velocity_x;
packet.delta_velocity_y = delta_velocity_y;
packet.delta_velocity_z = delta_velocity_z;
packet.joint_roll = joint_roll;
packet.joint_el = joint_el;
packet.joint_az = joint_az;
packet.target_system = target_system;
packet.target_component = target_component;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GIMBAL_REPORT_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_GIMBAL_REPORT;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GIMBAL_REPORT_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_REPORT_LEN, MAVLINK_MSG_ID_GIMBAL_REPORT_CRC);
}
/**
* @brief Pack a gimbal_report message on a channel
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID.
* @param target_component Component ID.
* @param delta_time [s] Time since last update.
* @param delta_angle_x [rad] Delta angle X.
* @param delta_angle_y [rad] Delta angle Y.
* @param delta_angle_z [rad] Delta angle X.
* @param delta_velocity_x [m/s] Delta velocity X.
* @param delta_velocity_y [m/s] Delta velocity Y.
* @param delta_velocity_z [m/s] Delta velocity Z.
* @param joint_roll [rad] Joint ROLL.
* @param joint_el [rad] Joint EL.
* @param joint_az [rad] Joint AZ.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_gimbal_report_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 delta_time,float delta_angle_x,float delta_angle_y,float delta_angle_z,float delta_velocity_x,float delta_velocity_y,float delta_velocity_z,float joint_roll,float joint_el,float joint_az)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_GIMBAL_REPORT_LEN];
_mav_put_float(buf, 0, delta_time);
_mav_put_float(buf, 4, delta_angle_x);
_mav_put_float(buf, 8, delta_angle_y);
_mav_put_float(buf, 12, delta_angle_z);
_mav_put_float(buf, 16, delta_velocity_x);
_mav_put_float(buf, 20, delta_velocity_y);
_mav_put_float(buf, 24, delta_velocity_z);
_mav_put_float(buf, 28, joint_roll);
_mav_put_float(buf, 32, joint_el);
_mav_put_float(buf, 36, joint_az);
_mav_put_uint8_t(buf, 40, target_system);
_mav_put_uint8_t(buf, 41, target_component);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GIMBAL_REPORT_LEN);
#else
mavlink_gimbal_report_t packet;
packet.delta_time = delta_time;
packet.delta_angle_x = delta_angle_x;
packet.delta_angle_y = delta_angle_y;
packet.delta_angle_z = delta_angle_z;
packet.delta_velocity_x = delta_velocity_x;
packet.delta_velocity_y = delta_velocity_y;
packet.delta_velocity_z = delta_velocity_z;
packet.joint_roll = joint_roll;
packet.joint_el = joint_el;
packet.joint_az = joint_az;
packet.target_system = target_system;
packet.target_component = target_component;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GIMBAL_REPORT_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_GIMBAL_REPORT;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GIMBAL_REPORT_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_REPORT_LEN, MAVLINK_MSG_ID_GIMBAL_REPORT_CRC);
}
/**
* @brief Encode a gimbal_report struct
*
* @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 gimbal_report C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_gimbal_report_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gimbal_report_t* gimbal_report)
{
return mavlink_msg_gimbal_report_pack(system_id, component_id, msg, gimbal_report->target_system, gimbal_report->target_component, gimbal_report->delta_time, gimbal_report->delta_angle_x, gimbal_report->delta_angle_y, gimbal_report->delta_angle_z, gimbal_report->delta_velocity_x, gimbal_report->delta_velocity_y, gimbal_report->delta_velocity_z, gimbal_report->joint_roll, gimbal_report->joint_el, gimbal_report->joint_az);
}
/**
* @brief Encode a gimbal_report struct on a channel
*
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param gimbal_report C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_gimbal_report_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gimbal_report_t* gimbal_report)
{
return mavlink_msg_gimbal_report_pack_chan(system_id, component_id, chan, msg, gimbal_report->target_system, gimbal_report->target_component, gimbal_report->delta_time, gimbal_report->delta_angle_x, gimbal_report->delta_angle_y, gimbal_report->delta_angle_z, gimbal_report->delta_velocity_x, gimbal_report->delta_velocity_y, gimbal_report->delta_velocity_z, gimbal_report->joint_roll, gimbal_report->joint_el, gimbal_report->joint_az);
}
/**
* @brief Send a gimbal_report message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID.
* @param target_component Component ID.
* @param delta_time [s] Time since last update.
* @param delta_angle_x [rad] Delta angle X.
* @param delta_angle_y [rad] Delta angle Y.
* @param delta_angle_z [rad] Delta angle X.
* @param delta_velocity_x [m/s] Delta velocity X.
* @param delta_velocity_y [m/s] Delta velocity Y.
* @param delta_velocity_z [m/s] Delta velocity Z.
* @param joint_roll [rad] Joint ROLL.
* @param joint_el [rad] Joint EL.
* @param joint_az [rad] Joint AZ.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_gimbal_report_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, float delta_time, float delta_angle_x, float delta_angle_y, float delta_angle_z, float delta_velocity_x, float delta_velocity_y, float delta_velocity_z, float joint_roll, float joint_el, float joint_az)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_GIMBAL_REPORT_LEN];
_mav_put_float(buf, 0, delta_time);
_mav_put_float(buf, 4, delta_angle_x);
_mav_put_float(buf, 8, delta_angle_y);
_mav_put_float(buf, 12, delta_angle_z);
_mav_put_float(buf, 16, delta_velocity_x);
_mav_put_float(buf, 20, delta_velocity_y);
_mav_put_float(buf, 24, delta_velocity_z);
_mav_put_float(buf, 28, joint_roll);
_mav_put_float(buf, 32, joint_el);
_mav_put_float(buf, 36, joint_az);
_mav_put_uint8_t(buf, 40, target_system);
_mav_put_uint8_t(buf, 41, target_component);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_REPORT, buf, MAVLINK_MSG_ID_GIMBAL_REPORT_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_REPORT_LEN, MAVLINK_MSG_ID_GIMBAL_REPORT_CRC);
#else
mavlink_gimbal_report_t packet;
packet.delta_time = delta_time;
packet.delta_angle_x = delta_angle_x;
packet.delta_angle_y = delta_angle_y;
packet.delta_angle_z = delta_angle_z;
packet.delta_velocity_x = delta_velocity_x;
packet.delta_velocity_y = delta_velocity_y;
packet.delta_velocity_z = delta_velocity_z;
packet.joint_roll = joint_roll;
packet.joint_el = joint_el;
packet.joint_az = joint_az;
packet.target_system = target_system;
packet.target_component = target_component;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_REPORT, (const char *)&packet, MAVLINK_MSG_ID_GIMBAL_REPORT_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_REPORT_LEN, MAVLINK_MSG_ID_GIMBAL_REPORT_CRC);
#endif
}
/**
* @brief Send a gimbal_report message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_gimbal_report_send_struct(mavlink_channel_t chan, const mavlink_gimbal_report_t* gimbal_report)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_gimbal_report_send(chan, gimbal_report->target_system, gimbal_report->target_component, gimbal_report->delta_time, gimbal_report->delta_angle_x, gimbal_report->delta_angle_y, gimbal_report->delta_angle_z, gimbal_report->delta_velocity_x, gimbal_report->delta_velocity_y, gimbal_report->delta_velocity_z, gimbal_report->joint_roll, gimbal_report->joint_el, gimbal_report->joint_az);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_REPORT, (const char *)gimbal_report, MAVLINK_MSG_ID_GIMBAL_REPORT_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_REPORT_LEN, MAVLINK_MSG_ID_GIMBAL_REPORT_CRC);
#endif
}
#if MAVLINK_MSG_ID_GIMBAL_REPORT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_gimbal_report_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, float delta_time, float delta_angle_x, float delta_angle_y, float delta_angle_z, float delta_velocity_x, float delta_velocity_y, float delta_velocity_z, float joint_roll, float joint_el, float joint_az)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_float(buf, 0, delta_time);
_mav_put_float(buf, 4, delta_angle_x);
_mav_put_float(buf, 8, delta_angle_y);
_mav_put_float(buf, 12, delta_angle_z);
_mav_put_float(buf, 16, delta_velocity_x);
_mav_put_float(buf, 20, delta_velocity_y);
_mav_put_float(buf, 24, delta_velocity_z);
_mav_put_float(buf, 28, joint_roll);
_mav_put_float(buf, 32, joint_el);
_mav_put_float(buf, 36, joint_az);
_mav_put_uint8_t(buf, 40, target_system);
_mav_put_uint8_t(buf, 41, target_component);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_REPORT, buf, MAVLINK_MSG_ID_GIMBAL_REPORT_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_REPORT_LEN, MAVLINK_MSG_ID_GIMBAL_REPORT_CRC);
#else
mavlink_gimbal_report_t *packet = (mavlink_gimbal_report_t *)msgbuf;
packet->delta_time = delta_time;
packet->delta_angle_x = delta_angle_x;
packet->delta_angle_y = delta_angle_y;
packet->delta_angle_z = delta_angle_z;
packet->delta_velocity_x = delta_velocity_x;
packet->delta_velocity_y = delta_velocity_y;
packet->delta_velocity_z = delta_velocity_z;
packet->joint_roll = joint_roll;
packet->joint_el = joint_el;
packet->joint_az = joint_az;
packet->target_system = target_system;
packet->target_component = target_component;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_REPORT, (const char *)packet, MAVLINK_MSG_ID_GIMBAL_REPORT_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_REPORT_LEN, MAVLINK_MSG_ID_GIMBAL_REPORT_CRC);
#endif
}
#endif
#endif
// MESSAGE GIMBAL_REPORT UNPACKING
/**
* @brief Get field target_system from gimbal_report message
*
* @return System ID.
*/
static inline uint8_t mavlink_msg_gimbal_report_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 40);
}
/**
* @brief Get field target_component from gimbal_report message
*
* @return Component ID.
*/
static inline uint8_t mavlink_msg_gimbal_report_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 41);
}
/**
* @brief Get field delta_time from gimbal_report message
*
* @return [s] Time since last update.
*/
static inline float mavlink_msg_gimbal_report_get_delta_time(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 0);
}
/**
* @brief Get field delta_angle_x from gimbal_report message
*
* @return [rad] Delta angle X.
*/
static inline float mavlink_msg_gimbal_report_get_delta_angle_x(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 4);
}
/**
* @brief Get field delta_angle_y from gimbal_report message
*
* @return [rad] Delta angle Y.
*/
static inline float mavlink_msg_gimbal_report_get_delta_angle_y(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
/**
* @brief Get field delta_angle_z from gimbal_report message
*
* @return [rad] Delta angle X.
*/
static inline float mavlink_msg_gimbal_report_get_delta_angle_z(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
/**
* @brief Get field delta_velocity_x from gimbal_report message
*
* @return [m/s] Delta velocity X.
*/
static inline float mavlink_msg_gimbal_report_get_delta_velocity_x(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 16);
}
/**
* @brief Get field delta_velocity_y from gimbal_report message
*
* @return [m/s] Delta velocity Y.
*/
static inline float mavlink_msg_gimbal_report_get_delta_velocity_y(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 20);
}
/**
* @brief Get field delta_velocity_z from gimbal_report message
*
* @return [m/s] Delta velocity Z.
*/
static inline float mavlink_msg_gimbal_report_get_delta_velocity_z(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 24);
}
/**
* @brief Get field joint_roll from gimbal_report message
*
* @return [rad] Joint ROLL.
*/
static inline float mavlink_msg_gimbal_report_get_joint_roll(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 28);
}
/**
* @brief Get field joint_el from gimbal_report message
*
* @return [rad] Joint EL.
*/
static inline float mavlink_msg_gimbal_report_get_joint_el(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 32);
}
/**
* @brief Get field joint_az from gimbal_report message
*
* @return [rad] Joint AZ.
*/
static inline float mavlink_msg_gimbal_report_get_joint_az(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 36);
}
/**
* @brief Decode a gimbal_report message into a struct
*
* @param msg The message to decode
* @param gimbal_report C-struct to decode the message contents into
*/
static inline void mavlink_msg_gimbal_report_decode(const mavlink_message_t* msg, mavlink_gimbal_report_t* gimbal_report)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
gimbal_report->delta_time = mavlink_msg_gimbal_report_get_delta_time(msg);
gimbal_report->delta_angle_x = mavlink_msg_gimbal_report_get_delta_angle_x(msg);
gimbal_report->delta_angle_y = mavlink_msg_gimbal_report_get_delta_angle_y(msg);
gimbal_report->delta_angle_z = mavlink_msg_gimbal_report_get_delta_angle_z(msg);
gimbal_report->delta_velocity_x = mavlink_msg_gimbal_report_get_delta_velocity_x(msg);
gimbal_report->delta_velocity_y = mavlink_msg_gimbal_report_get_delta_velocity_y(msg);
gimbal_report->delta_velocity_z = mavlink_msg_gimbal_report_get_delta_velocity_z(msg);
gimbal_report->joint_roll = mavlink_msg_gimbal_report_get_joint_roll(msg);
gimbal_report->joint_el = mavlink_msg_gimbal_report_get_joint_el(msg);
gimbal_report->joint_az = mavlink_msg_gimbal_report_get_joint_az(msg);
gimbal_report->target_system = mavlink_msg_gimbal_report_get_target_system(msg);
gimbal_report->target_component = mavlink_msg_gimbal_report_get_target_component(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_GIMBAL_REPORT_LEN? msg->len : MAVLINK_MSG_ID_GIMBAL_REPORT_LEN;
memset(gimbal_report, 0, MAVLINK_MSG_ID_GIMBAL_REPORT_LEN);
memcpy(gimbal_report, _MAV_PAYLOAD(msg), len);
#endif
}

View File

@@ -0,0 +1,313 @@
#pragma once
// MESSAGE GIMBAL_TORQUE_CMD_REPORT PACKING
#define MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT 214
MAVPACKED(
typedef struct __mavlink_gimbal_torque_cmd_report_t {
int16_t rl_torque_cmd; /*< Roll Torque Command.*/
int16_t el_torque_cmd; /*< Elevation Torque Command.*/
int16_t az_torque_cmd; /*< Azimuth Torque Command.*/
uint8_t target_system; /*< System ID.*/
uint8_t target_component; /*< Component ID.*/
}) mavlink_gimbal_torque_cmd_report_t;
#define MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_LEN 8
#define MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_MIN_LEN 8
#define MAVLINK_MSG_ID_214_LEN 8
#define MAVLINK_MSG_ID_214_MIN_LEN 8
#define MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_CRC 69
#define MAVLINK_MSG_ID_214_CRC 69
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_GIMBAL_TORQUE_CMD_REPORT { \
214, \
"GIMBAL_TORQUE_CMD_REPORT", \
5, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_gimbal_torque_cmd_report_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_gimbal_torque_cmd_report_t, target_component) }, \
{ "rl_torque_cmd", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_gimbal_torque_cmd_report_t, rl_torque_cmd) }, \
{ "el_torque_cmd", NULL, MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_gimbal_torque_cmd_report_t, el_torque_cmd) }, \
{ "az_torque_cmd", NULL, MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_gimbal_torque_cmd_report_t, az_torque_cmd) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_GIMBAL_TORQUE_CMD_REPORT { \
"GIMBAL_TORQUE_CMD_REPORT", \
5, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_gimbal_torque_cmd_report_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_gimbal_torque_cmd_report_t, target_component) }, \
{ "rl_torque_cmd", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_gimbal_torque_cmd_report_t, rl_torque_cmd) }, \
{ "el_torque_cmd", NULL, MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_gimbal_torque_cmd_report_t, el_torque_cmd) }, \
{ "az_torque_cmd", NULL, MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_gimbal_torque_cmd_report_t, az_torque_cmd) }, \
} \
}
#endif
/**
* @brief Pack a gimbal_torque_cmd_report 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.
* @param rl_torque_cmd Roll Torque Command.
* @param el_torque_cmd Elevation Torque Command.
* @param az_torque_cmd Azimuth Torque Command.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_gimbal_torque_cmd_report_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, int16_t rl_torque_cmd, int16_t el_torque_cmd, int16_t az_torque_cmd)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_LEN];
_mav_put_int16_t(buf, 0, rl_torque_cmd);
_mav_put_int16_t(buf, 2, el_torque_cmd);
_mav_put_int16_t(buf, 4, az_torque_cmd);
_mav_put_uint8_t(buf, 6, target_system);
_mav_put_uint8_t(buf, 7, target_component);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_LEN);
#else
mavlink_gimbal_torque_cmd_report_t packet;
packet.rl_torque_cmd = rl_torque_cmd;
packet.el_torque_cmd = el_torque_cmd;
packet.az_torque_cmd = az_torque_cmd;
packet.target_system = target_system;
packet.target_component = target_component;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_LEN, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_CRC);
}
/**
* @brief Pack a gimbal_torque_cmd_report message on a channel
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID.
* @param target_component Component ID.
* @param rl_torque_cmd Roll Torque Command.
* @param el_torque_cmd Elevation Torque Command.
* @param az_torque_cmd Azimuth Torque Command.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_gimbal_torque_cmd_report_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,int16_t rl_torque_cmd,int16_t el_torque_cmd,int16_t az_torque_cmd)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_LEN];
_mav_put_int16_t(buf, 0, rl_torque_cmd);
_mav_put_int16_t(buf, 2, el_torque_cmd);
_mav_put_int16_t(buf, 4, az_torque_cmd);
_mav_put_uint8_t(buf, 6, target_system);
_mav_put_uint8_t(buf, 7, target_component);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_LEN);
#else
mavlink_gimbal_torque_cmd_report_t packet;
packet.rl_torque_cmd = rl_torque_cmd;
packet.el_torque_cmd = el_torque_cmd;
packet.az_torque_cmd = az_torque_cmd;
packet.target_system = target_system;
packet.target_component = target_component;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_LEN, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_CRC);
}
/**
* @brief Encode a gimbal_torque_cmd_report struct
*
* @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 gimbal_torque_cmd_report C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_gimbal_torque_cmd_report_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gimbal_torque_cmd_report_t* gimbal_torque_cmd_report)
{
return mavlink_msg_gimbal_torque_cmd_report_pack(system_id, component_id, msg, gimbal_torque_cmd_report->target_system, gimbal_torque_cmd_report->target_component, gimbal_torque_cmd_report->rl_torque_cmd, gimbal_torque_cmd_report->el_torque_cmd, gimbal_torque_cmd_report->az_torque_cmd);
}
/**
* @brief Encode a gimbal_torque_cmd_report struct on a channel
*
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param gimbal_torque_cmd_report C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_gimbal_torque_cmd_report_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gimbal_torque_cmd_report_t* gimbal_torque_cmd_report)
{
return mavlink_msg_gimbal_torque_cmd_report_pack_chan(system_id, component_id, chan, msg, gimbal_torque_cmd_report->target_system, gimbal_torque_cmd_report->target_component, gimbal_torque_cmd_report->rl_torque_cmd, gimbal_torque_cmd_report->el_torque_cmd, gimbal_torque_cmd_report->az_torque_cmd);
}
/**
* @brief Send a gimbal_torque_cmd_report message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID.
* @param target_component Component ID.
* @param rl_torque_cmd Roll Torque Command.
* @param el_torque_cmd Elevation Torque Command.
* @param az_torque_cmd Azimuth Torque Command.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_gimbal_torque_cmd_report_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, int16_t rl_torque_cmd, int16_t el_torque_cmd, int16_t az_torque_cmd)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_LEN];
_mav_put_int16_t(buf, 0, rl_torque_cmd);
_mav_put_int16_t(buf, 2, el_torque_cmd);
_mav_put_int16_t(buf, 4, az_torque_cmd);
_mav_put_uint8_t(buf, 6, target_system);
_mav_put_uint8_t(buf, 7, target_component);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT, buf, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_LEN, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_CRC);
#else
mavlink_gimbal_torque_cmd_report_t packet;
packet.rl_torque_cmd = rl_torque_cmd;
packet.el_torque_cmd = el_torque_cmd;
packet.az_torque_cmd = az_torque_cmd;
packet.target_system = target_system;
packet.target_component = target_component;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT, (const char *)&packet, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_LEN, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_CRC);
#endif
}
/**
* @brief Send a gimbal_torque_cmd_report message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_gimbal_torque_cmd_report_send_struct(mavlink_channel_t chan, const mavlink_gimbal_torque_cmd_report_t* gimbal_torque_cmd_report)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_gimbal_torque_cmd_report_send(chan, gimbal_torque_cmd_report->target_system, gimbal_torque_cmd_report->target_component, gimbal_torque_cmd_report->rl_torque_cmd, gimbal_torque_cmd_report->el_torque_cmd, gimbal_torque_cmd_report->az_torque_cmd);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT, (const char *)gimbal_torque_cmd_report, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_LEN, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_CRC);
#endif
}
#if MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_gimbal_torque_cmd_report_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, int16_t rl_torque_cmd, int16_t el_torque_cmd, int16_t az_torque_cmd)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_int16_t(buf, 0, rl_torque_cmd);
_mav_put_int16_t(buf, 2, el_torque_cmd);
_mav_put_int16_t(buf, 4, az_torque_cmd);
_mav_put_uint8_t(buf, 6, target_system);
_mav_put_uint8_t(buf, 7, target_component);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT, buf, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_LEN, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_CRC);
#else
mavlink_gimbal_torque_cmd_report_t *packet = (mavlink_gimbal_torque_cmd_report_t *)msgbuf;
packet->rl_torque_cmd = rl_torque_cmd;
packet->el_torque_cmd = el_torque_cmd;
packet->az_torque_cmd = az_torque_cmd;
packet->target_system = target_system;
packet->target_component = target_component;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT, (const char *)packet, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_LEN, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_CRC);
#endif
}
#endif
#endif
// MESSAGE GIMBAL_TORQUE_CMD_REPORT UNPACKING
/**
* @brief Get field target_system from gimbal_torque_cmd_report message
*
* @return System ID.
*/
static inline uint8_t mavlink_msg_gimbal_torque_cmd_report_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 6);
}
/**
* @brief Get field target_component from gimbal_torque_cmd_report message
*
* @return Component ID.
*/
static inline uint8_t mavlink_msg_gimbal_torque_cmd_report_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 7);
}
/**
* @brief Get field rl_torque_cmd from gimbal_torque_cmd_report message
*
* @return Roll Torque Command.
*/
static inline int16_t mavlink_msg_gimbal_torque_cmd_report_get_rl_torque_cmd(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 0);
}
/**
* @brief Get field el_torque_cmd from gimbal_torque_cmd_report message
*
* @return Elevation Torque Command.
*/
static inline int16_t mavlink_msg_gimbal_torque_cmd_report_get_el_torque_cmd(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 2);
}
/**
* @brief Get field az_torque_cmd from gimbal_torque_cmd_report message
*
* @return Azimuth Torque Command.
*/
static inline int16_t mavlink_msg_gimbal_torque_cmd_report_get_az_torque_cmd(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 4);
}
/**
* @brief Decode a gimbal_torque_cmd_report message into a struct
*
* @param msg The message to decode
* @param gimbal_torque_cmd_report C-struct to decode the message contents into
*/
static inline void mavlink_msg_gimbal_torque_cmd_report_decode(const mavlink_message_t* msg, mavlink_gimbal_torque_cmd_report_t* gimbal_torque_cmd_report)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
gimbal_torque_cmd_report->rl_torque_cmd = mavlink_msg_gimbal_torque_cmd_report_get_rl_torque_cmd(msg);
gimbal_torque_cmd_report->el_torque_cmd = mavlink_msg_gimbal_torque_cmd_report_get_el_torque_cmd(msg);
gimbal_torque_cmd_report->az_torque_cmd = mavlink_msg_gimbal_torque_cmd_report_get_az_torque_cmd(msg);
gimbal_torque_cmd_report->target_system = mavlink_msg_gimbal_torque_cmd_report_get_target_system(msg);
gimbal_torque_cmd_report->target_component = mavlink_msg_gimbal_torque_cmd_report_get_target_component(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_LEN? msg->len : MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_LEN;
memset(gimbal_torque_cmd_report, 0, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_LEN);
memcpy(gimbal_torque_cmd_report, _MAV_PAYLOAD(msg), len);
#endif
}

View File

@@ -0,0 +1,263 @@
#pragma once
// MESSAGE GOPRO_GET_REQUEST PACKING
#define MAVLINK_MSG_ID_GOPRO_GET_REQUEST 216
MAVPACKED(
typedef struct __mavlink_gopro_get_request_t {
uint8_t target_system; /*< System ID.*/
uint8_t target_component; /*< Component ID.*/
uint8_t cmd_id; /*< Command ID.*/
}) mavlink_gopro_get_request_t;
#define MAVLINK_MSG_ID_GOPRO_GET_REQUEST_LEN 3
#define MAVLINK_MSG_ID_GOPRO_GET_REQUEST_MIN_LEN 3
#define MAVLINK_MSG_ID_216_LEN 3
#define MAVLINK_MSG_ID_216_MIN_LEN 3
#define MAVLINK_MSG_ID_GOPRO_GET_REQUEST_CRC 50
#define MAVLINK_MSG_ID_216_CRC 50
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_GOPRO_GET_REQUEST { \
216, \
"GOPRO_GET_REQUEST", \
3, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_gopro_get_request_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_gopro_get_request_t, target_component) }, \
{ "cmd_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_gopro_get_request_t, cmd_id) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_GOPRO_GET_REQUEST { \
"GOPRO_GET_REQUEST", \
3, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_gopro_get_request_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_gopro_get_request_t, target_component) }, \
{ "cmd_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_gopro_get_request_t, cmd_id) }, \
} \
}
#endif
/**
* @brief Pack a gopro_get_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.
* @param cmd_id Command ID.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_gopro_get_request_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, uint8_t cmd_id)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_GOPRO_GET_REQUEST_LEN];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint8_t(buf, 2, cmd_id);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GOPRO_GET_REQUEST_LEN);
#else
mavlink_gopro_get_request_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.cmd_id = cmd_id;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GOPRO_GET_REQUEST_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_GOPRO_GET_REQUEST;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GOPRO_GET_REQUEST_MIN_LEN, MAVLINK_MSG_ID_GOPRO_GET_REQUEST_LEN, MAVLINK_MSG_ID_GOPRO_GET_REQUEST_CRC);
}
/**
* @brief Pack a gopro_get_request message on a channel
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID.
* @param target_component Component ID.
* @param cmd_id Command ID.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_gopro_get_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,uint8_t cmd_id)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_GOPRO_GET_REQUEST_LEN];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint8_t(buf, 2, cmd_id);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GOPRO_GET_REQUEST_LEN);
#else
mavlink_gopro_get_request_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.cmd_id = cmd_id;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GOPRO_GET_REQUEST_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_GOPRO_GET_REQUEST;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GOPRO_GET_REQUEST_MIN_LEN, MAVLINK_MSG_ID_GOPRO_GET_REQUEST_LEN, MAVLINK_MSG_ID_GOPRO_GET_REQUEST_CRC);
}
/**
* @brief Encode a gopro_get_request struct
*
* @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 gopro_get_request C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_gopro_get_request_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gopro_get_request_t* gopro_get_request)
{
return mavlink_msg_gopro_get_request_pack(system_id, component_id, msg, gopro_get_request->target_system, gopro_get_request->target_component, gopro_get_request->cmd_id);
}
/**
* @brief Encode a gopro_get_request struct on a channel
*
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param gopro_get_request C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_gopro_get_request_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gopro_get_request_t* gopro_get_request)
{
return mavlink_msg_gopro_get_request_pack_chan(system_id, component_id, chan, msg, gopro_get_request->target_system, gopro_get_request->target_component, gopro_get_request->cmd_id);
}
/**
* @brief Send a gopro_get_request message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID.
* @param target_component Component ID.
* @param cmd_id Command ID.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_gopro_get_request_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t cmd_id)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_GOPRO_GET_REQUEST_LEN];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint8_t(buf, 2, cmd_id);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GOPRO_GET_REQUEST, buf, MAVLINK_MSG_ID_GOPRO_GET_REQUEST_MIN_LEN, MAVLINK_MSG_ID_GOPRO_GET_REQUEST_LEN, MAVLINK_MSG_ID_GOPRO_GET_REQUEST_CRC);
#else
mavlink_gopro_get_request_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.cmd_id = cmd_id;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GOPRO_GET_REQUEST, (const char *)&packet, MAVLINK_MSG_ID_GOPRO_GET_REQUEST_MIN_LEN, MAVLINK_MSG_ID_GOPRO_GET_REQUEST_LEN, MAVLINK_MSG_ID_GOPRO_GET_REQUEST_CRC);
#endif
}
/**
* @brief Send a gopro_get_request message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_gopro_get_request_send_struct(mavlink_channel_t chan, const mavlink_gopro_get_request_t* gopro_get_request)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_gopro_get_request_send(chan, gopro_get_request->target_system, gopro_get_request->target_component, gopro_get_request->cmd_id);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GOPRO_GET_REQUEST, (const char *)gopro_get_request, MAVLINK_MSG_ID_GOPRO_GET_REQUEST_MIN_LEN, MAVLINK_MSG_ID_GOPRO_GET_REQUEST_LEN, MAVLINK_MSG_ID_GOPRO_GET_REQUEST_CRC);
#endif
}
#if MAVLINK_MSG_ID_GOPRO_GET_REQUEST_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_gopro_get_request_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t cmd_id)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint8_t(buf, 2, cmd_id);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GOPRO_GET_REQUEST, buf, MAVLINK_MSG_ID_GOPRO_GET_REQUEST_MIN_LEN, MAVLINK_MSG_ID_GOPRO_GET_REQUEST_LEN, MAVLINK_MSG_ID_GOPRO_GET_REQUEST_CRC);
#else
mavlink_gopro_get_request_t *packet = (mavlink_gopro_get_request_t *)msgbuf;
packet->target_system = target_system;
packet->target_component = target_component;
packet->cmd_id = cmd_id;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GOPRO_GET_REQUEST, (const char *)packet, MAVLINK_MSG_ID_GOPRO_GET_REQUEST_MIN_LEN, MAVLINK_MSG_ID_GOPRO_GET_REQUEST_LEN, MAVLINK_MSG_ID_GOPRO_GET_REQUEST_CRC);
#endif
}
#endif
#endif
// MESSAGE GOPRO_GET_REQUEST UNPACKING
/**
* @brief Get field target_system from gopro_get_request message
*
* @return System ID.
*/
static inline uint8_t mavlink_msg_gopro_get_request_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 0);
}
/**
* @brief Get field target_component from gopro_get_request message
*
* @return Component ID.
*/
static inline uint8_t mavlink_msg_gopro_get_request_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 1);
}
/**
* @brief Get field cmd_id from gopro_get_request message
*
* @return Command ID.
*/
static inline uint8_t mavlink_msg_gopro_get_request_get_cmd_id(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 2);
}
/**
* @brief Decode a gopro_get_request message into a struct
*
* @param msg The message to decode
* @param gopro_get_request C-struct to decode the message contents into
*/
static inline void mavlink_msg_gopro_get_request_decode(const mavlink_message_t* msg, mavlink_gopro_get_request_t* gopro_get_request)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
gopro_get_request->target_system = mavlink_msg_gopro_get_request_get_target_system(msg);
gopro_get_request->target_component = mavlink_msg_gopro_get_request_get_target_component(msg);
gopro_get_request->cmd_id = mavlink_msg_gopro_get_request_get_cmd_id(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_GOPRO_GET_REQUEST_LEN? msg->len : MAVLINK_MSG_ID_GOPRO_GET_REQUEST_LEN;
memset(gopro_get_request, 0, MAVLINK_MSG_ID_GOPRO_GET_REQUEST_LEN);
memcpy(gopro_get_request, _MAV_PAYLOAD(msg), len);
#endif
}

View File

@@ -0,0 +1,255 @@
#pragma once
// MESSAGE GOPRO_GET_RESPONSE PACKING
#define MAVLINK_MSG_ID_GOPRO_GET_RESPONSE 217
MAVPACKED(
typedef struct __mavlink_gopro_get_response_t {
uint8_t cmd_id; /*< Command ID.*/
uint8_t status; /*< Status.*/
uint8_t value[4]; /*< Value.*/
}) mavlink_gopro_get_response_t;
#define MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_LEN 6
#define MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_MIN_LEN 6
#define MAVLINK_MSG_ID_217_LEN 6
#define MAVLINK_MSG_ID_217_MIN_LEN 6
#define MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_CRC 202
#define MAVLINK_MSG_ID_217_CRC 202
#define MAVLINK_MSG_GOPRO_GET_RESPONSE_FIELD_VALUE_LEN 4
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_GOPRO_GET_RESPONSE { \
217, \
"GOPRO_GET_RESPONSE", \
3, \
{ { "cmd_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_gopro_get_response_t, cmd_id) }, \
{ "status", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_gopro_get_response_t, status) }, \
{ "value", NULL, MAVLINK_TYPE_UINT8_T, 4, 2, offsetof(mavlink_gopro_get_response_t, value) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_GOPRO_GET_RESPONSE { \
"GOPRO_GET_RESPONSE", \
3, \
{ { "cmd_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_gopro_get_response_t, cmd_id) }, \
{ "status", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_gopro_get_response_t, status) }, \
{ "value", NULL, MAVLINK_TYPE_UINT8_T, 4, 2, offsetof(mavlink_gopro_get_response_t, value) }, \
} \
}
#endif
/**
* @brief Pack a gopro_get_response message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param cmd_id Command ID.
* @param status Status.
* @param value Value.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_gopro_get_response_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t cmd_id, uint8_t status, const uint8_t *value)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_LEN];
_mav_put_uint8_t(buf, 0, cmd_id);
_mav_put_uint8_t(buf, 1, status);
_mav_put_uint8_t_array(buf, 2, value, 4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_LEN);
#else
mavlink_gopro_get_response_t packet;
packet.cmd_id = cmd_id;
packet.status = status;
mav_array_memcpy(packet.value, value, sizeof(uint8_t)*4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_GOPRO_GET_RESPONSE;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_MIN_LEN, MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_LEN, MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_CRC);
}
/**
* @brief Pack a gopro_get_response message on a channel
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param cmd_id Command ID.
* @param status Status.
* @param value Value.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_gopro_get_response_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint8_t cmd_id,uint8_t status,const uint8_t *value)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_LEN];
_mav_put_uint8_t(buf, 0, cmd_id);
_mav_put_uint8_t(buf, 1, status);
_mav_put_uint8_t_array(buf, 2, value, 4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_LEN);
#else
mavlink_gopro_get_response_t packet;
packet.cmd_id = cmd_id;
packet.status = status;
mav_array_memcpy(packet.value, value, sizeof(uint8_t)*4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_GOPRO_GET_RESPONSE;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_MIN_LEN, MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_LEN, MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_CRC);
}
/**
* @brief Encode a gopro_get_response struct
*
* @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 gopro_get_response C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_gopro_get_response_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gopro_get_response_t* gopro_get_response)
{
return mavlink_msg_gopro_get_response_pack(system_id, component_id, msg, gopro_get_response->cmd_id, gopro_get_response->status, gopro_get_response->value);
}
/**
* @brief Encode a gopro_get_response struct on a channel
*
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param gopro_get_response C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_gopro_get_response_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gopro_get_response_t* gopro_get_response)
{
return mavlink_msg_gopro_get_response_pack_chan(system_id, component_id, chan, msg, gopro_get_response->cmd_id, gopro_get_response->status, gopro_get_response->value);
}
/**
* @brief Send a gopro_get_response message
* @param chan MAVLink channel to send the message
*
* @param cmd_id Command ID.
* @param status Status.
* @param value Value.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_gopro_get_response_send(mavlink_channel_t chan, uint8_t cmd_id, uint8_t status, const uint8_t *value)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_LEN];
_mav_put_uint8_t(buf, 0, cmd_id);
_mav_put_uint8_t(buf, 1, status);
_mav_put_uint8_t_array(buf, 2, value, 4);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GOPRO_GET_RESPONSE, buf, MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_MIN_LEN, MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_LEN, MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_CRC);
#else
mavlink_gopro_get_response_t packet;
packet.cmd_id = cmd_id;
packet.status = status;
mav_array_memcpy(packet.value, value, sizeof(uint8_t)*4);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GOPRO_GET_RESPONSE, (const char *)&packet, MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_MIN_LEN, MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_LEN, MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_CRC);
#endif
}
/**
* @brief Send a gopro_get_response message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_gopro_get_response_send_struct(mavlink_channel_t chan, const mavlink_gopro_get_response_t* gopro_get_response)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_gopro_get_response_send(chan, gopro_get_response->cmd_id, gopro_get_response->status, gopro_get_response->value);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GOPRO_GET_RESPONSE, (const char *)gopro_get_response, MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_MIN_LEN, MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_LEN, MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_CRC);
#endif
}
#if MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_gopro_get_response_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t cmd_id, uint8_t status, const uint8_t *value)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint8_t(buf, 0, cmd_id);
_mav_put_uint8_t(buf, 1, status);
_mav_put_uint8_t_array(buf, 2, value, 4);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GOPRO_GET_RESPONSE, buf, MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_MIN_LEN, MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_LEN, MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_CRC);
#else
mavlink_gopro_get_response_t *packet = (mavlink_gopro_get_response_t *)msgbuf;
packet->cmd_id = cmd_id;
packet->status = status;
mav_array_memcpy(packet->value, value, sizeof(uint8_t)*4);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GOPRO_GET_RESPONSE, (const char *)packet, MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_MIN_LEN, MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_LEN, MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_CRC);
#endif
}
#endif
#endif
// MESSAGE GOPRO_GET_RESPONSE UNPACKING
/**
* @brief Get field cmd_id from gopro_get_response message
*
* @return Command ID.
*/
static inline uint8_t mavlink_msg_gopro_get_response_get_cmd_id(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 0);
}
/**
* @brief Get field status from gopro_get_response message
*
* @return Status.
*/
static inline uint8_t mavlink_msg_gopro_get_response_get_status(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 1);
}
/**
* @brief Get field value from gopro_get_response message
*
* @return Value.
*/
static inline uint16_t mavlink_msg_gopro_get_response_get_value(const mavlink_message_t* msg, uint8_t *value)
{
return _MAV_RETURN_uint8_t_array(msg, value, 4, 2);
}
/**
* @brief Decode a gopro_get_response message into a struct
*
* @param msg The message to decode
* @param gopro_get_response C-struct to decode the message contents into
*/
static inline void mavlink_msg_gopro_get_response_decode(const mavlink_message_t* msg, mavlink_gopro_get_response_t* gopro_get_response)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
gopro_get_response->cmd_id = mavlink_msg_gopro_get_response_get_cmd_id(msg);
gopro_get_response->status = mavlink_msg_gopro_get_response_get_status(msg);
mavlink_msg_gopro_get_response_get_value(msg, gopro_get_response->value);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_LEN? msg->len : MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_LEN;
memset(gopro_get_response, 0, MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_LEN);
memcpy(gopro_get_response, _MAV_PAYLOAD(msg), len);
#endif
}

View File

@@ -0,0 +1,263 @@
#pragma once
// MESSAGE GOPRO_HEARTBEAT PACKING
#define MAVLINK_MSG_ID_GOPRO_HEARTBEAT 215
MAVPACKED(
typedef struct __mavlink_gopro_heartbeat_t {
uint8_t status; /*< Status.*/
uint8_t capture_mode; /*< Current capture mode.*/
uint8_t flags; /*< Additional status bits.*/
}) mavlink_gopro_heartbeat_t;
#define MAVLINK_MSG_ID_GOPRO_HEARTBEAT_LEN 3
#define MAVLINK_MSG_ID_GOPRO_HEARTBEAT_MIN_LEN 3
#define MAVLINK_MSG_ID_215_LEN 3
#define MAVLINK_MSG_ID_215_MIN_LEN 3
#define MAVLINK_MSG_ID_GOPRO_HEARTBEAT_CRC 101
#define MAVLINK_MSG_ID_215_CRC 101
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_GOPRO_HEARTBEAT { \
215, \
"GOPRO_HEARTBEAT", \
3, \
{ { "status", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_gopro_heartbeat_t, status) }, \
{ "capture_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_gopro_heartbeat_t, capture_mode) }, \
{ "flags", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_gopro_heartbeat_t, flags) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_GOPRO_HEARTBEAT { \
"GOPRO_HEARTBEAT", \
3, \
{ { "status", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_gopro_heartbeat_t, status) }, \
{ "capture_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_gopro_heartbeat_t, capture_mode) }, \
{ "flags", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_gopro_heartbeat_t, flags) }, \
} \
}
#endif
/**
* @brief Pack a gopro_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 status Status.
* @param capture_mode Current capture mode.
* @param flags Additional status bits.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_gopro_heartbeat_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t status, uint8_t capture_mode, uint8_t flags)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_GOPRO_HEARTBEAT_LEN];
_mav_put_uint8_t(buf, 0, status);
_mav_put_uint8_t(buf, 1, capture_mode);
_mav_put_uint8_t(buf, 2, flags);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GOPRO_HEARTBEAT_LEN);
#else
mavlink_gopro_heartbeat_t packet;
packet.status = status;
packet.capture_mode = capture_mode;
packet.flags = flags;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GOPRO_HEARTBEAT_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_GOPRO_HEARTBEAT;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GOPRO_HEARTBEAT_MIN_LEN, MAVLINK_MSG_ID_GOPRO_HEARTBEAT_LEN, MAVLINK_MSG_ID_GOPRO_HEARTBEAT_CRC);
}
/**
* @brief Pack a gopro_heartbeat message on a channel
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param status Status.
* @param capture_mode Current capture mode.
* @param flags Additional status bits.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_gopro_heartbeat_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint8_t status,uint8_t capture_mode,uint8_t flags)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_GOPRO_HEARTBEAT_LEN];
_mav_put_uint8_t(buf, 0, status);
_mav_put_uint8_t(buf, 1, capture_mode);
_mav_put_uint8_t(buf, 2, flags);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GOPRO_HEARTBEAT_LEN);
#else
mavlink_gopro_heartbeat_t packet;
packet.status = status;
packet.capture_mode = capture_mode;
packet.flags = flags;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GOPRO_HEARTBEAT_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_GOPRO_HEARTBEAT;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GOPRO_HEARTBEAT_MIN_LEN, MAVLINK_MSG_ID_GOPRO_HEARTBEAT_LEN, MAVLINK_MSG_ID_GOPRO_HEARTBEAT_CRC);
}
/**
* @brief Encode a gopro_heartbeat struct
*
* @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 gopro_heartbeat C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_gopro_heartbeat_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gopro_heartbeat_t* gopro_heartbeat)
{
return mavlink_msg_gopro_heartbeat_pack(system_id, component_id, msg, gopro_heartbeat->status, gopro_heartbeat->capture_mode, gopro_heartbeat->flags);
}
/**
* @brief Encode a gopro_heartbeat struct on a channel
*
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param gopro_heartbeat C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_gopro_heartbeat_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gopro_heartbeat_t* gopro_heartbeat)
{
return mavlink_msg_gopro_heartbeat_pack_chan(system_id, component_id, chan, msg, gopro_heartbeat->status, gopro_heartbeat->capture_mode, gopro_heartbeat->flags);
}
/**
* @brief Send a gopro_heartbeat message
* @param chan MAVLink channel to send the message
*
* @param status Status.
* @param capture_mode Current capture mode.
* @param flags Additional status bits.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_gopro_heartbeat_send(mavlink_channel_t chan, uint8_t status, uint8_t capture_mode, uint8_t flags)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_GOPRO_HEARTBEAT_LEN];
_mav_put_uint8_t(buf, 0, status);
_mav_put_uint8_t(buf, 1, capture_mode);
_mav_put_uint8_t(buf, 2, flags);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GOPRO_HEARTBEAT, buf, MAVLINK_MSG_ID_GOPRO_HEARTBEAT_MIN_LEN, MAVLINK_MSG_ID_GOPRO_HEARTBEAT_LEN, MAVLINK_MSG_ID_GOPRO_HEARTBEAT_CRC);
#else
mavlink_gopro_heartbeat_t packet;
packet.status = status;
packet.capture_mode = capture_mode;
packet.flags = flags;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GOPRO_HEARTBEAT, (const char *)&packet, MAVLINK_MSG_ID_GOPRO_HEARTBEAT_MIN_LEN, MAVLINK_MSG_ID_GOPRO_HEARTBEAT_LEN, MAVLINK_MSG_ID_GOPRO_HEARTBEAT_CRC);
#endif
}
/**
* @brief Send a gopro_heartbeat message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_gopro_heartbeat_send_struct(mavlink_channel_t chan, const mavlink_gopro_heartbeat_t* gopro_heartbeat)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_gopro_heartbeat_send(chan, gopro_heartbeat->status, gopro_heartbeat->capture_mode, gopro_heartbeat->flags);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GOPRO_HEARTBEAT, (const char *)gopro_heartbeat, MAVLINK_MSG_ID_GOPRO_HEARTBEAT_MIN_LEN, MAVLINK_MSG_ID_GOPRO_HEARTBEAT_LEN, MAVLINK_MSG_ID_GOPRO_HEARTBEAT_CRC);
#endif
}
#if MAVLINK_MSG_ID_GOPRO_HEARTBEAT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_gopro_heartbeat_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t status, uint8_t capture_mode, uint8_t flags)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint8_t(buf, 0, status);
_mav_put_uint8_t(buf, 1, capture_mode);
_mav_put_uint8_t(buf, 2, flags);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GOPRO_HEARTBEAT, buf, MAVLINK_MSG_ID_GOPRO_HEARTBEAT_MIN_LEN, MAVLINK_MSG_ID_GOPRO_HEARTBEAT_LEN, MAVLINK_MSG_ID_GOPRO_HEARTBEAT_CRC);
#else
mavlink_gopro_heartbeat_t *packet = (mavlink_gopro_heartbeat_t *)msgbuf;
packet->status = status;
packet->capture_mode = capture_mode;
packet->flags = flags;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GOPRO_HEARTBEAT, (const char *)packet, MAVLINK_MSG_ID_GOPRO_HEARTBEAT_MIN_LEN, MAVLINK_MSG_ID_GOPRO_HEARTBEAT_LEN, MAVLINK_MSG_ID_GOPRO_HEARTBEAT_CRC);
#endif
}
#endif
#endif
// MESSAGE GOPRO_HEARTBEAT UNPACKING
/**
* @brief Get field status from gopro_heartbeat message
*
* @return Status.
*/
static inline uint8_t mavlink_msg_gopro_heartbeat_get_status(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 0);
}
/**
* @brief Get field capture_mode from gopro_heartbeat message
*
* @return Current capture mode.
*/
static inline uint8_t mavlink_msg_gopro_heartbeat_get_capture_mode(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 1);
}
/**
* @brief Get field flags from gopro_heartbeat message
*
* @return Additional status bits.
*/
static inline uint8_t mavlink_msg_gopro_heartbeat_get_flags(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 2);
}
/**
* @brief Decode a gopro_heartbeat message into a struct
*
* @param msg The message to decode
* @param gopro_heartbeat C-struct to decode the message contents into
*/
static inline void mavlink_msg_gopro_heartbeat_decode(const mavlink_message_t* msg, mavlink_gopro_heartbeat_t* gopro_heartbeat)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
gopro_heartbeat->status = mavlink_msg_gopro_heartbeat_get_status(msg);
gopro_heartbeat->capture_mode = mavlink_msg_gopro_heartbeat_get_capture_mode(msg);
gopro_heartbeat->flags = mavlink_msg_gopro_heartbeat_get_flags(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_GOPRO_HEARTBEAT_LEN? msg->len : MAVLINK_MSG_ID_GOPRO_HEARTBEAT_LEN;
memset(gopro_heartbeat, 0, MAVLINK_MSG_ID_GOPRO_HEARTBEAT_LEN);
memcpy(gopro_heartbeat, _MAV_PAYLOAD(msg), len);
#endif
}

View File

@@ -0,0 +1,280 @@
#pragma once
// MESSAGE GOPRO_SET_REQUEST PACKING
#define MAVLINK_MSG_ID_GOPRO_SET_REQUEST 218
MAVPACKED(
typedef struct __mavlink_gopro_set_request_t {
uint8_t target_system; /*< System ID.*/
uint8_t target_component; /*< Component ID.*/
uint8_t cmd_id; /*< Command ID.*/
uint8_t value[4]; /*< Value.*/
}) mavlink_gopro_set_request_t;
#define MAVLINK_MSG_ID_GOPRO_SET_REQUEST_LEN 7
#define MAVLINK_MSG_ID_GOPRO_SET_REQUEST_MIN_LEN 7
#define MAVLINK_MSG_ID_218_LEN 7
#define MAVLINK_MSG_ID_218_MIN_LEN 7
#define MAVLINK_MSG_ID_GOPRO_SET_REQUEST_CRC 17
#define MAVLINK_MSG_ID_218_CRC 17
#define MAVLINK_MSG_GOPRO_SET_REQUEST_FIELD_VALUE_LEN 4
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_GOPRO_SET_REQUEST { \
218, \
"GOPRO_SET_REQUEST", \
4, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_gopro_set_request_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_gopro_set_request_t, target_component) }, \
{ "cmd_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_gopro_set_request_t, cmd_id) }, \
{ "value", NULL, MAVLINK_TYPE_UINT8_T, 4, 3, offsetof(mavlink_gopro_set_request_t, value) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_GOPRO_SET_REQUEST { \
"GOPRO_SET_REQUEST", \
4, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_gopro_set_request_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_gopro_set_request_t, target_component) }, \
{ "cmd_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_gopro_set_request_t, cmd_id) }, \
{ "value", NULL, MAVLINK_TYPE_UINT8_T, 4, 3, offsetof(mavlink_gopro_set_request_t, value) }, \
} \
}
#endif
/**
* @brief Pack a gopro_set_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.
* @param cmd_id Command ID.
* @param value Value.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_gopro_set_request_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, uint8_t cmd_id, const uint8_t *value)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_GOPRO_SET_REQUEST_LEN];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint8_t(buf, 2, cmd_id);
_mav_put_uint8_t_array(buf, 3, value, 4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GOPRO_SET_REQUEST_LEN);
#else
mavlink_gopro_set_request_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.cmd_id = cmd_id;
mav_array_memcpy(packet.value, value, sizeof(uint8_t)*4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GOPRO_SET_REQUEST_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_GOPRO_SET_REQUEST;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GOPRO_SET_REQUEST_MIN_LEN, MAVLINK_MSG_ID_GOPRO_SET_REQUEST_LEN, MAVLINK_MSG_ID_GOPRO_SET_REQUEST_CRC);
}
/**
* @brief Pack a gopro_set_request message on a channel
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID.
* @param target_component Component ID.
* @param cmd_id Command ID.
* @param value Value.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_gopro_set_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,uint8_t cmd_id,const uint8_t *value)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_GOPRO_SET_REQUEST_LEN];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint8_t(buf, 2, cmd_id);
_mav_put_uint8_t_array(buf, 3, value, 4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GOPRO_SET_REQUEST_LEN);
#else
mavlink_gopro_set_request_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.cmd_id = cmd_id;
mav_array_memcpy(packet.value, value, sizeof(uint8_t)*4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GOPRO_SET_REQUEST_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_GOPRO_SET_REQUEST;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GOPRO_SET_REQUEST_MIN_LEN, MAVLINK_MSG_ID_GOPRO_SET_REQUEST_LEN, MAVLINK_MSG_ID_GOPRO_SET_REQUEST_CRC);
}
/**
* @brief Encode a gopro_set_request struct
*
* @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 gopro_set_request C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_gopro_set_request_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gopro_set_request_t* gopro_set_request)
{
return mavlink_msg_gopro_set_request_pack(system_id, component_id, msg, gopro_set_request->target_system, gopro_set_request->target_component, gopro_set_request->cmd_id, gopro_set_request->value);
}
/**
* @brief Encode a gopro_set_request struct on a channel
*
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param gopro_set_request C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_gopro_set_request_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gopro_set_request_t* gopro_set_request)
{
return mavlink_msg_gopro_set_request_pack_chan(system_id, component_id, chan, msg, gopro_set_request->target_system, gopro_set_request->target_component, gopro_set_request->cmd_id, gopro_set_request->value);
}
/**
* @brief Send a gopro_set_request message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID.
* @param target_component Component ID.
* @param cmd_id Command ID.
* @param value Value.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_gopro_set_request_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t cmd_id, const uint8_t *value)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_GOPRO_SET_REQUEST_LEN];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint8_t(buf, 2, cmd_id);
_mav_put_uint8_t_array(buf, 3, value, 4);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GOPRO_SET_REQUEST, buf, MAVLINK_MSG_ID_GOPRO_SET_REQUEST_MIN_LEN, MAVLINK_MSG_ID_GOPRO_SET_REQUEST_LEN, MAVLINK_MSG_ID_GOPRO_SET_REQUEST_CRC);
#else
mavlink_gopro_set_request_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.cmd_id = cmd_id;
mav_array_memcpy(packet.value, value, sizeof(uint8_t)*4);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GOPRO_SET_REQUEST, (const char *)&packet, MAVLINK_MSG_ID_GOPRO_SET_REQUEST_MIN_LEN, MAVLINK_MSG_ID_GOPRO_SET_REQUEST_LEN, MAVLINK_MSG_ID_GOPRO_SET_REQUEST_CRC);
#endif
}
/**
* @brief Send a gopro_set_request message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_gopro_set_request_send_struct(mavlink_channel_t chan, const mavlink_gopro_set_request_t* gopro_set_request)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_gopro_set_request_send(chan, gopro_set_request->target_system, gopro_set_request->target_component, gopro_set_request->cmd_id, gopro_set_request->value);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GOPRO_SET_REQUEST, (const char *)gopro_set_request, MAVLINK_MSG_ID_GOPRO_SET_REQUEST_MIN_LEN, MAVLINK_MSG_ID_GOPRO_SET_REQUEST_LEN, MAVLINK_MSG_ID_GOPRO_SET_REQUEST_CRC);
#endif
}
#if MAVLINK_MSG_ID_GOPRO_SET_REQUEST_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_gopro_set_request_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t cmd_id, const uint8_t *value)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint8_t(buf, 2, cmd_id);
_mav_put_uint8_t_array(buf, 3, value, 4);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GOPRO_SET_REQUEST, buf, MAVLINK_MSG_ID_GOPRO_SET_REQUEST_MIN_LEN, MAVLINK_MSG_ID_GOPRO_SET_REQUEST_LEN, MAVLINK_MSG_ID_GOPRO_SET_REQUEST_CRC);
#else
mavlink_gopro_set_request_t *packet = (mavlink_gopro_set_request_t *)msgbuf;
packet->target_system = target_system;
packet->target_component = target_component;
packet->cmd_id = cmd_id;
mav_array_memcpy(packet->value, value, sizeof(uint8_t)*4);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GOPRO_SET_REQUEST, (const char *)packet, MAVLINK_MSG_ID_GOPRO_SET_REQUEST_MIN_LEN, MAVLINK_MSG_ID_GOPRO_SET_REQUEST_LEN, MAVLINK_MSG_ID_GOPRO_SET_REQUEST_CRC);
#endif
}
#endif
#endif
// MESSAGE GOPRO_SET_REQUEST UNPACKING
/**
* @brief Get field target_system from gopro_set_request message
*
* @return System ID.
*/
static inline uint8_t mavlink_msg_gopro_set_request_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 0);
}
/**
* @brief Get field target_component from gopro_set_request message
*
* @return Component ID.
*/
static inline uint8_t mavlink_msg_gopro_set_request_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 1);
}
/**
* @brief Get field cmd_id from gopro_set_request message
*
* @return Command ID.
*/
static inline uint8_t mavlink_msg_gopro_set_request_get_cmd_id(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 2);
}
/**
* @brief Get field value from gopro_set_request message
*
* @return Value.
*/
static inline uint16_t mavlink_msg_gopro_set_request_get_value(const mavlink_message_t* msg, uint8_t *value)
{
return _MAV_RETURN_uint8_t_array(msg, value, 4, 3);
}
/**
* @brief Decode a gopro_set_request message into a struct
*
* @param msg The message to decode
* @param gopro_set_request C-struct to decode the message contents into
*/
static inline void mavlink_msg_gopro_set_request_decode(const mavlink_message_t* msg, mavlink_gopro_set_request_t* gopro_set_request)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
gopro_set_request->target_system = mavlink_msg_gopro_set_request_get_target_system(msg);
gopro_set_request->target_component = mavlink_msg_gopro_set_request_get_target_component(msg);
gopro_set_request->cmd_id = mavlink_msg_gopro_set_request_get_cmd_id(msg);
mavlink_msg_gopro_set_request_get_value(msg, gopro_set_request->value);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_GOPRO_SET_REQUEST_LEN? msg->len : MAVLINK_MSG_ID_GOPRO_SET_REQUEST_LEN;
memset(gopro_set_request, 0, MAVLINK_MSG_ID_GOPRO_SET_REQUEST_LEN);
memcpy(gopro_set_request, _MAV_PAYLOAD(msg), len);
#endif
}

View File

@@ -0,0 +1,238 @@
#pragma once
// MESSAGE GOPRO_SET_RESPONSE PACKING
#define MAVLINK_MSG_ID_GOPRO_SET_RESPONSE 219
MAVPACKED(
typedef struct __mavlink_gopro_set_response_t {
uint8_t cmd_id; /*< Command ID.*/
uint8_t status; /*< Status.*/
}) mavlink_gopro_set_response_t;
#define MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_LEN 2
#define MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_MIN_LEN 2
#define MAVLINK_MSG_ID_219_LEN 2
#define MAVLINK_MSG_ID_219_MIN_LEN 2
#define MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_CRC 162
#define MAVLINK_MSG_ID_219_CRC 162
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_GOPRO_SET_RESPONSE { \
219, \
"GOPRO_SET_RESPONSE", \
2, \
{ { "cmd_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_gopro_set_response_t, cmd_id) }, \
{ "status", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_gopro_set_response_t, status) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_GOPRO_SET_RESPONSE { \
"GOPRO_SET_RESPONSE", \
2, \
{ { "cmd_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_gopro_set_response_t, cmd_id) }, \
{ "status", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_gopro_set_response_t, status) }, \
} \
}
#endif
/**
* @brief Pack a gopro_set_response message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param cmd_id Command ID.
* @param status Status.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_gopro_set_response_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t cmd_id, uint8_t status)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_LEN];
_mav_put_uint8_t(buf, 0, cmd_id);
_mav_put_uint8_t(buf, 1, status);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_LEN);
#else
mavlink_gopro_set_response_t packet;
packet.cmd_id = cmd_id;
packet.status = status;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_GOPRO_SET_RESPONSE;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_MIN_LEN, MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_LEN, MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_CRC);
}
/**
* @brief Pack a gopro_set_response message on a channel
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param cmd_id Command ID.
* @param status Status.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_gopro_set_response_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint8_t cmd_id,uint8_t status)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_LEN];
_mav_put_uint8_t(buf, 0, cmd_id);
_mav_put_uint8_t(buf, 1, status);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_LEN);
#else
mavlink_gopro_set_response_t packet;
packet.cmd_id = cmd_id;
packet.status = status;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_GOPRO_SET_RESPONSE;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_MIN_LEN, MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_LEN, MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_CRC);
}
/**
* @brief Encode a gopro_set_response struct
*
* @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 gopro_set_response C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_gopro_set_response_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gopro_set_response_t* gopro_set_response)
{
return mavlink_msg_gopro_set_response_pack(system_id, component_id, msg, gopro_set_response->cmd_id, gopro_set_response->status);
}
/**
* @brief Encode a gopro_set_response struct on a channel
*
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param gopro_set_response C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_gopro_set_response_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gopro_set_response_t* gopro_set_response)
{
return mavlink_msg_gopro_set_response_pack_chan(system_id, component_id, chan, msg, gopro_set_response->cmd_id, gopro_set_response->status);
}
/**
* @brief Send a gopro_set_response message
* @param chan MAVLink channel to send the message
*
* @param cmd_id Command ID.
* @param status Status.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_gopro_set_response_send(mavlink_channel_t chan, uint8_t cmd_id, uint8_t status)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_LEN];
_mav_put_uint8_t(buf, 0, cmd_id);
_mav_put_uint8_t(buf, 1, status);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GOPRO_SET_RESPONSE, buf, MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_MIN_LEN, MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_LEN, MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_CRC);
#else
mavlink_gopro_set_response_t packet;
packet.cmd_id = cmd_id;
packet.status = status;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GOPRO_SET_RESPONSE, (const char *)&packet, MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_MIN_LEN, MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_LEN, MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_CRC);
#endif
}
/**
* @brief Send a gopro_set_response message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_gopro_set_response_send_struct(mavlink_channel_t chan, const mavlink_gopro_set_response_t* gopro_set_response)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_gopro_set_response_send(chan, gopro_set_response->cmd_id, gopro_set_response->status);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GOPRO_SET_RESPONSE, (const char *)gopro_set_response, MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_MIN_LEN, MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_LEN, MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_CRC);
#endif
}
#if MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_gopro_set_response_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t cmd_id, uint8_t status)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint8_t(buf, 0, cmd_id);
_mav_put_uint8_t(buf, 1, status);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GOPRO_SET_RESPONSE, buf, MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_MIN_LEN, MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_LEN, MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_CRC);
#else
mavlink_gopro_set_response_t *packet = (mavlink_gopro_set_response_t *)msgbuf;
packet->cmd_id = cmd_id;
packet->status = status;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GOPRO_SET_RESPONSE, (const char *)packet, MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_MIN_LEN, MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_LEN, MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_CRC);
#endif
}
#endif
#endif
// MESSAGE GOPRO_SET_RESPONSE UNPACKING
/**
* @brief Get field cmd_id from gopro_set_response message
*
* @return Command ID.
*/
static inline uint8_t mavlink_msg_gopro_set_response_get_cmd_id(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 0);
}
/**
* @brief Get field status from gopro_set_response message
*
* @return Status.
*/
static inline uint8_t mavlink_msg_gopro_set_response_get_status(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 1);
}
/**
* @brief Decode a gopro_set_response message into a struct
*
* @param msg The message to decode
* @param gopro_set_response C-struct to decode the message contents into
*/
static inline void mavlink_msg_gopro_set_response_decode(const mavlink_message_t* msg, mavlink_gopro_set_response_t* gopro_set_response)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
gopro_set_response->cmd_id = mavlink_msg_gopro_set_response_get_cmd_id(msg);
gopro_set_response->status = mavlink_msg_gopro_set_response_get_status(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_LEN? msg->len : MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_LEN;
memset(gopro_set_response, 0, MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_LEN);
memcpy(gopro_set_response, _MAV_PAYLOAD(msg), len);
#endif
}

View File

@@ -0,0 +1,238 @@
#pragma once
// MESSAGE HWSTATUS PACKING
#define MAVLINK_MSG_ID_HWSTATUS 165
MAVPACKED(
typedef struct __mavlink_hwstatus_t {
uint16_t Vcc; /*< [mV] Board voltage.*/
uint8_t I2Cerr; /*< I2C error count.*/
}) mavlink_hwstatus_t;
#define MAVLINK_MSG_ID_HWSTATUS_LEN 3
#define MAVLINK_MSG_ID_HWSTATUS_MIN_LEN 3
#define MAVLINK_MSG_ID_165_LEN 3
#define MAVLINK_MSG_ID_165_MIN_LEN 3
#define MAVLINK_MSG_ID_HWSTATUS_CRC 21
#define MAVLINK_MSG_ID_165_CRC 21
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_HWSTATUS { \
165, \
"HWSTATUS", \
2, \
{ { "Vcc", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_hwstatus_t, Vcc) }, \
{ "I2Cerr", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_hwstatus_t, I2Cerr) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_HWSTATUS { \
"HWSTATUS", \
2, \
{ { "Vcc", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_hwstatus_t, Vcc) }, \
{ "I2Cerr", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_hwstatus_t, I2Cerr) }, \
} \
}
#endif
/**
* @brief Pack a hwstatus 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 Vcc [mV] Board voltage.
* @param I2Cerr I2C error count.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_hwstatus_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint16_t Vcc, uint8_t I2Cerr)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_HWSTATUS_LEN];
_mav_put_uint16_t(buf, 0, Vcc);
_mav_put_uint8_t(buf, 2, I2Cerr);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HWSTATUS_LEN);
#else
mavlink_hwstatus_t packet;
packet.Vcc = Vcc;
packet.I2Cerr = I2Cerr;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HWSTATUS_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_HWSTATUS;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HWSTATUS_MIN_LEN, MAVLINK_MSG_ID_HWSTATUS_LEN, MAVLINK_MSG_ID_HWSTATUS_CRC);
}
/**
* @brief Pack a hwstatus message on a channel
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param Vcc [mV] Board voltage.
* @param I2Cerr I2C error count.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_hwstatus_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint16_t Vcc,uint8_t I2Cerr)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_HWSTATUS_LEN];
_mav_put_uint16_t(buf, 0, Vcc);
_mav_put_uint8_t(buf, 2, I2Cerr);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HWSTATUS_LEN);
#else
mavlink_hwstatus_t packet;
packet.Vcc = Vcc;
packet.I2Cerr = I2Cerr;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HWSTATUS_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_HWSTATUS;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HWSTATUS_MIN_LEN, MAVLINK_MSG_ID_HWSTATUS_LEN, MAVLINK_MSG_ID_HWSTATUS_CRC);
}
/**
* @brief Encode a hwstatus struct
*
* @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 hwstatus C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_hwstatus_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_hwstatus_t* hwstatus)
{
return mavlink_msg_hwstatus_pack(system_id, component_id, msg, hwstatus->Vcc, hwstatus->I2Cerr);
}
/**
* @brief Encode a hwstatus struct on a channel
*
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param hwstatus C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_hwstatus_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_hwstatus_t* hwstatus)
{
return mavlink_msg_hwstatus_pack_chan(system_id, component_id, chan, msg, hwstatus->Vcc, hwstatus->I2Cerr);
}
/**
* @brief Send a hwstatus message
* @param chan MAVLink channel to send the message
*
* @param Vcc [mV] Board voltage.
* @param I2Cerr I2C error count.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_hwstatus_send(mavlink_channel_t chan, uint16_t Vcc, uint8_t I2Cerr)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_HWSTATUS_LEN];
_mav_put_uint16_t(buf, 0, Vcc);
_mav_put_uint8_t(buf, 2, I2Cerr);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HWSTATUS, buf, MAVLINK_MSG_ID_HWSTATUS_MIN_LEN, MAVLINK_MSG_ID_HWSTATUS_LEN, MAVLINK_MSG_ID_HWSTATUS_CRC);
#else
mavlink_hwstatus_t packet;
packet.Vcc = Vcc;
packet.I2Cerr = I2Cerr;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HWSTATUS, (const char *)&packet, MAVLINK_MSG_ID_HWSTATUS_MIN_LEN, MAVLINK_MSG_ID_HWSTATUS_LEN, MAVLINK_MSG_ID_HWSTATUS_CRC);
#endif
}
/**
* @brief Send a hwstatus message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_hwstatus_send_struct(mavlink_channel_t chan, const mavlink_hwstatus_t* hwstatus)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_hwstatus_send(chan, hwstatus->Vcc, hwstatus->I2Cerr);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HWSTATUS, (const char *)hwstatus, MAVLINK_MSG_ID_HWSTATUS_MIN_LEN, MAVLINK_MSG_ID_HWSTATUS_LEN, MAVLINK_MSG_ID_HWSTATUS_CRC);
#endif
}
#if MAVLINK_MSG_ID_HWSTATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_hwstatus_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t Vcc, uint8_t I2Cerr)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint16_t(buf, 0, Vcc);
_mav_put_uint8_t(buf, 2, I2Cerr);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HWSTATUS, buf, MAVLINK_MSG_ID_HWSTATUS_MIN_LEN, MAVLINK_MSG_ID_HWSTATUS_LEN, MAVLINK_MSG_ID_HWSTATUS_CRC);
#else
mavlink_hwstatus_t *packet = (mavlink_hwstatus_t *)msgbuf;
packet->Vcc = Vcc;
packet->I2Cerr = I2Cerr;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HWSTATUS, (const char *)packet, MAVLINK_MSG_ID_HWSTATUS_MIN_LEN, MAVLINK_MSG_ID_HWSTATUS_LEN, MAVLINK_MSG_ID_HWSTATUS_CRC);
#endif
}
#endif
#endif
// MESSAGE HWSTATUS UNPACKING
/**
* @brief Get field Vcc from hwstatus message
*
* @return [mV] Board voltage.
*/
static inline uint16_t mavlink_msg_hwstatus_get_Vcc(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 0);
}
/**
* @brief Get field I2Cerr from hwstatus message
*
* @return I2C error count.
*/
static inline uint8_t mavlink_msg_hwstatus_get_I2Cerr(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 2);
}
/**
* @brief Decode a hwstatus message into a struct
*
* @param msg The message to decode
* @param hwstatus C-struct to decode the message contents into
*/
static inline void mavlink_msg_hwstatus_decode(const mavlink_message_t* msg, mavlink_hwstatus_t* hwstatus)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
hwstatus->Vcc = mavlink_msg_hwstatus_get_Vcc(msg);
hwstatus->I2Cerr = mavlink_msg_hwstatus_get_I2Cerr(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_HWSTATUS_LEN? msg->len : MAVLINK_MSG_ID_HWSTATUS_LEN;
memset(hwstatus, 0, MAVLINK_MSG_ID_HWSTATUS_LEN);
memcpy(hwstatus, _MAV_PAYLOAD(msg), len);
#endif
}

View File

@@ -0,0 +1,330 @@
#pragma once
// MESSAGE LED_CONTROL PACKING
#define MAVLINK_MSG_ID_LED_CONTROL 186
MAVPACKED(
typedef struct __mavlink_led_control_t {
uint8_t target_system; /*< System ID.*/
uint8_t target_component; /*< Component ID.*/
uint8_t instance; /*< Instance (LED instance to control or 255 for all LEDs).*/
uint8_t pattern; /*< Pattern (see LED_PATTERN_ENUM).*/
uint8_t custom_len; /*< Custom Byte Length.*/
uint8_t custom_bytes[24]; /*< Custom Bytes.*/
}) mavlink_led_control_t;
#define MAVLINK_MSG_ID_LED_CONTROL_LEN 29
#define MAVLINK_MSG_ID_LED_CONTROL_MIN_LEN 29
#define MAVLINK_MSG_ID_186_LEN 29
#define MAVLINK_MSG_ID_186_MIN_LEN 29
#define MAVLINK_MSG_ID_LED_CONTROL_CRC 72
#define MAVLINK_MSG_ID_186_CRC 72
#define MAVLINK_MSG_LED_CONTROL_FIELD_CUSTOM_BYTES_LEN 24
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_LED_CONTROL { \
186, \
"LED_CONTROL", \
6, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_led_control_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_led_control_t, target_component) }, \
{ "instance", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_led_control_t, instance) }, \
{ "pattern", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_led_control_t, pattern) }, \
{ "custom_len", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_led_control_t, custom_len) }, \
{ "custom_bytes", NULL, MAVLINK_TYPE_UINT8_T, 24, 5, offsetof(mavlink_led_control_t, custom_bytes) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_LED_CONTROL { \
"LED_CONTROL", \
6, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_led_control_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_led_control_t, target_component) }, \
{ "instance", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_led_control_t, instance) }, \
{ "pattern", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_led_control_t, pattern) }, \
{ "custom_len", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_led_control_t, custom_len) }, \
{ "custom_bytes", NULL, MAVLINK_TYPE_UINT8_T, 24, 5, offsetof(mavlink_led_control_t, custom_bytes) }, \
} \
}
#endif
/**
* @brief Pack a led_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_system System ID.
* @param target_component Component ID.
* @param instance Instance (LED instance to control or 255 for all LEDs).
* @param pattern Pattern (see LED_PATTERN_ENUM).
* @param custom_len Custom Byte Length.
* @param custom_bytes Custom Bytes.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_led_control_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, uint8_t instance, uint8_t pattern, uint8_t custom_len, const uint8_t *custom_bytes)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_LED_CONTROL_LEN];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint8_t(buf, 2, instance);
_mav_put_uint8_t(buf, 3, pattern);
_mav_put_uint8_t(buf, 4, custom_len);
_mav_put_uint8_t_array(buf, 5, custom_bytes, 24);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LED_CONTROL_LEN);
#else
mavlink_led_control_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.instance = instance;
packet.pattern = pattern;
packet.custom_len = custom_len;
mav_array_memcpy(packet.custom_bytes, custom_bytes, sizeof(uint8_t)*24);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LED_CONTROL_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_LED_CONTROL;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LED_CONTROL_MIN_LEN, MAVLINK_MSG_ID_LED_CONTROL_LEN, MAVLINK_MSG_ID_LED_CONTROL_CRC);
}
/**
* @brief Pack a led_control message on a channel
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID.
* @param target_component Component ID.
* @param instance Instance (LED instance to control or 255 for all LEDs).
* @param pattern Pattern (see LED_PATTERN_ENUM).
* @param custom_len Custom Byte Length.
* @param custom_bytes Custom Bytes.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_led_control_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 instance,uint8_t pattern,uint8_t custom_len,const uint8_t *custom_bytes)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_LED_CONTROL_LEN];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint8_t(buf, 2, instance);
_mav_put_uint8_t(buf, 3, pattern);
_mav_put_uint8_t(buf, 4, custom_len);
_mav_put_uint8_t_array(buf, 5, custom_bytes, 24);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LED_CONTROL_LEN);
#else
mavlink_led_control_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.instance = instance;
packet.pattern = pattern;
packet.custom_len = custom_len;
mav_array_memcpy(packet.custom_bytes, custom_bytes, sizeof(uint8_t)*24);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LED_CONTROL_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_LED_CONTROL;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LED_CONTROL_MIN_LEN, MAVLINK_MSG_ID_LED_CONTROL_LEN, MAVLINK_MSG_ID_LED_CONTROL_CRC);
}
/**
* @brief Encode a led_control struct
*
* @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 led_control C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_led_control_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_led_control_t* led_control)
{
return mavlink_msg_led_control_pack(system_id, component_id, msg, led_control->target_system, led_control->target_component, led_control->instance, led_control->pattern, led_control->custom_len, led_control->custom_bytes);
}
/**
* @brief Encode a led_control struct on a channel
*
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param led_control C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_led_control_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_led_control_t* led_control)
{
return mavlink_msg_led_control_pack_chan(system_id, component_id, chan, msg, led_control->target_system, led_control->target_component, led_control->instance, led_control->pattern, led_control->custom_len, led_control->custom_bytes);
}
/**
* @brief Send a led_control message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID.
* @param target_component Component ID.
* @param instance Instance (LED instance to control or 255 for all LEDs).
* @param pattern Pattern (see LED_PATTERN_ENUM).
* @param custom_len Custom Byte Length.
* @param custom_bytes Custom Bytes.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_led_control_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t instance, uint8_t pattern, uint8_t custom_len, const uint8_t *custom_bytes)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_LED_CONTROL_LEN];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint8_t(buf, 2, instance);
_mav_put_uint8_t(buf, 3, pattern);
_mav_put_uint8_t(buf, 4, custom_len);
_mav_put_uint8_t_array(buf, 5, custom_bytes, 24);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LED_CONTROL, buf, MAVLINK_MSG_ID_LED_CONTROL_MIN_LEN, MAVLINK_MSG_ID_LED_CONTROL_LEN, MAVLINK_MSG_ID_LED_CONTROL_CRC);
#else
mavlink_led_control_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.instance = instance;
packet.pattern = pattern;
packet.custom_len = custom_len;
mav_array_memcpy(packet.custom_bytes, custom_bytes, sizeof(uint8_t)*24);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LED_CONTROL, (const char *)&packet, MAVLINK_MSG_ID_LED_CONTROL_MIN_LEN, MAVLINK_MSG_ID_LED_CONTROL_LEN, MAVLINK_MSG_ID_LED_CONTROL_CRC);
#endif
}
/**
* @brief Send a led_control message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_led_control_send_struct(mavlink_channel_t chan, const mavlink_led_control_t* led_control)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_led_control_send(chan, led_control->target_system, led_control->target_component, led_control->instance, led_control->pattern, led_control->custom_len, led_control->custom_bytes);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LED_CONTROL, (const char *)led_control, MAVLINK_MSG_ID_LED_CONTROL_MIN_LEN, MAVLINK_MSG_ID_LED_CONTROL_LEN, MAVLINK_MSG_ID_LED_CONTROL_CRC);
#endif
}
#if MAVLINK_MSG_ID_LED_CONTROL_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_led_control_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t instance, uint8_t pattern, uint8_t custom_len, const uint8_t *custom_bytes)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint8_t(buf, 2, instance);
_mav_put_uint8_t(buf, 3, pattern);
_mav_put_uint8_t(buf, 4, custom_len);
_mav_put_uint8_t_array(buf, 5, custom_bytes, 24);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LED_CONTROL, buf, MAVLINK_MSG_ID_LED_CONTROL_MIN_LEN, MAVLINK_MSG_ID_LED_CONTROL_LEN, MAVLINK_MSG_ID_LED_CONTROL_CRC);
#else
mavlink_led_control_t *packet = (mavlink_led_control_t *)msgbuf;
packet->target_system = target_system;
packet->target_component = target_component;
packet->instance = instance;
packet->pattern = pattern;
packet->custom_len = custom_len;
mav_array_memcpy(packet->custom_bytes, custom_bytes, sizeof(uint8_t)*24);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LED_CONTROL, (const char *)packet, MAVLINK_MSG_ID_LED_CONTROL_MIN_LEN, MAVLINK_MSG_ID_LED_CONTROL_LEN, MAVLINK_MSG_ID_LED_CONTROL_CRC);
#endif
}
#endif
#endif
// MESSAGE LED_CONTROL UNPACKING
/**
* @brief Get field target_system from led_control message
*
* @return System ID.
*/
static inline uint8_t mavlink_msg_led_control_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 0);
}
/**
* @brief Get field target_component from led_control message
*
* @return Component ID.
*/
static inline uint8_t mavlink_msg_led_control_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 1);
}
/**
* @brief Get field instance from led_control message
*
* @return Instance (LED instance to control or 255 for all LEDs).
*/
static inline uint8_t mavlink_msg_led_control_get_instance(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 2);
}
/**
* @brief Get field pattern from led_control message
*
* @return Pattern (see LED_PATTERN_ENUM).
*/
static inline uint8_t mavlink_msg_led_control_get_pattern(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 3);
}
/**
* @brief Get field custom_len from led_control message
*
* @return Custom Byte Length.
*/
static inline uint8_t mavlink_msg_led_control_get_custom_len(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 4);
}
/**
* @brief Get field custom_bytes from led_control message
*
* @return Custom Bytes.
*/
static inline uint16_t mavlink_msg_led_control_get_custom_bytes(const mavlink_message_t* msg, uint8_t *custom_bytes)
{
return _MAV_RETURN_uint8_t_array(msg, custom_bytes, 24, 5);
}
/**
* @brief Decode a led_control message into a struct
*
* @param msg The message to decode
* @param led_control C-struct to decode the message contents into
*/
static inline void mavlink_msg_led_control_decode(const mavlink_message_t* msg, mavlink_led_control_t* led_control)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
led_control->target_system = mavlink_msg_led_control_get_target_system(msg);
led_control->target_component = mavlink_msg_led_control_get_target_component(msg);
led_control->instance = mavlink_msg_led_control_get_instance(msg);
led_control->pattern = mavlink_msg_led_control_get_pattern(msg);
led_control->custom_len = mavlink_msg_led_control_get_custom_len(msg);
mavlink_msg_led_control_get_custom_bytes(msg, led_control->custom_bytes);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_LED_CONTROL_LEN? msg->len : MAVLINK_MSG_ID_LED_CONTROL_LEN;
memset(led_control, 0, MAVLINK_MSG_ID_LED_CONTROL_LEN);
memcpy(led_control, _MAV_PAYLOAD(msg), len);
#endif
}

View File

@@ -0,0 +1,413 @@
#pragma once
// MESSAGE LIMITS_STATUS PACKING
#define MAVLINK_MSG_ID_LIMITS_STATUS 167
MAVPACKED(
typedef struct __mavlink_limits_status_t {
uint32_t last_trigger; /*< [ms] Time (since boot) of last breach.*/
uint32_t last_action; /*< [ms] Time (since boot) of last recovery action.*/
uint32_t last_recovery; /*< [ms] Time (since boot) of last successful recovery.*/
uint32_t last_clear; /*< [ms] Time (since boot) of last all-clear.*/
uint16_t breach_count; /*< Number of fence breaches.*/
uint8_t limits_state; /*< State of AP_Limits.*/
uint8_t mods_enabled; /*< AP_Limit_Module bitfield of enabled modules.*/
uint8_t mods_required; /*< AP_Limit_Module bitfield of required modules.*/
uint8_t mods_triggered; /*< AP_Limit_Module bitfield of triggered modules.*/
}) mavlink_limits_status_t;
#define MAVLINK_MSG_ID_LIMITS_STATUS_LEN 22
#define MAVLINK_MSG_ID_LIMITS_STATUS_MIN_LEN 22
#define MAVLINK_MSG_ID_167_LEN 22
#define MAVLINK_MSG_ID_167_MIN_LEN 22
#define MAVLINK_MSG_ID_LIMITS_STATUS_CRC 144
#define MAVLINK_MSG_ID_167_CRC 144
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_LIMITS_STATUS { \
167, \
"LIMITS_STATUS", \
9, \
{ { "limits_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 18, offsetof(mavlink_limits_status_t, limits_state) }, \
{ "last_trigger", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_limits_status_t, last_trigger) }, \
{ "last_action", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_limits_status_t, last_action) }, \
{ "last_recovery", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_limits_status_t, last_recovery) }, \
{ "last_clear", NULL, MAVLINK_TYPE_UINT32_T, 0, 12, offsetof(mavlink_limits_status_t, last_clear) }, \
{ "breach_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_limits_status_t, breach_count) }, \
{ "mods_enabled", NULL, MAVLINK_TYPE_UINT8_T, 0, 19, offsetof(mavlink_limits_status_t, mods_enabled) }, \
{ "mods_required", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_limits_status_t, mods_required) }, \
{ "mods_triggered", NULL, MAVLINK_TYPE_UINT8_T, 0, 21, offsetof(mavlink_limits_status_t, mods_triggered) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_LIMITS_STATUS { \
"LIMITS_STATUS", \
9, \
{ { "limits_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 18, offsetof(mavlink_limits_status_t, limits_state) }, \
{ "last_trigger", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_limits_status_t, last_trigger) }, \
{ "last_action", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_limits_status_t, last_action) }, \
{ "last_recovery", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_limits_status_t, last_recovery) }, \
{ "last_clear", NULL, MAVLINK_TYPE_UINT32_T, 0, 12, offsetof(mavlink_limits_status_t, last_clear) }, \
{ "breach_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_limits_status_t, breach_count) }, \
{ "mods_enabled", NULL, MAVLINK_TYPE_UINT8_T, 0, 19, offsetof(mavlink_limits_status_t, mods_enabled) }, \
{ "mods_required", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_limits_status_t, mods_required) }, \
{ "mods_triggered", NULL, MAVLINK_TYPE_UINT8_T, 0, 21, offsetof(mavlink_limits_status_t, mods_triggered) }, \
} \
}
#endif
/**
* @brief Pack a limits_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 limits_state State of AP_Limits.
* @param last_trigger [ms] Time (since boot) of last breach.
* @param last_action [ms] Time (since boot) of last recovery action.
* @param last_recovery [ms] Time (since boot) of last successful recovery.
* @param last_clear [ms] Time (since boot) of last all-clear.
* @param breach_count Number of fence breaches.
* @param mods_enabled AP_Limit_Module bitfield of enabled modules.
* @param mods_required AP_Limit_Module bitfield of required modules.
* @param mods_triggered AP_Limit_Module bitfield of triggered modules.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_limits_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t limits_state, uint32_t last_trigger, uint32_t last_action, uint32_t last_recovery, uint32_t last_clear, uint16_t breach_count, uint8_t mods_enabled, uint8_t mods_required, uint8_t mods_triggered)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_LIMITS_STATUS_LEN];
_mav_put_uint32_t(buf, 0, last_trigger);
_mav_put_uint32_t(buf, 4, last_action);
_mav_put_uint32_t(buf, 8, last_recovery);
_mav_put_uint32_t(buf, 12, last_clear);
_mav_put_uint16_t(buf, 16, breach_count);
_mav_put_uint8_t(buf, 18, limits_state);
_mav_put_uint8_t(buf, 19, mods_enabled);
_mav_put_uint8_t(buf, 20, mods_required);
_mav_put_uint8_t(buf, 21, mods_triggered);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LIMITS_STATUS_LEN);
#else
mavlink_limits_status_t packet;
packet.last_trigger = last_trigger;
packet.last_action = last_action;
packet.last_recovery = last_recovery;
packet.last_clear = last_clear;
packet.breach_count = breach_count;
packet.limits_state = limits_state;
packet.mods_enabled = mods_enabled;
packet.mods_required = mods_required;
packet.mods_triggered = mods_triggered;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LIMITS_STATUS_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_LIMITS_STATUS;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LIMITS_STATUS_MIN_LEN, MAVLINK_MSG_ID_LIMITS_STATUS_LEN, MAVLINK_MSG_ID_LIMITS_STATUS_CRC);
}
/**
* @brief Pack a limits_status message on a channel
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param limits_state State of AP_Limits.
* @param last_trigger [ms] Time (since boot) of last breach.
* @param last_action [ms] Time (since boot) of last recovery action.
* @param last_recovery [ms] Time (since boot) of last successful recovery.
* @param last_clear [ms] Time (since boot) of last all-clear.
* @param breach_count Number of fence breaches.
* @param mods_enabled AP_Limit_Module bitfield of enabled modules.
* @param mods_required AP_Limit_Module bitfield of required modules.
* @param mods_triggered AP_Limit_Module bitfield of triggered modules.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_limits_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint8_t limits_state,uint32_t last_trigger,uint32_t last_action,uint32_t last_recovery,uint32_t last_clear,uint16_t breach_count,uint8_t mods_enabled,uint8_t mods_required,uint8_t mods_triggered)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_LIMITS_STATUS_LEN];
_mav_put_uint32_t(buf, 0, last_trigger);
_mav_put_uint32_t(buf, 4, last_action);
_mav_put_uint32_t(buf, 8, last_recovery);
_mav_put_uint32_t(buf, 12, last_clear);
_mav_put_uint16_t(buf, 16, breach_count);
_mav_put_uint8_t(buf, 18, limits_state);
_mav_put_uint8_t(buf, 19, mods_enabled);
_mav_put_uint8_t(buf, 20, mods_required);
_mav_put_uint8_t(buf, 21, mods_triggered);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LIMITS_STATUS_LEN);
#else
mavlink_limits_status_t packet;
packet.last_trigger = last_trigger;
packet.last_action = last_action;
packet.last_recovery = last_recovery;
packet.last_clear = last_clear;
packet.breach_count = breach_count;
packet.limits_state = limits_state;
packet.mods_enabled = mods_enabled;
packet.mods_required = mods_required;
packet.mods_triggered = mods_triggered;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LIMITS_STATUS_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_LIMITS_STATUS;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LIMITS_STATUS_MIN_LEN, MAVLINK_MSG_ID_LIMITS_STATUS_LEN, MAVLINK_MSG_ID_LIMITS_STATUS_CRC);
}
/**
* @brief Encode a limits_status struct
*
* @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 limits_status C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_limits_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_limits_status_t* limits_status)
{
return mavlink_msg_limits_status_pack(system_id, component_id, msg, limits_status->limits_state, limits_status->last_trigger, limits_status->last_action, limits_status->last_recovery, limits_status->last_clear, limits_status->breach_count, limits_status->mods_enabled, limits_status->mods_required, limits_status->mods_triggered);
}
/**
* @brief Encode a limits_status struct on a channel
*
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param limits_status C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_limits_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_limits_status_t* limits_status)
{
return mavlink_msg_limits_status_pack_chan(system_id, component_id, chan, msg, limits_status->limits_state, limits_status->last_trigger, limits_status->last_action, limits_status->last_recovery, limits_status->last_clear, limits_status->breach_count, limits_status->mods_enabled, limits_status->mods_required, limits_status->mods_triggered);
}
/**
* @brief Send a limits_status message
* @param chan MAVLink channel to send the message
*
* @param limits_state State of AP_Limits.
* @param last_trigger [ms] Time (since boot) of last breach.
* @param last_action [ms] Time (since boot) of last recovery action.
* @param last_recovery [ms] Time (since boot) of last successful recovery.
* @param last_clear [ms] Time (since boot) of last all-clear.
* @param breach_count Number of fence breaches.
* @param mods_enabled AP_Limit_Module bitfield of enabled modules.
* @param mods_required AP_Limit_Module bitfield of required modules.
* @param mods_triggered AP_Limit_Module bitfield of triggered modules.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_limits_status_send(mavlink_channel_t chan, uint8_t limits_state, uint32_t last_trigger, uint32_t last_action, uint32_t last_recovery, uint32_t last_clear, uint16_t breach_count, uint8_t mods_enabled, uint8_t mods_required, uint8_t mods_triggered)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_LIMITS_STATUS_LEN];
_mav_put_uint32_t(buf, 0, last_trigger);
_mav_put_uint32_t(buf, 4, last_action);
_mav_put_uint32_t(buf, 8, last_recovery);
_mav_put_uint32_t(buf, 12, last_clear);
_mav_put_uint16_t(buf, 16, breach_count);
_mav_put_uint8_t(buf, 18, limits_state);
_mav_put_uint8_t(buf, 19, mods_enabled);
_mav_put_uint8_t(buf, 20, mods_required);
_mav_put_uint8_t(buf, 21, mods_triggered);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LIMITS_STATUS, buf, MAVLINK_MSG_ID_LIMITS_STATUS_MIN_LEN, MAVLINK_MSG_ID_LIMITS_STATUS_LEN, MAVLINK_MSG_ID_LIMITS_STATUS_CRC);
#else
mavlink_limits_status_t packet;
packet.last_trigger = last_trigger;
packet.last_action = last_action;
packet.last_recovery = last_recovery;
packet.last_clear = last_clear;
packet.breach_count = breach_count;
packet.limits_state = limits_state;
packet.mods_enabled = mods_enabled;
packet.mods_required = mods_required;
packet.mods_triggered = mods_triggered;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LIMITS_STATUS, (const char *)&packet, MAVLINK_MSG_ID_LIMITS_STATUS_MIN_LEN, MAVLINK_MSG_ID_LIMITS_STATUS_LEN, MAVLINK_MSG_ID_LIMITS_STATUS_CRC);
#endif
}
/**
* @brief Send a limits_status message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_limits_status_send_struct(mavlink_channel_t chan, const mavlink_limits_status_t* limits_status)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_limits_status_send(chan, limits_status->limits_state, limits_status->last_trigger, limits_status->last_action, limits_status->last_recovery, limits_status->last_clear, limits_status->breach_count, limits_status->mods_enabled, limits_status->mods_required, limits_status->mods_triggered);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LIMITS_STATUS, (const char *)limits_status, MAVLINK_MSG_ID_LIMITS_STATUS_MIN_LEN, MAVLINK_MSG_ID_LIMITS_STATUS_LEN, MAVLINK_MSG_ID_LIMITS_STATUS_CRC);
#endif
}
#if MAVLINK_MSG_ID_LIMITS_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_limits_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t limits_state, uint32_t last_trigger, uint32_t last_action, uint32_t last_recovery, uint32_t last_clear, uint16_t breach_count, uint8_t mods_enabled, uint8_t mods_required, uint8_t mods_triggered)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint32_t(buf, 0, last_trigger);
_mav_put_uint32_t(buf, 4, last_action);
_mav_put_uint32_t(buf, 8, last_recovery);
_mav_put_uint32_t(buf, 12, last_clear);
_mav_put_uint16_t(buf, 16, breach_count);
_mav_put_uint8_t(buf, 18, limits_state);
_mav_put_uint8_t(buf, 19, mods_enabled);
_mav_put_uint8_t(buf, 20, mods_required);
_mav_put_uint8_t(buf, 21, mods_triggered);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LIMITS_STATUS, buf, MAVLINK_MSG_ID_LIMITS_STATUS_MIN_LEN, MAVLINK_MSG_ID_LIMITS_STATUS_LEN, MAVLINK_MSG_ID_LIMITS_STATUS_CRC);
#else
mavlink_limits_status_t *packet = (mavlink_limits_status_t *)msgbuf;
packet->last_trigger = last_trigger;
packet->last_action = last_action;
packet->last_recovery = last_recovery;
packet->last_clear = last_clear;
packet->breach_count = breach_count;
packet->limits_state = limits_state;
packet->mods_enabled = mods_enabled;
packet->mods_required = mods_required;
packet->mods_triggered = mods_triggered;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LIMITS_STATUS, (const char *)packet, MAVLINK_MSG_ID_LIMITS_STATUS_MIN_LEN, MAVLINK_MSG_ID_LIMITS_STATUS_LEN, MAVLINK_MSG_ID_LIMITS_STATUS_CRC);
#endif
}
#endif
#endif
// MESSAGE LIMITS_STATUS UNPACKING
/**
* @brief Get field limits_state from limits_status message
*
* @return State of AP_Limits.
*/
static inline uint8_t mavlink_msg_limits_status_get_limits_state(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 18);
}
/**
* @brief Get field last_trigger from limits_status message
*
* @return [ms] Time (since boot) of last breach.
*/
static inline uint32_t mavlink_msg_limits_status_get_last_trigger(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 0);
}
/**
* @brief Get field last_action from limits_status message
*
* @return [ms] Time (since boot) of last recovery action.
*/
static inline uint32_t mavlink_msg_limits_status_get_last_action(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 4);
}
/**
* @brief Get field last_recovery from limits_status message
*
* @return [ms] Time (since boot) of last successful recovery.
*/
static inline uint32_t mavlink_msg_limits_status_get_last_recovery(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 8);
}
/**
* @brief Get field last_clear from limits_status message
*
* @return [ms] Time (since boot) of last all-clear.
*/
static inline uint32_t mavlink_msg_limits_status_get_last_clear(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 12);
}
/**
* @brief Get field breach_count from limits_status message
*
* @return Number of fence breaches.
*/
static inline uint16_t mavlink_msg_limits_status_get_breach_count(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 16);
}
/**
* @brief Get field mods_enabled from limits_status message
*
* @return AP_Limit_Module bitfield of enabled modules.
*/
static inline uint8_t mavlink_msg_limits_status_get_mods_enabled(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 19);
}
/**
* @brief Get field mods_required from limits_status message
*
* @return AP_Limit_Module bitfield of required modules.
*/
static inline uint8_t mavlink_msg_limits_status_get_mods_required(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 20);
}
/**
* @brief Get field mods_triggered from limits_status message
*
* @return AP_Limit_Module bitfield of triggered modules.
*/
static inline uint8_t mavlink_msg_limits_status_get_mods_triggered(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 21);
}
/**
* @brief Decode a limits_status message into a struct
*
* @param msg The message to decode
* @param limits_status C-struct to decode the message contents into
*/
static inline void mavlink_msg_limits_status_decode(const mavlink_message_t* msg, mavlink_limits_status_t* limits_status)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
limits_status->last_trigger = mavlink_msg_limits_status_get_last_trigger(msg);
limits_status->last_action = mavlink_msg_limits_status_get_last_action(msg);
limits_status->last_recovery = mavlink_msg_limits_status_get_last_recovery(msg);
limits_status->last_clear = mavlink_msg_limits_status_get_last_clear(msg);
limits_status->breach_count = mavlink_msg_limits_status_get_breach_count(msg);
limits_status->limits_state = mavlink_msg_limits_status_get_limits_state(msg);
limits_status->mods_enabled = mavlink_msg_limits_status_get_mods_enabled(msg);
limits_status->mods_required = mavlink_msg_limits_status_get_mods_required(msg);
limits_status->mods_triggered = mavlink_msg_limits_status_get_mods_triggered(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_LIMITS_STATUS_LEN? msg->len : MAVLINK_MSG_ID_LIMITS_STATUS_LEN;
memset(limits_status, 0, MAVLINK_MSG_ID_LIMITS_STATUS_LEN);
memcpy(limits_status, _MAV_PAYLOAD(msg), len);
#endif
}

View File

@@ -0,0 +1,405 @@
#pragma once
// MESSAGE MAG_CAL_PROGRESS PACKING
#define MAVLINK_MSG_ID_MAG_CAL_PROGRESS 191
MAVPACKED(
typedef struct __mavlink_mag_cal_progress_t {
float direction_x; /*< Body frame direction vector for display.*/
float direction_y; /*< Body frame direction vector for display.*/
float direction_z; /*< Body frame direction vector for display.*/
uint8_t compass_id; /*< Compass being calibrated.*/
uint8_t cal_mask; /*< Bitmask of compasses being calibrated.*/
uint8_t cal_status; /*< Calibration Status.*/
uint8_t attempt; /*< Attempt number.*/
uint8_t completion_pct; /*< [%] Completion percentage.*/
uint8_t completion_mask[10]; /*< Bitmask of sphere sections (see http://en.wikipedia.org/wiki/Geodesic_grid).*/
}) mavlink_mag_cal_progress_t;
#define MAVLINK_MSG_ID_MAG_CAL_PROGRESS_LEN 27
#define MAVLINK_MSG_ID_MAG_CAL_PROGRESS_MIN_LEN 27
#define MAVLINK_MSG_ID_191_LEN 27
#define MAVLINK_MSG_ID_191_MIN_LEN 27
#define MAVLINK_MSG_ID_MAG_CAL_PROGRESS_CRC 92
#define MAVLINK_MSG_ID_191_CRC 92
#define MAVLINK_MSG_MAG_CAL_PROGRESS_FIELD_COMPLETION_MASK_LEN 10
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_MAG_CAL_PROGRESS { \
191, \
"MAG_CAL_PROGRESS", \
9, \
{ { "compass_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_mag_cal_progress_t, compass_id) }, \
{ "cal_mask", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_mag_cal_progress_t, cal_mask) }, \
{ "cal_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 14, offsetof(mavlink_mag_cal_progress_t, cal_status) }, \
{ "attempt", NULL, MAVLINK_TYPE_UINT8_T, 0, 15, offsetof(mavlink_mag_cal_progress_t, attempt) }, \
{ "completion_pct", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_mag_cal_progress_t, completion_pct) }, \
{ "completion_mask", NULL, MAVLINK_TYPE_UINT8_T, 10, 17, offsetof(mavlink_mag_cal_progress_t, completion_mask) }, \
{ "direction_x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_mag_cal_progress_t, direction_x) }, \
{ "direction_y", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_mag_cal_progress_t, direction_y) }, \
{ "direction_z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_mag_cal_progress_t, direction_z) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_MAG_CAL_PROGRESS { \
"MAG_CAL_PROGRESS", \
9, \
{ { "compass_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_mag_cal_progress_t, compass_id) }, \
{ "cal_mask", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_mag_cal_progress_t, cal_mask) }, \
{ "cal_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 14, offsetof(mavlink_mag_cal_progress_t, cal_status) }, \
{ "attempt", NULL, MAVLINK_TYPE_UINT8_T, 0, 15, offsetof(mavlink_mag_cal_progress_t, attempt) }, \
{ "completion_pct", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_mag_cal_progress_t, completion_pct) }, \
{ "completion_mask", NULL, MAVLINK_TYPE_UINT8_T, 10, 17, offsetof(mavlink_mag_cal_progress_t, completion_mask) }, \
{ "direction_x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_mag_cal_progress_t, direction_x) }, \
{ "direction_y", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_mag_cal_progress_t, direction_y) }, \
{ "direction_z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_mag_cal_progress_t, direction_z) }, \
} \
}
#endif
/**
* @brief Pack a mag_cal_progress 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 compass_id Compass being calibrated.
* @param cal_mask Bitmask of compasses being calibrated.
* @param cal_status Calibration Status.
* @param attempt Attempt number.
* @param completion_pct [%] Completion percentage.
* @param completion_mask Bitmask of sphere sections (see http://en.wikipedia.org/wiki/Geodesic_grid).
* @param direction_x Body frame direction vector for display.
* @param direction_y Body frame direction vector for display.
* @param direction_z Body frame direction vector for display.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_mag_cal_progress_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t compass_id, uint8_t cal_mask, uint8_t cal_status, uint8_t attempt, uint8_t completion_pct, const uint8_t *completion_mask, float direction_x, float direction_y, float direction_z)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_MAG_CAL_PROGRESS_LEN];
_mav_put_float(buf, 0, direction_x);
_mav_put_float(buf, 4, direction_y);
_mav_put_float(buf, 8, direction_z);
_mav_put_uint8_t(buf, 12, compass_id);
_mav_put_uint8_t(buf, 13, cal_mask);
_mav_put_uint8_t(buf, 14, cal_status);
_mav_put_uint8_t(buf, 15, attempt);
_mav_put_uint8_t(buf, 16, completion_pct);
_mav_put_uint8_t_array(buf, 17, completion_mask, 10);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MAG_CAL_PROGRESS_LEN);
#else
mavlink_mag_cal_progress_t packet;
packet.direction_x = direction_x;
packet.direction_y = direction_y;
packet.direction_z = direction_z;
packet.compass_id = compass_id;
packet.cal_mask = cal_mask;
packet.cal_status = cal_status;
packet.attempt = attempt;
packet.completion_pct = completion_pct;
mav_array_memcpy(packet.completion_mask, completion_mask, sizeof(uint8_t)*10);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MAG_CAL_PROGRESS_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_MAG_CAL_PROGRESS;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MAG_CAL_PROGRESS_MIN_LEN, MAVLINK_MSG_ID_MAG_CAL_PROGRESS_LEN, MAVLINK_MSG_ID_MAG_CAL_PROGRESS_CRC);
}
/**
* @brief Pack a mag_cal_progress message on a channel
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param compass_id Compass being calibrated.
* @param cal_mask Bitmask of compasses being calibrated.
* @param cal_status Calibration Status.
* @param attempt Attempt number.
* @param completion_pct [%] Completion percentage.
* @param completion_mask Bitmask of sphere sections (see http://en.wikipedia.org/wiki/Geodesic_grid).
* @param direction_x Body frame direction vector for display.
* @param direction_y Body frame direction vector for display.
* @param direction_z Body frame direction vector for display.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_mag_cal_progress_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint8_t compass_id,uint8_t cal_mask,uint8_t cal_status,uint8_t attempt,uint8_t completion_pct,const uint8_t *completion_mask,float direction_x,float direction_y,float direction_z)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_MAG_CAL_PROGRESS_LEN];
_mav_put_float(buf, 0, direction_x);
_mav_put_float(buf, 4, direction_y);
_mav_put_float(buf, 8, direction_z);
_mav_put_uint8_t(buf, 12, compass_id);
_mav_put_uint8_t(buf, 13, cal_mask);
_mav_put_uint8_t(buf, 14, cal_status);
_mav_put_uint8_t(buf, 15, attempt);
_mav_put_uint8_t(buf, 16, completion_pct);
_mav_put_uint8_t_array(buf, 17, completion_mask, 10);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MAG_CAL_PROGRESS_LEN);
#else
mavlink_mag_cal_progress_t packet;
packet.direction_x = direction_x;
packet.direction_y = direction_y;
packet.direction_z = direction_z;
packet.compass_id = compass_id;
packet.cal_mask = cal_mask;
packet.cal_status = cal_status;
packet.attempt = attempt;
packet.completion_pct = completion_pct;
mav_array_memcpy(packet.completion_mask, completion_mask, sizeof(uint8_t)*10);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MAG_CAL_PROGRESS_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_MAG_CAL_PROGRESS;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MAG_CAL_PROGRESS_MIN_LEN, MAVLINK_MSG_ID_MAG_CAL_PROGRESS_LEN, MAVLINK_MSG_ID_MAG_CAL_PROGRESS_CRC);
}
/**
* @brief Encode a mag_cal_progress struct
*
* @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 mag_cal_progress C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_mag_cal_progress_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mag_cal_progress_t* mag_cal_progress)
{
return mavlink_msg_mag_cal_progress_pack(system_id, component_id, msg, mag_cal_progress->compass_id, mag_cal_progress->cal_mask, mag_cal_progress->cal_status, mag_cal_progress->attempt, mag_cal_progress->completion_pct, mag_cal_progress->completion_mask, mag_cal_progress->direction_x, mag_cal_progress->direction_y, mag_cal_progress->direction_z);
}
/**
* @brief Encode a mag_cal_progress struct on a channel
*
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param mag_cal_progress C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_mag_cal_progress_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mag_cal_progress_t* mag_cal_progress)
{
return mavlink_msg_mag_cal_progress_pack_chan(system_id, component_id, chan, msg, mag_cal_progress->compass_id, mag_cal_progress->cal_mask, mag_cal_progress->cal_status, mag_cal_progress->attempt, mag_cal_progress->completion_pct, mag_cal_progress->completion_mask, mag_cal_progress->direction_x, mag_cal_progress->direction_y, mag_cal_progress->direction_z);
}
/**
* @brief Send a mag_cal_progress message
* @param chan MAVLink channel to send the message
*
* @param compass_id Compass being calibrated.
* @param cal_mask Bitmask of compasses being calibrated.
* @param cal_status Calibration Status.
* @param attempt Attempt number.
* @param completion_pct [%] Completion percentage.
* @param completion_mask Bitmask of sphere sections (see http://en.wikipedia.org/wiki/Geodesic_grid).
* @param direction_x Body frame direction vector for display.
* @param direction_y Body frame direction vector for display.
* @param direction_z Body frame direction vector for display.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_mag_cal_progress_send(mavlink_channel_t chan, uint8_t compass_id, uint8_t cal_mask, uint8_t cal_status, uint8_t attempt, uint8_t completion_pct, const uint8_t *completion_mask, float direction_x, float direction_y, float direction_z)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_MAG_CAL_PROGRESS_LEN];
_mav_put_float(buf, 0, direction_x);
_mav_put_float(buf, 4, direction_y);
_mav_put_float(buf, 8, direction_z);
_mav_put_uint8_t(buf, 12, compass_id);
_mav_put_uint8_t(buf, 13, cal_mask);
_mav_put_uint8_t(buf, 14, cal_status);
_mav_put_uint8_t(buf, 15, attempt);
_mav_put_uint8_t(buf, 16, completion_pct);
_mav_put_uint8_t_array(buf, 17, completion_mask, 10);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MAG_CAL_PROGRESS, buf, MAVLINK_MSG_ID_MAG_CAL_PROGRESS_MIN_LEN, MAVLINK_MSG_ID_MAG_CAL_PROGRESS_LEN, MAVLINK_MSG_ID_MAG_CAL_PROGRESS_CRC);
#else
mavlink_mag_cal_progress_t packet;
packet.direction_x = direction_x;
packet.direction_y = direction_y;
packet.direction_z = direction_z;
packet.compass_id = compass_id;
packet.cal_mask = cal_mask;
packet.cal_status = cal_status;
packet.attempt = attempt;
packet.completion_pct = completion_pct;
mav_array_memcpy(packet.completion_mask, completion_mask, sizeof(uint8_t)*10);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MAG_CAL_PROGRESS, (const char *)&packet, MAVLINK_MSG_ID_MAG_CAL_PROGRESS_MIN_LEN, MAVLINK_MSG_ID_MAG_CAL_PROGRESS_LEN, MAVLINK_MSG_ID_MAG_CAL_PROGRESS_CRC);
#endif
}
/**
* @brief Send a mag_cal_progress message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_mag_cal_progress_send_struct(mavlink_channel_t chan, const mavlink_mag_cal_progress_t* mag_cal_progress)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_mag_cal_progress_send(chan, mag_cal_progress->compass_id, mag_cal_progress->cal_mask, mag_cal_progress->cal_status, mag_cal_progress->attempt, mag_cal_progress->completion_pct, mag_cal_progress->completion_mask, mag_cal_progress->direction_x, mag_cal_progress->direction_y, mag_cal_progress->direction_z);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MAG_CAL_PROGRESS, (const char *)mag_cal_progress, MAVLINK_MSG_ID_MAG_CAL_PROGRESS_MIN_LEN, MAVLINK_MSG_ID_MAG_CAL_PROGRESS_LEN, MAVLINK_MSG_ID_MAG_CAL_PROGRESS_CRC);
#endif
}
#if MAVLINK_MSG_ID_MAG_CAL_PROGRESS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_mag_cal_progress_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t compass_id, uint8_t cal_mask, uint8_t cal_status, uint8_t attempt, uint8_t completion_pct, const uint8_t *completion_mask, float direction_x, float direction_y, float direction_z)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_float(buf, 0, direction_x);
_mav_put_float(buf, 4, direction_y);
_mav_put_float(buf, 8, direction_z);
_mav_put_uint8_t(buf, 12, compass_id);
_mav_put_uint8_t(buf, 13, cal_mask);
_mav_put_uint8_t(buf, 14, cal_status);
_mav_put_uint8_t(buf, 15, attempt);
_mav_put_uint8_t(buf, 16, completion_pct);
_mav_put_uint8_t_array(buf, 17, completion_mask, 10);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MAG_CAL_PROGRESS, buf, MAVLINK_MSG_ID_MAG_CAL_PROGRESS_MIN_LEN, MAVLINK_MSG_ID_MAG_CAL_PROGRESS_LEN, MAVLINK_MSG_ID_MAG_CAL_PROGRESS_CRC);
#else
mavlink_mag_cal_progress_t *packet = (mavlink_mag_cal_progress_t *)msgbuf;
packet->direction_x = direction_x;
packet->direction_y = direction_y;
packet->direction_z = direction_z;
packet->compass_id = compass_id;
packet->cal_mask = cal_mask;
packet->cal_status = cal_status;
packet->attempt = attempt;
packet->completion_pct = completion_pct;
mav_array_memcpy(packet->completion_mask, completion_mask, sizeof(uint8_t)*10);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MAG_CAL_PROGRESS, (const char *)packet, MAVLINK_MSG_ID_MAG_CAL_PROGRESS_MIN_LEN, MAVLINK_MSG_ID_MAG_CAL_PROGRESS_LEN, MAVLINK_MSG_ID_MAG_CAL_PROGRESS_CRC);
#endif
}
#endif
#endif
// MESSAGE MAG_CAL_PROGRESS UNPACKING
/**
* @brief Get field compass_id from mag_cal_progress message
*
* @return Compass being calibrated.
*/
static inline uint8_t mavlink_msg_mag_cal_progress_get_compass_id(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 12);
}
/**
* @brief Get field cal_mask from mag_cal_progress message
*
* @return Bitmask of compasses being calibrated.
*/
static inline uint8_t mavlink_msg_mag_cal_progress_get_cal_mask(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 13);
}
/**
* @brief Get field cal_status from mag_cal_progress message
*
* @return Calibration Status.
*/
static inline uint8_t mavlink_msg_mag_cal_progress_get_cal_status(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 14);
}
/**
* @brief Get field attempt from mag_cal_progress message
*
* @return Attempt number.
*/
static inline uint8_t mavlink_msg_mag_cal_progress_get_attempt(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 15);
}
/**
* @brief Get field completion_pct from mag_cal_progress message
*
* @return [%] Completion percentage.
*/
static inline uint8_t mavlink_msg_mag_cal_progress_get_completion_pct(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 16);
}
/**
* @brief Get field completion_mask from mag_cal_progress message
*
* @return Bitmask of sphere sections (see http://en.wikipedia.org/wiki/Geodesic_grid).
*/
static inline uint16_t mavlink_msg_mag_cal_progress_get_completion_mask(const mavlink_message_t* msg, uint8_t *completion_mask)
{
return _MAV_RETURN_uint8_t_array(msg, completion_mask, 10, 17);
}
/**
* @brief Get field direction_x from mag_cal_progress message
*
* @return Body frame direction vector for display.
*/
static inline float mavlink_msg_mag_cal_progress_get_direction_x(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 0);
}
/**
* @brief Get field direction_y from mag_cal_progress message
*
* @return Body frame direction vector for display.
*/
static inline float mavlink_msg_mag_cal_progress_get_direction_y(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 4);
}
/**
* @brief Get field direction_z from mag_cal_progress message
*
* @return Body frame direction vector for display.
*/
static inline float mavlink_msg_mag_cal_progress_get_direction_z(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
/**
* @brief Decode a mag_cal_progress message into a struct
*
* @param msg The message to decode
* @param mag_cal_progress C-struct to decode the message contents into
*/
static inline void mavlink_msg_mag_cal_progress_decode(const mavlink_message_t* msg, mavlink_mag_cal_progress_t* mag_cal_progress)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mag_cal_progress->direction_x = mavlink_msg_mag_cal_progress_get_direction_x(msg);
mag_cal_progress->direction_y = mavlink_msg_mag_cal_progress_get_direction_y(msg);
mag_cal_progress->direction_z = mavlink_msg_mag_cal_progress_get_direction_z(msg);
mag_cal_progress->compass_id = mavlink_msg_mag_cal_progress_get_compass_id(msg);
mag_cal_progress->cal_mask = mavlink_msg_mag_cal_progress_get_cal_mask(msg);
mag_cal_progress->cal_status = mavlink_msg_mag_cal_progress_get_cal_status(msg);
mag_cal_progress->attempt = mavlink_msg_mag_cal_progress_get_attempt(msg);
mag_cal_progress->completion_pct = mavlink_msg_mag_cal_progress_get_completion_pct(msg);
mavlink_msg_mag_cal_progress_get_completion_mask(msg, mag_cal_progress->completion_mask);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_MAG_CAL_PROGRESS_LEN? msg->len : MAVLINK_MSG_ID_MAG_CAL_PROGRESS_LEN;
memset(mag_cal_progress, 0, MAVLINK_MSG_ID_MAG_CAL_PROGRESS_LEN);
memcpy(mag_cal_progress, _MAV_PAYLOAD(msg), len);
#endif
}

View File

@@ -0,0 +1,613 @@
#pragma once
// MESSAGE MAG_CAL_REPORT PACKING
#define MAVLINK_MSG_ID_MAG_CAL_REPORT 192
MAVPACKED(
typedef struct __mavlink_mag_cal_report_t {
float fitness; /*< [mgauss] RMS milligauss residuals.*/
float ofs_x; /*< X offset.*/
float ofs_y; /*< Y offset.*/
float ofs_z; /*< Z offset.*/
float diag_x; /*< X diagonal (matrix 11).*/
float diag_y; /*< Y diagonal (matrix 22).*/
float diag_z; /*< Z diagonal (matrix 33).*/
float offdiag_x; /*< X off-diagonal (matrix 12 and 21).*/
float offdiag_y; /*< Y off-diagonal (matrix 13 and 31).*/
float offdiag_z; /*< Z off-diagonal (matrix 32 and 23).*/
uint8_t compass_id; /*< Compass being calibrated.*/
uint8_t cal_mask; /*< Bitmask of compasses being calibrated.*/
uint8_t cal_status; /*< Calibration Status.*/
uint8_t autosaved; /*< 0=requires a MAV_CMD_DO_ACCEPT_MAG_CAL, 1=saved to parameters.*/
float orientation_confidence; /*< Confidence in orientation (higher is better).*/
uint8_t old_orientation; /*< orientation before calibration.*/
uint8_t new_orientation; /*< orientation after calibration.*/
}) mavlink_mag_cal_report_t;
#define MAVLINK_MSG_ID_MAG_CAL_REPORT_LEN 50
#define MAVLINK_MSG_ID_MAG_CAL_REPORT_MIN_LEN 44
#define MAVLINK_MSG_ID_192_LEN 50
#define MAVLINK_MSG_ID_192_MIN_LEN 44
#define MAVLINK_MSG_ID_MAG_CAL_REPORT_CRC 36
#define MAVLINK_MSG_ID_192_CRC 36
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_MAG_CAL_REPORT { \
192, \
"MAG_CAL_REPORT", \
17, \
{ { "compass_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 40, offsetof(mavlink_mag_cal_report_t, compass_id) }, \
{ "cal_mask", NULL, MAVLINK_TYPE_UINT8_T, 0, 41, offsetof(mavlink_mag_cal_report_t, cal_mask) }, \
{ "cal_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_mag_cal_report_t, cal_status) }, \
{ "autosaved", NULL, MAVLINK_TYPE_UINT8_T, 0, 43, offsetof(mavlink_mag_cal_report_t, autosaved) }, \
{ "fitness", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_mag_cal_report_t, fitness) }, \
{ "ofs_x", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_mag_cal_report_t, ofs_x) }, \
{ "ofs_y", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_mag_cal_report_t, ofs_y) }, \
{ "ofs_z", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_mag_cal_report_t, ofs_z) }, \
{ "diag_x", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_mag_cal_report_t, diag_x) }, \
{ "diag_y", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_mag_cal_report_t, diag_y) }, \
{ "diag_z", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_mag_cal_report_t, diag_z) }, \
{ "offdiag_x", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_mag_cal_report_t, offdiag_x) }, \
{ "offdiag_y", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_mag_cal_report_t, offdiag_y) }, \
{ "offdiag_z", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_mag_cal_report_t, offdiag_z) }, \
{ "orientation_confidence", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_mag_cal_report_t, orientation_confidence) }, \
{ "old_orientation", NULL, MAVLINK_TYPE_UINT8_T, 0, 48, offsetof(mavlink_mag_cal_report_t, old_orientation) }, \
{ "new_orientation", NULL, MAVLINK_TYPE_UINT8_T, 0, 49, offsetof(mavlink_mag_cal_report_t, new_orientation) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_MAG_CAL_REPORT { \
"MAG_CAL_REPORT", \
17, \
{ { "compass_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 40, offsetof(mavlink_mag_cal_report_t, compass_id) }, \
{ "cal_mask", NULL, MAVLINK_TYPE_UINT8_T, 0, 41, offsetof(mavlink_mag_cal_report_t, cal_mask) }, \
{ "cal_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_mag_cal_report_t, cal_status) }, \
{ "autosaved", NULL, MAVLINK_TYPE_UINT8_T, 0, 43, offsetof(mavlink_mag_cal_report_t, autosaved) }, \
{ "fitness", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_mag_cal_report_t, fitness) }, \
{ "ofs_x", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_mag_cal_report_t, ofs_x) }, \
{ "ofs_y", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_mag_cal_report_t, ofs_y) }, \
{ "ofs_z", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_mag_cal_report_t, ofs_z) }, \
{ "diag_x", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_mag_cal_report_t, diag_x) }, \
{ "diag_y", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_mag_cal_report_t, diag_y) }, \
{ "diag_z", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_mag_cal_report_t, diag_z) }, \
{ "offdiag_x", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_mag_cal_report_t, offdiag_x) }, \
{ "offdiag_y", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_mag_cal_report_t, offdiag_y) }, \
{ "offdiag_z", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_mag_cal_report_t, offdiag_z) }, \
{ "orientation_confidence", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_mag_cal_report_t, orientation_confidence) }, \
{ "old_orientation", NULL, MAVLINK_TYPE_UINT8_T, 0, 48, offsetof(mavlink_mag_cal_report_t, old_orientation) }, \
{ "new_orientation", NULL, MAVLINK_TYPE_UINT8_T, 0, 49, offsetof(mavlink_mag_cal_report_t, new_orientation) }, \
} \
}
#endif
/**
* @brief Pack a mag_cal_report 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 compass_id Compass being calibrated.
* @param cal_mask Bitmask of compasses being calibrated.
* @param cal_status Calibration Status.
* @param autosaved 0=requires a MAV_CMD_DO_ACCEPT_MAG_CAL, 1=saved to parameters.
* @param fitness [mgauss] RMS milligauss residuals.
* @param ofs_x X offset.
* @param ofs_y Y offset.
* @param ofs_z Z offset.
* @param diag_x X diagonal (matrix 11).
* @param diag_y Y diagonal (matrix 22).
* @param diag_z Z diagonal (matrix 33).
* @param offdiag_x X off-diagonal (matrix 12 and 21).
* @param offdiag_y Y off-diagonal (matrix 13 and 31).
* @param offdiag_z Z off-diagonal (matrix 32 and 23).
* @param orientation_confidence Confidence in orientation (higher is better).
* @param old_orientation orientation before calibration.
* @param new_orientation orientation after calibration.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_mag_cal_report_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t compass_id, uint8_t cal_mask, uint8_t cal_status, uint8_t autosaved, float fitness, float ofs_x, float ofs_y, float ofs_z, float diag_x, float diag_y, float diag_z, float offdiag_x, float offdiag_y, float offdiag_z, float orientation_confidence, uint8_t old_orientation, uint8_t new_orientation)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_MAG_CAL_REPORT_LEN];
_mav_put_float(buf, 0, fitness);
_mav_put_float(buf, 4, ofs_x);
_mav_put_float(buf, 8, ofs_y);
_mav_put_float(buf, 12, ofs_z);
_mav_put_float(buf, 16, diag_x);
_mav_put_float(buf, 20, diag_y);
_mav_put_float(buf, 24, diag_z);
_mav_put_float(buf, 28, offdiag_x);
_mav_put_float(buf, 32, offdiag_y);
_mav_put_float(buf, 36, offdiag_z);
_mav_put_uint8_t(buf, 40, compass_id);
_mav_put_uint8_t(buf, 41, cal_mask);
_mav_put_uint8_t(buf, 42, cal_status);
_mav_put_uint8_t(buf, 43, autosaved);
_mav_put_float(buf, 44, orientation_confidence);
_mav_put_uint8_t(buf, 48, old_orientation);
_mav_put_uint8_t(buf, 49, new_orientation);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MAG_CAL_REPORT_LEN);
#else
mavlink_mag_cal_report_t packet;
packet.fitness = fitness;
packet.ofs_x = ofs_x;
packet.ofs_y = ofs_y;
packet.ofs_z = ofs_z;
packet.diag_x = diag_x;
packet.diag_y = diag_y;
packet.diag_z = diag_z;
packet.offdiag_x = offdiag_x;
packet.offdiag_y = offdiag_y;
packet.offdiag_z = offdiag_z;
packet.compass_id = compass_id;
packet.cal_mask = cal_mask;
packet.cal_status = cal_status;
packet.autosaved = autosaved;
packet.orientation_confidence = orientation_confidence;
packet.old_orientation = old_orientation;
packet.new_orientation = new_orientation;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MAG_CAL_REPORT_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_MAG_CAL_REPORT;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MAG_CAL_REPORT_MIN_LEN, MAVLINK_MSG_ID_MAG_CAL_REPORT_LEN, MAVLINK_MSG_ID_MAG_CAL_REPORT_CRC);
}
/**
* @brief Pack a mag_cal_report message on a channel
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param compass_id Compass being calibrated.
* @param cal_mask Bitmask of compasses being calibrated.
* @param cal_status Calibration Status.
* @param autosaved 0=requires a MAV_CMD_DO_ACCEPT_MAG_CAL, 1=saved to parameters.
* @param fitness [mgauss] RMS milligauss residuals.
* @param ofs_x X offset.
* @param ofs_y Y offset.
* @param ofs_z Z offset.
* @param diag_x X diagonal (matrix 11).
* @param diag_y Y diagonal (matrix 22).
* @param diag_z Z diagonal (matrix 33).
* @param offdiag_x X off-diagonal (matrix 12 and 21).
* @param offdiag_y Y off-diagonal (matrix 13 and 31).
* @param offdiag_z Z off-diagonal (matrix 32 and 23).
* @param orientation_confidence Confidence in orientation (higher is better).
* @param old_orientation orientation before calibration.
* @param new_orientation orientation after calibration.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_mag_cal_report_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint8_t compass_id,uint8_t cal_mask,uint8_t cal_status,uint8_t autosaved,float fitness,float ofs_x,float ofs_y,float ofs_z,float diag_x,float diag_y,float diag_z,float offdiag_x,float offdiag_y,float offdiag_z,float orientation_confidence,uint8_t old_orientation,uint8_t new_orientation)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_MAG_CAL_REPORT_LEN];
_mav_put_float(buf, 0, fitness);
_mav_put_float(buf, 4, ofs_x);
_mav_put_float(buf, 8, ofs_y);
_mav_put_float(buf, 12, ofs_z);
_mav_put_float(buf, 16, diag_x);
_mav_put_float(buf, 20, diag_y);
_mav_put_float(buf, 24, diag_z);
_mav_put_float(buf, 28, offdiag_x);
_mav_put_float(buf, 32, offdiag_y);
_mav_put_float(buf, 36, offdiag_z);
_mav_put_uint8_t(buf, 40, compass_id);
_mav_put_uint8_t(buf, 41, cal_mask);
_mav_put_uint8_t(buf, 42, cal_status);
_mav_put_uint8_t(buf, 43, autosaved);
_mav_put_float(buf, 44, orientation_confidence);
_mav_put_uint8_t(buf, 48, old_orientation);
_mav_put_uint8_t(buf, 49, new_orientation);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MAG_CAL_REPORT_LEN);
#else
mavlink_mag_cal_report_t packet;
packet.fitness = fitness;
packet.ofs_x = ofs_x;
packet.ofs_y = ofs_y;
packet.ofs_z = ofs_z;
packet.diag_x = diag_x;
packet.diag_y = diag_y;
packet.diag_z = diag_z;
packet.offdiag_x = offdiag_x;
packet.offdiag_y = offdiag_y;
packet.offdiag_z = offdiag_z;
packet.compass_id = compass_id;
packet.cal_mask = cal_mask;
packet.cal_status = cal_status;
packet.autosaved = autosaved;
packet.orientation_confidence = orientation_confidence;
packet.old_orientation = old_orientation;
packet.new_orientation = new_orientation;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MAG_CAL_REPORT_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_MAG_CAL_REPORT;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MAG_CAL_REPORT_MIN_LEN, MAVLINK_MSG_ID_MAG_CAL_REPORT_LEN, MAVLINK_MSG_ID_MAG_CAL_REPORT_CRC);
}
/**
* @brief Encode a mag_cal_report struct
*
* @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 mag_cal_report C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_mag_cal_report_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mag_cal_report_t* mag_cal_report)
{
return mavlink_msg_mag_cal_report_pack(system_id, component_id, msg, mag_cal_report->compass_id, mag_cal_report->cal_mask, mag_cal_report->cal_status, mag_cal_report->autosaved, mag_cal_report->fitness, mag_cal_report->ofs_x, mag_cal_report->ofs_y, mag_cal_report->ofs_z, mag_cal_report->diag_x, mag_cal_report->diag_y, mag_cal_report->diag_z, mag_cal_report->offdiag_x, mag_cal_report->offdiag_y, mag_cal_report->offdiag_z, mag_cal_report->orientation_confidence, mag_cal_report->old_orientation, mag_cal_report->new_orientation);
}
/**
* @brief Encode a mag_cal_report struct on a channel
*
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param mag_cal_report C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_mag_cal_report_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mag_cal_report_t* mag_cal_report)
{
return mavlink_msg_mag_cal_report_pack_chan(system_id, component_id, chan, msg, mag_cal_report->compass_id, mag_cal_report->cal_mask, mag_cal_report->cal_status, mag_cal_report->autosaved, mag_cal_report->fitness, mag_cal_report->ofs_x, mag_cal_report->ofs_y, mag_cal_report->ofs_z, mag_cal_report->diag_x, mag_cal_report->diag_y, mag_cal_report->diag_z, mag_cal_report->offdiag_x, mag_cal_report->offdiag_y, mag_cal_report->offdiag_z, mag_cal_report->orientation_confidence, mag_cal_report->old_orientation, mag_cal_report->new_orientation);
}
/**
* @brief Send a mag_cal_report message
* @param chan MAVLink channel to send the message
*
* @param compass_id Compass being calibrated.
* @param cal_mask Bitmask of compasses being calibrated.
* @param cal_status Calibration Status.
* @param autosaved 0=requires a MAV_CMD_DO_ACCEPT_MAG_CAL, 1=saved to parameters.
* @param fitness [mgauss] RMS milligauss residuals.
* @param ofs_x X offset.
* @param ofs_y Y offset.
* @param ofs_z Z offset.
* @param diag_x X diagonal (matrix 11).
* @param diag_y Y diagonal (matrix 22).
* @param diag_z Z diagonal (matrix 33).
* @param offdiag_x X off-diagonal (matrix 12 and 21).
* @param offdiag_y Y off-diagonal (matrix 13 and 31).
* @param offdiag_z Z off-diagonal (matrix 32 and 23).
* @param orientation_confidence Confidence in orientation (higher is better).
* @param old_orientation orientation before calibration.
* @param new_orientation orientation after calibration.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_mag_cal_report_send(mavlink_channel_t chan, uint8_t compass_id, uint8_t cal_mask, uint8_t cal_status, uint8_t autosaved, float fitness, float ofs_x, float ofs_y, float ofs_z, float diag_x, float diag_y, float diag_z, float offdiag_x, float offdiag_y, float offdiag_z, float orientation_confidence, uint8_t old_orientation, uint8_t new_orientation)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_MAG_CAL_REPORT_LEN];
_mav_put_float(buf, 0, fitness);
_mav_put_float(buf, 4, ofs_x);
_mav_put_float(buf, 8, ofs_y);
_mav_put_float(buf, 12, ofs_z);
_mav_put_float(buf, 16, diag_x);
_mav_put_float(buf, 20, diag_y);
_mav_put_float(buf, 24, diag_z);
_mav_put_float(buf, 28, offdiag_x);
_mav_put_float(buf, 32, offdiag_y);
_mav_put_float(buf, 36, offdiag_z);
_mav_put_uint8_t(buf, 40, compass_id);
_mav_put_uint8_t(buf, 41, cal_mask);
_mav_put_uint8_t(buf, 42, cal_status);
_mav_put_uint8_t(buf, 43, autosaved);
_mav_put_float(buf, 44, orientation_confidence);
_mav_put_uint8_t(buf, 48, old_orientation);
_mav_put_uint8_t(buf, 49, new_orientation);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MAG_CAL_REPORT, buf, MAVLINK_MSG_ID_MAG_CAL_REPORT_MIN_LEN, MAVLINK_MSG_ID_MAG_CAL_REPORT_LEN, MAVLINK_MSG_ID_MAG_CAL_REPORT_CRC);
#else
mavlink_mag_cal_report_t packet;
packet.fitness = fitness;
packet.ofs_x = ofs_x;
packet.ofs_y = ofs_y;
packet.ofs_z = ofs_z;
packet.diag_x = diag_x;
packet.diag_y = diag_y;
packet.diag_z = diag_z;
packet.offdiag_x = offdiag_x;
packet.offdiag_y = offdiag_y;
packet.offdiag_z = offdiag_z;
packet.compass_id = compass_id;
packet.cal_mask = cal_mask;
packet.cal_status = cal_status;
packet.autosaved = autosaved;
packet.orientation_confidence = orientation_confidence;
packet.old_orientation = old_orientation;
packet.new_orientation = new_orientation;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MAG_CAL_REPORT, (const char *)&packet, MAVLINK_MSG_ID_MAG_CAL_REPORT_MIN_LEN, MAVLINK_MSG_ID_MAG_CAL_REPORT_LEN, MAVLINK_MSG_ID_MAG_CAL_REPORT_CRC);
#endif
}
/**
* @brief Send a mag_cal_report message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_mag_cal_report_send_struct(mavlink_channel_t chan, const mavlink_mag_cal_report_t* mag_cal_report)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_mag_cal_report_send(chan, mag_cal_report->compass_id, mag_cal_report->cal_mask, mag_cal_report->cal_status, mag_cal_report->autosaved, mag_cal_report->fitness, mag_cal_report->ofs_x, mag_cal_report->ofs_y, mag_cal_report->ofs_z, mag_cal_report->diag_x, mag_cal_report->diag_y, mag_cal_report->diag_z, mag_cal_report->offdiag_x, mag_cal_report->offdiag_y, mag_cal_report->offdiag_z, mag_cal_report->orientation_confidence, mag_cal_report->old_orientation, mag_cal_report->new_orientation);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MAG_CAL_REPORT, (const char *)mag_cal_report, MAVLINK_MSG_ID_MAG_CAL_REPORT_MIN_LEN, MAVLINK_MSG_ID_MAG_CAL_REPORT_LEN, MAVLINK_MSG_ID_MAG_CAL_REPORT_CRC);
#endif
}
#if MAVLINK_MSG_ID_MAG_CAL_REPORT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_mag_cal_report_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t compass_id, uint8_t cal_mask, uint8_t cal_status, uint8_t autosaved, float fitness, float ofs_x, float ofs_y, float ofs_z, float diag_x, float diag_y, float diag_z, float offdiag_x, float offdiag_y, float offdiag_z, float orientation_confidence, uint8_t old_orientation, uint8_t new_orientation)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_float(buf, 0, fitness);
_mav_put_float(buf, 4, ofs_x);
_mav_put_float(buf, 8, ofs_y);
_mav_put_float(buf, 12, ofs_z);
_mav_put_float(buf, 16, diag_x);
_mav_put_float(buf, 20, diag_y);
_mav_put_float(buf, 24, diag_z);
_mav_put_float(buf, 28, offdiag_x);
_mav_put_float(buf, 32, offdiag_y);
_mav_put_float(buf, 36, offdiag_z);
_mav_put_uint8_t(buf, 40, compass_id);
_mav_put_uint8_t(buf, 41, cal_mask);
_mav_put_uint8_t(buf, 42, cal_status);
_mav_put_uint8_t(buf, 43, autosaved);
_mav_put_float(buf, 44, orientation_confidence);
_mav_put_uint8_t(buf, 48, old_orientation);
_mav_put_uint8_t(buf, 49, new_orientation);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MAG_CAL_REPORT, buf, MAVLINK_MSG_ID_MAG_CAL_REPORT_MIN_LEN, MAVLINK_MSG_ID_MAG_CAL_REPORT_LEN, MAVLINK_MSG_ID_MAG_CAL_REPORT_CRC);
#else
mavlink_mag_cal_report_t *packet = (mavlink_mag_cal_report_t *)msgbuf;
packet->fitness = fitness;
packet->ofs_x = ofs_x;
packet->ofs_y = ofs_y;
packet->ofs_z = ofs_z;
packet->diag_x = diag_x;
packet->diag_y = diag_y;
packet->diag_z = diag_z;
packet->offdiag_x = offdiag_x;
packet->offdiag_y = offdiag_y;
packet->offdiag_z = offdiag_z;
packet->compass_id = compass_id;
packet->cal_mask = cal_mask;
packet->cal_status = cal_status;
packet->autosaved = autosaved;
packet->orientation_confidence = orientation_confidence;
packet->old_orientation = old_orientation;
packet->new_orientation = new_orientation;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MAG_CAL_REPORT, (const char *)packet, MAVLINK_MSG_ID_MAG_CAL_REPORT_MIN_LEN, MAVLINK_MSG_ID_MAG_CAL_REPORT_LEN, MAVLINK_MSG_ID_MAG_CAL_REPORT_CRC);
#endif
}
#endif
#endif
// MESSAGE MAG_CAL_REPORT UNPACKING
/**
* @brief Get field compass_id from mag_cal_report message
*
* @return Compass being calibrated.
*/
static inline uint8_t mavlink_msg_mag_cal_report_get_compass_id(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 40);
}
/**
* @brief Get field cal_mask from mag_cal_report message
*
* @return Bitmask of compasses being calibrated.
*/
static inline uint8_t mavlink_msg_mag_cal_report_get_cal_mask(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 41);
}
/**
* @brief Get field cal_status from mag_cal_report message
*
* @return Calibration Status.
*/
static inline uint8_t mavlink_msg_mag_cal_report_get_cal_status(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 42);
}
/**
* @brief Get field autosaved from mag_cal_report message
*
* @return 0=requires a MAV_CMD_DO_ACCEPT_MAG_CAL, 1=saved to parameters.
*/
static inline uint8_t mavlink_msg_mag_cal_report_get_autosaved(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 43);
}
/**
* @brief Get field fitness from mag_cal_report message
*
* @return [mgauss] RMS milligauss residuals.
*/
static inline float mavlink_msg_mag_cal_report_get_fitness(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 0);
}
/**
* @brief Get field ofs_x from mag_cal_report message
*
* @return X offset.
*/
static inline float mavlink_msg_mag_cal_report_get_ofs_x(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 4);
}
/**
* @brief Get field ofs_y from mag_cal_report message
*
* @return Y offset.
*/
static inline float mavlink_msg_mag_cal_report_get_ofs_y(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
/**
* @brief Get field ofs_z from mag_cal_report message
*
* @return Z offset.
*/
static inline float mavlink_msg_mag_cal_report_get_ofs_z(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
/**
* @brief Get field diag_x from mag_cal_report message
*
* @return X diagonal (matrix 11).
*/
static inline float mavlink_msg_mag_cal_report_get_diag_x(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 16);
}
/**
* @brief Get field diag_y from mag_cal_report message
*
* @return Y diagonal (matrix 22).
*/
static inline float mavlink_msg_mag_cal_report_get_diag_y(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 20);
}
/**
* @brief Get field diag_z from mag_cal_report message
*
* @return Z diagonal (matrix 33).
*/
static inline float mavlink_msg_mag_cal_report_get_diag_z(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 24);
}
/**
* @brief Get field offdiag_x from mag_cal_report message
*
* @return X off-diagonal (matrix 12 and 21).
*/
static inline float mavlink_msg_mag_cal_report_get_offdiag_x(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 28);
}
/**
* @brief Get field offdiag_y from mag_cal_report message
*
* @return Y off-diagonal (matrix 13 and 31).
*/
static inline float mavlink_msg_mag_cal_report_get_offdiag_y(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 32);
}
/**
* @brief Get field offdiag_z from mag_cal_report message
*
* @return Z off-diagonal (matrix 32 and 23).
*/
static inline float mavlink_msg_mag_cal_report_get_offdiag_z(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 36);
}
/**
* @brief Get field orientation_confidence from mag_cal_report message
*
* @return Confidence in orientation (higher is better).
*/
static inline float mavlink_msg_mag_cal_report_get_orientation_confidence(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 44);
}
/**
* @brief Get field old_orientation from mag_cal_report message
*
* @return orientation before calibration.
*/
static inline uint8_t mavlink_msg_mag_cal_report_get_old_orientation(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 48);
}
/**
* @brief Get field new_orientation from mag_cal_report message
*
* @return orientation after calibration.
*/
static inline uint8_t mavlink_msg_mag_cal_report_get_new_orientation(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 49);
}
/**
* @brief Decode a mag_cal_report message into a struct
*
* @param msg The message to decode
* @param mag_cal_report C-struct to decode the message contents into
*/
static inline void mavlink_msg_mag_cal_report_decode(const mavlink_message_t* msg, mavlink_mag_cal_report_t* mag_cal_report)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mag_cal_report->fitness = mavlink_msg_mag_cal_report_get_fitness(msg);
mag_cal_report->ofs_x = mavlink_msg_mag_cal_report_get_ofs_x(msg);
mag_cal_report->ofs_y = mavlink_msg_mag_cal_report_get_ofs_y(msg);
mag_cal_report->ofs_z = mavlink_msg_mag_cal_report_get_ofs_z(msg);
mag_cal_report->diag_x = mavlink_msg_mag_cal_report_get_diag_x(msg);
mag_cal_report->diag_y = mavlink_msg_mag_cal_report_get_diag_y(msg);
mag_cal_report->diag_z = mavlink_msg_mag_cal_report_get_diag_z(msg);
mag_cal_report->offdiag_x = mavlink_msg_mag_cal_report_get_offdiag_x(msg);
mag_cal_report->offdiag_y = mavlink_msg_mag_cal_report_get_offdiag_y(msg);
mag_cal_report->offdiag_z = mavlink_msg_mag_cal_report_get_offdiag_z(msg);
mag_cal_report->compass_id = mavlink_msg_mag_cal_report_get_compass_id(msg);
mag_cal_report->cal_mask = mavlink_msg_mag_cal_report_get_cal_mask(msg);
mag_cal_report->cal_status = mavlink_msg_mag_cal_report_get_cal_status(msg);
mag_cal_report->autosaved = mavlink_msg_mag_cal_report_get_autosaved(msg);
mag_cal_report->orientation_confidence = mavlink_msg_mag_cal_report_get_orientation_confidence(msg);
mag_cal_report->old_orientation = mavlink_msg_mag_cal_report_get_old_orientation(msg);
mag_cal_report->new_orientation = mavlink_msg_mag_cal_report_get_new_orientation(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_MAG_CAL_REPORT_LEN? msg->len : MAVLINK_MSG_ID_MAG_CAL_REPORT_LEN;
memset(mag_cal_report, 0, MAVLINK_MSG_ID_MAG_CAL_REPORT_LEN);
memcpy(mag_cal_report, _MAV_PAYLOAD(msg), len);
#endif
}

View File

@@ -0,0 +1,263 @@
#pragma once
// MESSAGE MEMINFO PACKING
#define MAVLINK_MSG_ID_MEMINFO 152
MAVPACKED(
typedef struct __mavlink_meminfo_t {
uint16_t brkval; /*< Heap top.*/
uint16_t freemem; /*< [bytes] Free memory.*/
uint32_t freemem32; /*< [bytes] Free memory (32 bit).*/
}) mavlink_meminfo_t;
#define MAVLINK_MSG_ID_MEMINFO_LEN 8
#define MAVLINK_MSG_ID_MEMINFO_MIN_LEN 4
#define MAVLINK_MSG_ID_152_LEN 8
#define MAVLINK_MSG_ID_152_MIN_LEN 4
#define MAVLINK_MSG_ID_MEMINFO_CRC 208
#define MAVLINK_MSG_ID_152_CRC 208
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_MEMINFO { \
152, \
"MEMINFO", \
3, \
{ { "brkval", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_meminfo_t, brkval) }, \
{ "freemem", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_meminfo_t, freemem) }, \
{ "freemem32", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_meminfo_t, freemem32) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_MEMINFO { \
"MEMINFO", \
3, \
{ { "brkval", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_meminfo_t, brkval) }, \
{ "freemem", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_meminfo_t, freemem) }, \
{ "freemem32", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_meminfo_t, freemem32) }, \
} \
}
#endif
/**
* @brief Pack a meminfo 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 brkval Heap top.
* @param freemem [bytes] Free memory.
* @param freemem32 [bytes] Free memory (32 bit).
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_meminfo_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint16_t brkval, uint16_t freemem, uint32_t freemem32)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_MEMINFO_LEN];
_mav_put_uint16_t(buf, 0, brkval);
_mav_put_uint16_t(buf, 2, freemem);
_mav_put_uint32_t(buf, 4, freemem32);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MEMINFO_LEN);
#else
mavlink_meminfo_t packet;
packet.brkval = brkval;
packet.freemem = freemem;
packet.freemem32 = freemem32;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MEMINFO_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_MEMINFO;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MEMINFO_MIN_LEN, MAVLINK_MSG_ID_MEMINFO_LEN, MAVLINK_MSG_ID_MEMINFO_CRC);
}
/**
* @brief Pack a meminfo message on a channel
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param brkval Heap top.
* @param freemem [bytes] Free memory.
* @param freemem32 [bytes] Free memory (32 bit).
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_meminfo_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint16_t brkval,uint16_t freemem,uint32_t freemem32)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_MEMINFO_LEN];
_mav_put_uint16_t(buf, 0, brkval);
_mav_put_uint16_t(buf, 2, freemem);
_mav_put_uint32_t(buf, 4, freemem32);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MEMINFO_LEN);
#else
mavlink_meminfo_t packet;
packet.brkval = brkval;
packet.freemem = freemem;
packet.freemem32 = freemem32;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MEMINFO_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_MEMINFO;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MEMINFO_MIN_LEN, MAVLINK_MSG_ID_MEMINFO_LEN, MAVLINK_MSG_ID_MEMINFO_CRC);
}
/**
* @brief Encode a meminfo struct
*
* @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 meminfo C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_meminfo_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_meminfo_t* meminfo)
{
return mavlink_msg_meminfo_pack(system_id, component_id, msg, meminfo->brkval, meminfo->freemem, meminfo->freemem32);
}
/**
* @brief Encode a meminfo struct on a channel
*
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param meminfo C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_meminfo_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_meminfo_t* meminfo)
{
return mavlink_msg_meminfo_pack_chan(system_id, component_id, chan, msg, meminfo->brkval, meminfo->freemem, meminfo->freemem32);
}
/**
* @brief Send a meminfo message
* @param chan MAVLink channel to send the message
*
* @param brkval Heap top.
* @param freemem [bytes] Free memory.
* @param freemem32 [bytes] Free memory (32 bit).
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_meminfo_send(mavlink_channel_t chan, uint16_t brkval, uint16_t freemem, uint32_t freemem32)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_MEMINFO_LEN];
_mav_put_uint16_t(buf, 0, brkval);
_mav_put_uint16_t(buf, 2, freemem);
_mav_put_uint32_t(buf, 4, freemem32);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMINFO, buf, MAVLINK_MSG_ID_MEMINFO_MIN_LEN, MAVLINK_MSG_ID_MEMINFO_LEN, MAVLINK_MSG_ID_MEMINFO_CRC);
#else
mavlink_meminfo_t packet;
packet.brkval = brkval;
packet.freemem = freemem;
packet.freemem32 = freemem32;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMINFO, (const char *)&packet, MAVLINK_MSG_ID_MEMINFO_MIN_LEN, MAVLINK_MSG_ID_MEMINFO_LEN, MAVLINK_MSG_ID_MEMINFO_CRC);
#endif
}
/**
* @brief Send a meminfo message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_meminfo_send_struct(mavlink_channel_t chan, const mavlink_meminfo_t* meminfo)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_meminfo_send(chan, meminfo->brkval, meminfo->freemem, meminfo->freemem32);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMINFO, (const char *)meminfo, MAVLINK_MSG_ID_MEMINFO_MIN_LEN, MAVLINK_MSG_ID_MEMINFO_LEN, MAVLINK_MSG_ID_MEMINFO_CRC);
#endif
}
#if MAVLINK_MSG_ID_MEMINFO_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_meminfo_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t brkval, uint16_t freemem, uint32_t freemem32)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint16_t(buf, 0, brkval);
_mav_put_uint16_t(buf, 2, freemem);
_mav_put_uint32_t(buf, 4, freemem32);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMINFO, buf, MAVLINK_MSG_ID_MEMINFO_MIN_LEN, MAVLINK_MSG_ID_MEMINFO_LEN, MAVLINK_MSG_ID_MEMINFO_CRC);
#else
mavlink_meminfo_t *packet = (mavlink_meminfo_t *)msgbuf;
packet->brkval = brkval;
packet->freemem = freemem;
packet->freemem32 = freemem32;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMINFO, (const char *)packet, MAVLINK_MSG_ID_MEMINFO_MIN_LEN, MAVLINK_MSG_ID_MEMINFO_LEN, MAVLINK_MSG_ID_MEMINFO_CRC);
#endif
}
#endif
#endif
// MESSAGE MEMINFO UNPACKING
/**
* @brief Get field brkval from meminfo message
*
* @return Heap top.
*/
static inline uint16_t mavlink_msg_meminfo_get_brkval(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 0);
}
/**
* @brief Get field freemem from meminfo message
*
* @return [bytes] Free memory.
*/
static inline uint16_t mavlink_msg_meminfo_get_freemem(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 2);
}
/**
* @brief Get field freemem32 from meminfo message
*
* @return [bytes] Free memory (32 bit).
*/
static inline uint32_t mavlink_msg_meminfo_get_freemem32(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 4);
}
/**
* @brief Decode a meminfo message into a struct
*
* @param msg The message to decode
* @param meminfo C-struct to decode the message contents into
*/
static inline void mavlink_msg_meminfo_decode(const mavlink_message_t* msg, mavlink_meminfo_t* meminfo)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
meminfo->brkval = mavlink_msg_meminfo_get_brkval(msg);
meminfo->freemem = mavlink_msg_meminfo_get_freemem(msg);
meminfo->freemem32 = mavlink_msg_meminfo_get_freemem32(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_MEMINFO_LEN? msg->len : MAVLINK_MSG_ID_MEMINFO_LEN;
memset(meminfo, 0, MAVLINK_MSG_ID_MEMINFO_LEN);
memcpy(meminfo, _MAV_PAYLOAD(msg), len);
#endif
}

View File

@@ -0,0 +1,338 @@
#pragma once
// MESSAGE MOUNT_CONFIGURE PACKING
#define MAVLINK_MSG_ID_MOUNT_CONFIGURE 156
MAVPACKED(
typedef struct __mavlink_mount_configure_t {
uint8_t target_system; /*< System ID.*/
uint8_t target_component; /*< Component ID.*/
uint8_t mount_mode; /*< Mount operating mode.*/
uint8_t stab_roll; /*< (1 = yes, 0 = no).*/
uint8_t stab_pitch; /*< (1 = yes, 0 = no).*/
uint8_t stab_yaw; /*< (1 = yes, 0 = no).*/
}) mavlink_mount_configure_t;
#define MAVLINK_MSG_ID_MOUNT_CONFIGURE_LEN 6
#define MAVLINK_MSG_ID_MOUNT_CONFIGURE_MIN_LEN 6
#define MAVLINK_MSG_ID_156_LEN 6
#define MAVLINK_MSG_ID_156_MIN_LEN 6
#define MAVLINK_MSG_ID_MOUNT_CONFIGURE_CRC 19
#define MAVLINK_MSG_ID_156_CRC 19
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_MOUNT_CONFIGURE { \
156, \
"MOUNT_CONFIGURE", \
6, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_mount_configure_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_mount_configure_t, target_component) }, \
{ "mount_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mount_configure_t, mount_mode) }, \
{ "stab_roll", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_mount_configure_t, stab_roll) }, \
{ "stab_pitch", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_mount_configure_t, stab_pitch) }, \
{ "stab_yaw", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_mount_configure_t, stab_yaw) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_MOUNT_CONFIGURE { \
"MOUNT_CONFIGURE", \
6, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_mount_configure_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_mount_configure_t, target_component) }, \
{ "mount_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mount_configure_t, mount_mode) }, \
{ "stab_roll", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_mount_configure_t, stab_roll) }, \
{ "stab_pitch", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_mount_configure_t, stab_pitch) }, \
{ "stab_yaw", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_mount_configure_t, stab_yaw) }, \
} \
}
#endif
/**
* @brief Pack a mount_configure 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.
* @param mount_mode Mount operating mode.
* @param stab_roll (1 = yes, 0 = no).
* @param stab_pitch (1 = yes, 0 = no).
* @param stab_yaw (1 = yes, 0 = no).
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_mount_configure_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, uint8_t mount_mode, uint8_t stab_roll, uint8_t stab_pitch, uint8_t stab_yaw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_MOUNT_CONFIGURE_LEN];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint8_t(buf, 2, mount_mode);
_mav_put_uint8_t(buf, 3, stab_roll);
_mav_put_uint8_t(buf, 4, stab_pitch);
_mav_put_uint8_t(buf, 5, stab_yaw);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MOUNT_CONFIGURE_LEN);
#else
mavlink_mount_configure_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.mount_mode = mount_mode;
packet.stab_roll = stab_roll;
packet.stab_pitch = stab_pitch;
packet.stab_yaw = stab_yaw;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MOUNT_CONFIGURE_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_MOUNT_CONFIGURE;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MOUNT_CONFIGURE_MIN_LEN, MAVLINK_MSG_ID_MOUNT_CONFIGURE_LEN, MAVLINK_MSG_ID_MOUNT_CONFIGURE_CRC);
}
/**
* @brief Pack a mount_configure message on a channel
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID.
* @param target_component Component ID.
* @param mount_mode Mount operating mode.
* @param stab_roll (1 = yes, 0 = no).
* @param stab_pitch (1 = yes, 0 = no).
* @param stab_yaw (1 = yes, 0 = no).
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_mount_configure_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 mount_mode,uint8_t stab_roll,uint8_t stab_pitch,uint8_t stab_yaw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_MOUNT_CONFIGURE_LEN];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint8_t(buf, 2, mount_mode);
_mav_put_uint8_t(buf, 3, stab_roll);
_mav_put_uint8_t(buf, 4, stab_pitch);
_mav_put_uint8_t(buf, 5, stab_yaw);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MOUNT_CONFIGURE_LEN);
#else
mavlink_mount_configure_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.mount_mode = mount_mode;
packet.stab_roll = stab_roll;
packet.stab_pitch = stab_pitch;
packet.stab_yaw = stab_yaw;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MOUNT_CONFIGURE_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_MOUNT_CONFIGURE;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MOUNT_CONFIGURE_MIN_LEN, MAVLINK_MSG_ID_MOUNT_CONFIGURE_LEN, MAVLINK_MSG_ID_MOUNT_CONFIGURE_CRC);
}
/**
* @brief Encode a mount_configure struct
*
* @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 mount_configure C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_mount_configure_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mount_configure_t* mount_configure)
{
return mavlink_msg_mount_configure_pack(system_id, component_id, msg, mount_configure->target_system, mount_configure->target_component, mount_configure->mount_mode, mount_configure->stab_roll, mount_configure->stab_pitch, mount_configure->stab_yaw);
}
/**
* @brief Encode a mount_configure struct on a channel
*
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param mount_configure C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_mount_configure_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mount_configure_t* mount_configure)
{
return mavlink_msg_mount_configure_pack_chan(system_id, component_id, chan, msg, mount_configure->target_system, mount_configure->target_component, mount_configure->mount_mode, mount_configure->stab_roll, mount_configure->stab_pitch, mount_configure->stab_yaw);
}
/**
* @brief Send a mount_configure message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID.
* @param target_component Component ID.
* @param mount_mode Mount operating mode.
* @param stab_roll (1 = yes, 0 = no).
* @param stab_pitch (1 = yes, 0 = no).
* @param stab_yaw (1 = yes, 0 = no).
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_mount_configure_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t mount_mode, uint8_t stab_roll, uint8_t stab_pitch, uint8_t stab_yaw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_MOUNT_CONFIGURE_LEN];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint8_t(buf, 2, mount_mode);
_mav_put_uint8_t(buf, 3, stab_roll);
_mav_put_uint8_t(buf, 4, stab_pitch);
_mav_put_uint8_t(buf, 5, stab_yaw);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_CONFIGURE, buf, MAVLINK_MSG_ID_MOUNT_CONFIGURE_MIN_LEN, MAVLINK_MSG_ID_MOUNT_CONFIGURE_LEN, MAVLINK_MSG_ID_MOUNT_CONFIGURE_CRC);
#else
mavlink_mount_configure_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.mount_mode = mount_mode;
packet.stab_roll = stab_roll;
packet.stab_pitch = stab_pitch;
packet.stab_yaw = stab_yaw;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_CONFIGURE, (const char *)&packet, MAVLINK_MSG_ID_MOUNT_CONFIGURE_MIN_LEN, MAVLINK_MSG_ID_MOUNT_CONFIGURE_LEN, MAVLINK_MSG_ID_MOUNT_CONFIGURE_CRC);
#endif
}
/**
* @brief Send a mount_configure message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_mount_configure_send_struct(mavlink_channel_t chan, const mavlink_mount_configure_t* mount_configure)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_mount_configure_send(chan, mount_configure->target_system, mount_configure->target_component, mount_configure->mount_mode, mount_configure->stab_roll, mount_configure->stab_pitch, mount_configure->stab_yaw);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_CONFIGURE, (const char *)mount_configure, MAVLINK_MSG_ID_MOUNT_CONFIGURE_MIN_LEN, MAVLINK_MSG_ID_MOUNT_CONFIGURE_LEN, MAVLINK_MSG_ID_MOUNT_CONFIGURE_CRC);
#endif
}
#if MAVLINK_MSG_ID_MOUNT_CONFIGURE_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_mount_configure_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t mount_mode, uint8_t stab_roll, uint8_t stab_pitch, uint8_t stab_yaw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint8_t(buf, 2, mount_mode);
_mav_put_uint8_t(buf, 3, stab_roll);
_mav_put_uint8_t(buf, 4, stab_pitch);
_mav_put_uint8_t(buf, 5, stab_yaw);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_CONFIGURE, buf, MAVLINK_MSG_ID_MOUNT_CONFIGURE_MIN_LEN, MAVLINK_MSG_ID_MOUNT_CONFIGURE_LEN, MAVLINK_MSG_ID_MOUNT_CONFIGURE_CRC);
#else
mavlink_mount_configure_t *packet = (mavlink_mount_configure_t *)msgbuf;
packet->target_system = target_system;
packet->target_component = target_component;
packet->mount_mode = mount_mode;
packet->stab_roll = stab_roll;
packet->stab_pitch = stab_pitch;
packet->stab_yaw = stab_yaw;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_CONFIGURE, (const char *)packet, MAVLINK_MSG_ID_MOUNT_CONFIGURE_MIN_LEN, MAVLINK_MSG_ID_MOUNT_CONFIGURE_LEN, MAVLINK_MSG_ID_MOUNT_CONFIGURE_CRC);
#endif
}
#endif
#endif
// MESSAGE MOUNT_CONFIGURE UNPACKING
/**
* @brief Get field target_system from mount_configure message
*
* @return System ID.
*/
static inline uint8_t mavlink_msg_mount_configure_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 0);
}
/**
* @brief Get field target_component from mount_configure message
*
* @return Component ID.
*/
static inline uint8_t mavlink_msg_mount_configure_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 1);
}
/**
* @brief Get field mount_mode from mount_configure message
*
* @return Mount operating mode.
*/
static inline uint8_t mavlink_msg_mount_configure_get_mount_mode(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 2);
}
/**
* @brief Get field stab_roll from mount_configure message
*
* @return (1 = yes, 0 = no).
*/
static inline uint8_t mavlink_msg_mount_configure_get_stab_roll(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 3);
}
/**
* @brief Get field stab_pitch from mount_configure message
*
* @return (1 = yes, 0 = no).
*/
static inline uint8_t mavlink_msg_mount_configure_get_stab_pitch(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 4);
}
/**
* @brief Get field stab_yaw from mount_configure message
*
* @return (1 = yes, 0 = no).
*/
static inline uint8_t mavlink_msg_mount_configure_get_stab_yaw(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 5);
}
/**
* @brief Decode a mount_configure message into a struct
*
* @param msg The message to decode
* @param mount_configure C-struct to decode the message contents into
*/
static inline void mavlink_msg_mount_configure_decode(const mavlink_message_t* msg, mavlink_mount_configure_t* mount_configure)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mount_configure->target_system = mavlink_msg_mount_configure_get_target_system(msg);
mount_configure->target_component = mavlink_msg_mount_configure_get_target_component(msg);
mount_configure->mount_mode = mavlink_msg_mount_configure_get_mount_mode(msg);
mount_configure->stab_roll = mavlink_msg_mount_configure_get_stab_roll(msg);
mount_configure->stab_pitch = mavlink_msg_mount_configure_get_stab_pitch(msg);
mount_configure->stab_yaw = mavlink_msg_mount_configure_get_stab_yaw(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_MOUNT_CONFIGURE_LEN? msg->len : MAVLINK_MSG_ID_MOUNT_CONFIGURE_LEN;
memset(mount_configure, 0, MAVLINK_MSG_ID_MOUNT_CONFIGURE_LEN);
memcpy(mount_configure, _MAV_PAYLOAD(msg), len);
#endif
}

View File

@@ -0,0 +1,338 @@
#pragma once
// MESSAGE MOUNT_CONTROL PACKING
#define MAVLINK_MSG_ID_MOUNT_CONTROL 157
MAVPACKED(
typedef struct __mavlink_mount_control_t {
int32_t input_a; /*< Pitch (centi-degrees) or lat (degE7), depending on mount mode.*/
int32_t input_b; /*< Roll (centi-degrees) or lon (degE7) depending on mount mode.*/
int32_t input_c; /*< Yaw (centi-degrees) or alt (cm) depending on mount mode.*/
uint8_t target_system; /*< System ID.*/
uint8_t target_component; /*< Component ID.*/
uint8_t save_position; /*< If "1" it will save current trimmed position on EEPROM (just valid for NEUTRAL and LANDING).*/
}) mavlink_mount_control_t;
#define MAVLINK_MSG_ID_MOUNT_CONTROL_LEN 15
#define MAVLINK_MSG_ID_MOUNT_CONTROL_MIN_LEN 15
#define MAVLINK_MSG_ID_157_LEN 15
#define MAVLINK_MSG_ID_157_MIN_LEN 15
#define MAVLINK_MSG_ID_MOUNT_CONTROL_CRC 21
#define MAVLINK_MSG_ID_157_CRC 21
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_MOUNT_CONTROL { \
157, \
"MOUNT_CONTROL", \
6, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_mount_control_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_mount_control_t, target_component) }, \
{ "input_a", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_mount_control_t, input_a) }, \
{ "input_b", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_mount_control_t, input_b) }, \
{ "input_c", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_mount_control_t, input_c) }, \
{ "save_position", NULL, MAVLINK_TYPE_UINT8_T, 0, 14, offsetof(mavlink_mount_control_t, save_position) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_MOUNT_CONTROL { \
"MOUNT_CONTROL", \
6, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_mount_control_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_mount_control_t, target_component) }, \
{ "input_a", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_mount_control_t, input_a) }, \
{ "input_b", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_mount_control_t, input_b) }, \
{ "input_c", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_mount_control_t, input_c) }, \
{ "save_position", NULL, MAVLINK_TYPE_UINT8_T, 0, 14, offsetof(mavlink_mount_control_t, save_position) }, \
} \
}
#endif
/**
* @brief Pack a mount_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_system System ID.
* @param target_component Component ID.
* @param input_a Pitch (centi-degrees) or lat (degE7), depending on mount mode.
* @param input_b Roll (centi-degrees) or lon (degE7) depending on mount mode.
* @param input_c Yaw (centi-degrees) or alt (cm) depending on mount mode.
* @param save_position If "1" it will save current trimmed position on EEPROM (just valid for NEUTRAL and LANDING).
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_mount_control_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, int32_t input_a, int32_t input_b, int32_t input_c, uint8_t save_position)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_MOUNT_CONTROL_LEN];
_mav_put_int32_t(buf, 0, input_a);
_mav_put_int32_t(buf, 4, input_b);
_mav_put_int32_t(buf, 8, input_c);
_mav_put_uint8_t(buf, 12, target_system);
_mav_put_uint8_t(buf, 13, target_component);
_mav_put_uint8_t(buf, 14, save_position);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MOUNT_CONTROL_LEN);
#else
mavlink_mount_control_t packet;
packet.input_a = input_a;
packet.input_b = input_b;
packet.input_c = input_c;
packet.target_system = target_system;
packet.target_component = target_component;
packet.save_position = save_position;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MOUNT_CONTROL_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_MOUNT_CONTROL;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MOUNT_CONTROL_MIN_LEN, MAVLINK_MSG_ID_MOUNT_CONTROL_LEN, MAVLINK_MSG_ID_MOUNT_CONTROL_CRC);
}
/**
* @brief Pack a mount_control message on a channel
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID.
* @param target_component Component ID.
* @param input_a Pitch (centi-degrees) or lat (degE7), depending on mount mode.
* @param input_b Roll (centi-degrees) or lon (degE7) depending on mount mode.
* @param input_c Yaw (centi-degrees) or alt (cm) depending on mount mode.
* @param save_position If "1" it will save current trimmed position on EEPROM (just valid for NEUTRAL and LANDING).
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_mount_control_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,int32_t input_a,int32_t input_b,int32_t input_c,uint8_t save_position)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_MOUNT_CONTROL_LEN];
_mav_put_int32_t(buf, 0, input_a);
_mav_put_int32_t(buf, 4, input_b);
_mav_put_int32_t(buf, 8, input_c);
_mav_put_uint8_t(buf, 12, target_system);
_mav_put_uint8_t(buf, 13, target_component);
_mav_put_uint8_t(buf, 14, save_position);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MOUNT_CONTROL_LEN);
#else
mavlink_mount_control_t packet;
packet.input_a = input_a;
packet.input_b = input_b;
packet.input_c = input_c;
packet.target_system = target_system;
packet.target_component = target_component;
packet.save_position = save_position;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MOUNT_CONTROL_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_MOUNT_CONTROL;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MOUNT_CONTROL_MIN_LEN, MAVLINK_MSG_ID_MOUNT_CONTROL_LEN, MAVLINK_MSG_ID_MOUNT_CONTROL_CRC);
}
/**
* @brief Encode a mount_control struct
*
* @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 mount_control C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_mount_control_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mount_control_t* mount_control)
{
return mavlink_msg_mount_control_pack(system_id, component_id, msg, mount_control->target_system, mount_control->target_component, mount_control->input_a, mount_control->input_b, mount_control->input_c, mount_control->save_position);
}
/**
* @brief Encode a mount_control struct on a channel
*
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param mount_control C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_mount_control_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mount_control_t* mount_control)
{
return mavlink_msg_mount_control_pack_chan(system_id, component_id, chan, msg, mount_control->target_system, mount_control->target_component, mount_control->input_a, mount_control->input_b, mount_control->input_c, mount_control->save_position);
}
/**
* @brief Send a mount_control message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID.
* @param target_component Component ID.
* @param input_a Pitch (centi-degrees) or lat (degE7), depending on mount mode.
* @param input_b Roll (centi-degrees) or lon (degE7) depending on mount mode.
* @param input_c Yaw (centi-degrees) or alt (cm) depending on mount mode.
* @param save_position If "1" it will save current trimmed position on EEPROM (just valid for NEUTRAL and LANDING).
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_mount_control_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, int32_t input_a, int32_t input_b, int32_t input_c, uint8_t save_position)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_MOUNT_CONTROL_LEN];
_mav_put_int32_t(buf, 0, input_a);
_mav_put_int32_t(buf, 4, input_b);
_mav_put_int32_t(buf, 8, input_c);
_mav_put_uint8_t(buf, 12, target_system);
_mav_put_uint8_t(buf, 13, target_component);
_mav_put_uint8_t(buf, 14, save_position);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_CONTROL, buf, MAVLINK_MSG_ID_MOUNT_CONTROL_MIN_LEN, MAVLINK_MSG_ID_MOUNT_CONTROL_LEN, MAVLINK_MSG_ID_MOUNT_CONTROL_CRC);
#else
mavlink_mount_control_t packet;
packet.input_a = input_a;
packet.input_b = input_b;
packet.input_c = input_c;
packet.target_system = target_system;
packet.target_component = target_component;
packet.save_position = save_position;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_CONTROL, (const char *)&packet, MAVLINK_MSG_ID_MOUNT_CONTROL_MIN_LEN, MAVLINK_MSG_ID_MOUNT_CONTROL_LEN, MAVLINK_MSG_ID_MOUNT_CONTROL_CRC);
#endif
}
/**
* @brief Send a mount_control message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_mount_control_send_struct(mavlink_channel_t chan, const mavlink_mount_control_t* mount_control)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_mount_control_send(chan, mount_control->target_system, mount_control->target_component, mount_control->input_a, mount_control->input_b, mount_control->input_c, mount_control->save_position);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_CONTROL, (const char *)mount_control, MAVLINK_MSG_ID_MOUNT_CONTROL_MIN_LEN, MAVLINK_MSG_ID_MOUNT_CONTROL_LEN, MAVLINK_MSG_ID_MOUNT_CONTROL_CRC);
#endif
}
#if MAVLINK_MSG_ID_MOUNT_CONTROL_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_mount_control_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, int32_t input_a, int32_t input_b, int32_t input_c, uint8_t save_position)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_int32_t(buf, 0, input_a);
_mav_put_int32_t(buf, 4, input_b);
_mav_put_int32_t(buf, 8, input_c);
_mav_put_uint8_t(buf, 12, target_system);
_mav_put_uint8_t(buf, 13, target_component);
_mav_put_uint8_t(buf, 14, save_position);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_CONTROL, buf, MAVLINK_MSG_ID_MOUNT_CONTROL_MIN_LEN, MAVLINK_MSG_ID_MOUNT_CONTROL_LEN, MAVLINK_MSG_ID_MOUNT_CONTROL_CRC);
#else
mavlink_mount_control_t *packet = (mavlink_mount_control_t *)msgbuf;
packet->input_a = input_a;
packet->input_b = input_b;
packet->input_c = input_c;
packet->target_system = target_system;
packet->target_component = target_component;
packet->save_position = save_position;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_CONTROL, (const char *)packet, MAVLINK_MSG_ID_MOUNT_CONTROL_MIN_LEN, MAVLINK_MSG_ID_MOUNT_CONTROL_LEN, MAVLINK_MSG_ID_MOUNT_CONTROL_CRC);
#endif
}
#endif
#endif
// MESSAGE MOUNT_CONTROL UNPACKING
/**
* @brief Get field target_system from mount_control message
*
* @return System ID.
*/
static inline uint8_t mavlink_msg_mount_control_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 12);
}
/**
* @brief Get field target_component from mount_control message
*
* @return Component ID.
*/
static inline uint8_t mavlink_msg_mount_control_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 13);
}
/**
* @brief Get field input_a from mount_control message
*
* @return Pitch (centi-degrees) or lat (degE7), depending on mount mode.
*/
static inline int32_t mavlink_msg_mount_control_get_input_a(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 0);
}
/**
* @brief Get field input_b from mount_control message
*
* @return Roll (centi-degrees) or lon (degE7) depending on mount mode.
*/
static inline int32_t mavlink_msg_mount_control_get_input_b(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 4);
}
/**
* @brief Get field input_c from mount_control message
*
* @return Yaw (centi-degrees) or alt (cm) depending on mount mode.
*/
static inline int32_t mavlink_msg_mount_control_get_input_c(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 8);
}
/**
* @brief Get field save_position from mount_control message
*
* @return If "1" it will save current trimmed position on EEPROM (just valid for NEUTRAL and LANDING).
*/
static inline uint8_t mavlink_msg_mount_control_get_save_position(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 14);
}
/**
* @brief Decode a mount_control message into a struct
*
* @param msg The message to decode
* @param mount_control C-struct to decode the message contents into
*/
static inline void mavlink_msg_mount_control_decode(const mavlink_message_t* msg, mavlink_mount_control_t* mount_control)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mount_control->input_a = mavlink_msg_mount_control_get_input_a(msg);
mount_control->input_b = mavlink_msg_mount_control_get_input_b(msg);
mount_control->input_c = mavlink_msg_mount_control_get_input_c(msg);
mount_control->target_system = mavlink_msg_mount_control_get_target_system(msg);
mount_control->target_component = mavlink_msg_mount_control_get_target_component(msg);
mount_control->save_position = mavlink_msg_mount_control_get_save_position(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_MOUNT_CONTROL_LEN? msg->len : MAVLINK_MSG_ID_MOUNT_CONTROL_LEN;
memset(mount_control, 0, MAVLINK_MSG_ID_MOUNT_CONTROL_LEN);
memcpy(mount_control, _MAV_PAYLOAD(msg), len);
#endif
}

View File

@@ -0,0 +1,313 @@
#pragma once
// MESSAGE MOUNT_STATUS PACKING
#define MAVLINK_MSG_ID_MOUNT_STATUS 158
MAVPACKED(
typedef struct __mavlink_mount_status_t {
int32_t pointing_a; /*< [cdeg] Pitch.*/
int32_t pointing_b; /*< [cdeg] Roll.*/
int32_t pointing_c; /*< [cdeg] Yaw.*/
uint8_t target_system; /*< System ID.*/
uint8_t target_component; /*< Component ID.*/
}) mavlink_mount_status_t;
#define MAVLINK_MSG_ID_MOUNT_STATUS_LEN 14
#define MAVLINK_MSG_ID_MOUNT_STATUS_MIN_LEN 14
#define MAVLINK_MSG_ID_158_LEN 14
#define MAVLINK_MSG_ID_158_MIN_LEN 14
#define MAVLINK_MSG_ID_MOUNT_STATUS_CRC 134
#define MAVLINK_MSG_ID_158_CRC 134
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_MOUNT_STATUS { \
158, \
"MOUNT_STATUS", \
5, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_mount_status_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_mount_status_t, target_component) }, \
{ "pointing_a", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_mount_status_t, pointing_a) }, \
{ "pointing_b", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_mount_status_t, pointing_b) }, \
{ "pointing_c", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_mount_status_t, pointing_c) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_MOUNT_STATUS { \
"MOUNT_STATUS", \
5, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_mount_status_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_mount_status_t, target_component) }, \
{ "pointing_a", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_mount_status_t, pointing_a) }, \
{ "pointing_b", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_mount_status_t, pointing_b) }, \
{ "pointing_c", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_mount_status_t, pointing_c) }, \
} \
}
#endif
/**
* @brief Pack a mount_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 target_system System ID.
* @param target_component Component ID.
* @param pointing_a [cdeg] Pitch.
* @param pointing_b [cdeg] Roll.
* @param pointing_c [cdeg] Yaw.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_mount_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, int32_t pointing_a, int32_t pointing_b, int32_t pointing_c)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_MOUNT_STATUS_LEN];
_mav_put_int32_t(buf, 0, pointing_a);
_mav_put_int32_t(buf, 4, pointing_b);
_mav_put_int32_t(buf, 8, pointing_c);
_mav_put_uint8_t(buf, 12, target_system);
_mav_put_uint8_t(buf, 13, target_component);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MOUNT_STATUS_LEN);
#else
mavlink_mount_status_t packet;
packet.pointing_a = pointing_a;
packet.pointing_b = pointing_b;
packet.pointing_c = pointing_c;
packet.target_system = target_system;
packet.target_component = target_component;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MOUNT_STATUS_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_MOUNT_STATUS;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MOUNT_STATUS_MIN_LEN, MAVLINK_MSG_ID_MOUNT_STATUS_LEN, MAVLINK_MSG_ID_MOUNT_STATUS_CRC);
}
/**
* @brief Pack a mount_status message on a channel
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID.
* @param target_component Component ID.
* @param pointing_a [cdeg] Pitch.
* @param pointing_b [cdeg] Roll.
* @param pointing_c [cdeg] Yaw.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_mount_status_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,int32_t pointing_a,int32_t pointing_b,int32_t pointing_c)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_MOUNT_STATUS_LEN];
_mav_put_int32_t(buf, 0, pointing_a);
_mav_put_int32_t(buf, 4, pointing_b);
_mav_put_int32_t(buf, 8, pointing_c);
_mav_put_uint8_t(buf, 12, target_system);
_mav_put_uint8_t(buf, 13, target_component);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MOUNT_STATUS_LEN);
#else
mavlink_mount_status_t packet;
packet.pointing_a = pointing_a;
packet.pointing_b = pointing_b;
packet.pointing_c = pointing_c;
packet.target_system = target_system;
packet.target_component = target_component;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MOUNT_STATUS_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_MOUNT_STATUS;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MOUNT_STATUS_MIN_LEN, MAVLINK_MSG_ID_MOUNT_STATUS_LEN, MAVLINK_MSG_ID_MOUNT_STATUS_CRC);
}
/**
* @brief Encode a mount_status struct
*
* @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 mount_status C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_mount_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mount_status_t* mount_status)
{
return mavlink_msg_mount_status_pack(system_id, component_id, msg, mount_status->target_system, mount_status->target_component, mount_status->pointing_a, mount_status->pointing_b, mount_status->pointing_c);
}
/**
* @brief Encode a mount_status struct on a channel
*
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param mount_status C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_mount_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mount_status_t* mount_status)
{
return mavlink_msg_mount_status_pack_chan(system_id, component_id, chan, msg, mount_status->target_system, mount_status->target_component, mount_status->pointing_a, mount_status->pointing_b, mount_status->pointing_c);
}
/**
* @brief Send a mount_status message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID.
* @param target_component Component ID.
* @param pointing_a [cdeg] Pitch.
* @param pointing_b [cdeg] Roll.
* @param pointing_c [cdeg] Yaw.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_mount_status_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, int32_t pointing_a, int32_t pointing_b, int32_t pointing_c)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_MOUNT_STATUS_LEN];
_mav_put_int32_t(buf, 0, pointing_a);
_mav_put_int32_t(buf, 4, pointing_b);
_mav_put_int32_t(buf, 8, pointing_c);
_mav_put_uint8_t(buf, 12, target_system);
_mav_put_uint8_t(buf, 13, target_component);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_STATUS, buf, MAVLINK_MSG_ID_MOUNT_STATUS_MIN_LEN, MAVLINK_MSG_ID_MOUNT_STATUS_LEN, MAVLINK_MSG_ID_MOUNT_STATUS_CRC);
#else
mavlink_mount_status_t packet;
packet.pointing_a = pointing_a;
packet.pointing_b = pointing_b;
packet.pointing_c = pointing_c;
packet.target_system = target_system;
packet.target_component = target_component;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_STATUS, (const char *)&packet, MAVLINK_MSG_ID_MOUNT_STATUS_MIN_LEN, MAVLINK_MSG_ID_MOUNT_STATUS_LEN, MAVLINK_MSG_ID_MOUNT_STATUS_CRC);
#endif
}
/**
* @brief Send a mount_status message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_mount_status_send_struct(mavlink_channel_t chan, const mavlink_mount_status_t* mount_status)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_mount_status_send(chan, mount_status->target_system, mount_status->target_component, mount_status->pointing_a, mount_status->pointing_b, mount_status->pointing_c);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_STATUS, (const char *)mount_status, MAVLINK_MSG_ID_MOUNT_STATUS_MIN_LEN, MAVLINK_MSG_ID_MOUNT_STATUS_LEN, MAVLINK_MSG_ID_MOUNT_STATUS_CRC);
#endif
}
#if MAVLINK_MSG_ID_MOUNT_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_mount_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, int32_t pointing_a, int32_t pointing_b, int32_t pointing_c)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_int32_t(buf, 0, pointing_a);
_mav_put_int32_t(buf, 4, pointing_b);
_mav_put_int32_t(buf, 8, pointing_c);
_mav_put_uint8_t(buf, 12, target_system);
_mav_put_uint8_t(buf, 13, target_component);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_STATUS, buf, MAVLINK_MSG_ID_MOUNT_STATUS_MIN_LEN, MAVLINK_MSG_ID_MOUNT_STATUS_LEN, MAVLINK_MSG_ID_MOUNT_STATUS_CRC);
#else
mavlink_mount_status_t *packet = (mavlink_mount_status_t *)msgbuf;
packet->pointing_a = pointing_a;
packet->pointing_b = pointing_b;
packet->pointing_c = pointing_c;
packet->target_system = target_system;
packet->target_component = target_component;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_STATUS, (const char *)packet, MAVLINK_MSG_ID_MOUNT_STATUS_MIN_LEN, MAVLINK_MSG_ID_MOUNT_STATUS_LEN, MAVLINK_MSG_ID_MOUNT_STATUS_CRC);
#endif
}
#endif
#endif
// MESSAGE MOUNT_STATUS UNPACKING
/**
* @brief Get field target_system from mount_status message
*
* @return System ID.
*/
static inline uint8_t mavlink_msg_mount_status_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 12);
}
/**
* @brief Get field target_component from mount_status message
*
* @return Component ID.
*/
static inline uint8_t mavlink_msg_mount_status_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 13);
}
/**
* @brief Get field pointing_a from mount_status message
*
* @return [cdeg] Pitch.
*/
static inline int32_t mavlink_msg_mount_status_get_pointing_a(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 0);
}
/**
* @brief Get field pointing_b from mount_status message
*
* @return [cdeg] Roll.
*/
static inline int32_t mavlink_msg_mount_status_get_pointing_b(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 4);
}
/**
* @brief Get field pointing_c from mount_status message
*
* @return [cdeg] Yaw.
*/
static inline int32_t mavlink_msg_mount_status_get_pointing_c(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 8);
}
/**
* @brief Decode a mount_status message into a struct
*
* @param msg The message to decode
* @param mount_status C-struct to decode the message contents into
*/
static inline void mavlink_msg_mount_status_decode(const mavlink_message_t* msg, mavlink_mount_status_t* mount_status)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mount_status->pointing_a = mavlink_msg_mount_status_get_pointing_a(msg);
mount_status->pointing_b = mavlink_msg_mount_status_get_pointing_b(msg);
mount_status->pointing_c = mavlink_msg_mount_status_get_pointing_c(msg);
mount_status->target_system = mavlink_msg_mount_status_get_target_system(msg);
mount_status->target_component = mavlink_msg_mount_status_get_target_component(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_MOUNT_STATUS_LEN? msg->len : MAVLINK_MSG_ID_MOUNT_STATUS_LEN;
memset(mount_status, 0, MAVLINK_MSG_ID_MOUNT_STATUS_LEN);
memcpy(mount_status, _MAV_PAYLOAD(msg), len);
#endif
}

View File

@@ -0,0 +1,363 @@
#pragma once
// MESSAGE PID_TUNING PACKING
#define MAVLINK_MSG_ID_PID_TUNING 194
MAVPACKED(
typedef struct __mavlink_pid_tuning_t {
float desired; /*< [deg/s] Desired rate.*/
float achieved; /*< [deg/s] Achieved rate.*/
float FF; /*< FF component.*/
float P; /*< P component.*/
float I; /*< I component.*/
float D; /*< D component.*/
uint8_t axis; /*< Axis.*/
}) mavlink_pid_tuning_t;
#define MAVLINK_MSG_ID_PID_TUNING_LEN 25
#define MAVLINK_MSG_ID_PID_TUNING_MIN_LEN 25
#define MAVLINK_MSG_ID_194_LEN 25
#define MAVLINK_MSG_ID_194_MIN_LEN 25
#define MAVLINK_MSG_ID_PID_TUNING_CRC 98
#define MAVLINK_MSG_ID_194_CRC 98
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_PID_TUNING { \
194, \
"PID_TUNING", \
7, \
{ { "axis", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_pid_tuning_t, axis) }, \
{ "desired", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_pid_tuning_t, desired) }, \
{ "achieved", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_pid_tuning_t, achieved) }, \
{ "FF", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_pid_tuning_t, FF) }, \
{ "P", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_pid_tuning_t, P) }, \
{ "I", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_pid_tuning_t, I) }, \
{ "D", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_pid_tuning_t, D) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_PID_TUNING { \
"PID_TUNING", \
7, \
{ { "axis", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_pid_tuning_t, axis) }, \
{ "desired", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_pid_tuning_t, desired) }, \
{ "achieved", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_pid_tuning_t, achieved) }, \
{ "FF", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_pid_tuning_t, FF) }, \
{ "P", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_pid_tuning_t, P) }, \
{ "I", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_pid_tuning_t, I) }, \
{ "D", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_pid_tuning_t, D) }, \
} \
}
#endif
/**
* @brief Pack a pid_tuning 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 axis Axis.
* @param desired [deg/s] Desired rate.
* @param achieved [deg/s] Achieved rate.
* @param FF FF component.
* @param P P component.
* @param I I component.
* @param D D component.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_pid_tuning_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t axis, float desired, float achieved, float FF, float P, float I, float D)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_PID_TUNING_LEN];
_mav_put_float(buf, 0, desired);
_mav_put_float(buf, 4, achieved);
_mav_put_float(buf, 8, FF);
_mav_put_float(buf, 12, P);
_mav_put_float(buf, 16, I);
_mav_put_float(buf, 20, D);
_mav_put_uint8_t(buf, 24, axis);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PID_TUNING_LEN);
#else
mavlink_pid_tuning_t packet;
packet.desired = desired;
packet.achieved = achieved;
packet.FF = FF;
packet.P = P;
packet.I = I;
packet.D = D;
packet.axis = axis;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PID_TUNING_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_PID_TUNING;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PID_TUNING_MIN_LEN, MAVLINK_MSG_ID_PID_TUNING_LEN, MAVLINK_MSG_ID_PID_TUNING_CRC);
}
/**
* @brief Pack a pid_tuning message on a channel
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param axis Axis.
* @param desired [deg/s] Desired rate.
* @param achieved [deg/s] Achieved rate.
* @param FF FF component.
* @param P P component.
* @param I I component.
* @param D D component.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_pid_tuning_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint8_t axis,float desired,float achieved,float FF,float P,float I,float D)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_PID_TUNING_LEN];
_mav_put_float(buf, 0, desired);
_mav_put_float(buf, 4, achieved);
_mav_put_float(buf, 8, FF);
_mav_put_float(buf, 12, P);
_mav_put_float(buf, 16, I);
_mav_put_float(buf, 20, D);
_mav_put_uint8_t(buf, 24, axis);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PID_TUNING_LEN);
#else
mavlink_pid_tuning_t packet;
packet.desired = desired;
packet.achieved = achieved;
packet.FF = FF;
packet.P = P;
packet.I = I;
packet.D = D;
packet.axis = axis;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PID_TUNING_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_PID_TUNING;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PID_TUNING_MIN_LEN, MAVLINK_MSG_ID_PID_TUNING_LEN, MAVLINK_MSG_ID_PID_TUNING_CRC);
}
/**
* @brief Encode a pid_tuning struct
*
* @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 pid_tuning C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_pid_tuning_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_pid_tuning_t* pid_tuning)
{
return mavlink_msg_pid_tuning_pack(system_id, component_id, msg, pid_tuning->axis, pid_tuning->desired, pid_tuning->achieved, pid_tuning->FF, pid_tuning->P, pid_tuning->I, pid_tuning->D);
}
/**
* @brief Encode a pid_tuning struct on a channel
*
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param pid_tuning C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_pid_tuning_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_pid_tuning_t* pid_tuning)
{
return mavlink_msg_pid_tuning_pack_chan(system_id, component_id, chan, msg, pid_tuning->axis, pid_tuning->desired, pid_tuning->achieved, pid_tuning->FF, pid_tuning->P, pid_tuning->I, pid_tuning->D);
}
/**
* @brief Send a pid_tuning message
* @param chan MAVLink channel to send the message
*
* @param axis Axis.
* @param desired [deg/s] Desired rate.
* @param achieved [deg/s] Achieved rate.
* @param FF FF component.
* @param P P component.
* @param I I component.
* @param D D component.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_pid_tuning_send(mavlink_channel_t chan, uint8_t axis, float desired, float achieved, float FF, float P, float I, float D)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_PID_TUNING_LEN];
_mav_put_float(buf, 0, desired);
_mav_put_float(buf, 4, achieved);
_mav_put_float(buf, 8, FF);
_mav_put_float(buf, 12, P);
_mav_put_float(buf, 16, I);
_mav_put_float(buf, 20, D);
_mav_put_uint8_t(buf, 24, axis);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PID_TUNING, buf, MAVLINK_MSG_ID_PID_TUNING_MIN_LEN, MAVLINK_MSG_ID_PID_TUNING_LEN, MAVLINK_MSG_ID_PID_TUNING_CRC);
#else
mavlink_pid_tuning_t packet;
packet.desired = desired;
packet.achieved = achieved;
packet.FF = FF;
packet.P = P;
packet.I = I;
packet.D = D;
packet.axis = axis;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PID_TUNING, (const char *)&packet, MAVLINK_MSG_ID_PID_TUNING_MIN_LEN, MAVLINK_MSG_ID_PID_TUNING_LEN, MAVLINK_MSG_ID_PID_TUNING_CRC);
#endif
}
/**
* @brief Send a pid_tuning message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_pid_tuning_send_struct(mavlink_channel_t chan, const mavlink_pid_tuning_t* pid_tuning)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_pid_tuning_send(chan, pid_tuning->axis, pid_tuning->desired, pid_tuning->achieved, pid_tuning->FF, pid_tuning->P, pid_tuning->I, pid_tuning->D);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PID_TUNING, (const char *)pid_tuning, MAVLINK_MSG_ID_PID_TUNING_MIN_LEN, MAVLINK_MSG_ID_PID_TUNING_LEN, MAVLINK_MSG_ID_PID_TUNING_CRC);
#endif
}
#if MAVLINK_MSG_ID_PID_TUNING_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_pid_tuning_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t axis, float desired, float achieved, float FF, float P, float I, float D)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_float(buf, 0, desired);
_mav_put_float(buf, 4, achieved);
_mav_put_float(buf, 8, FF);
_mav_put_float(buf, 12, P);
_mav_put_float(buf, 16, I);
_mav_put_float(buf, 20, D);
_mav_put_uint8_t(buf, 24, axis);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PID_TUNING, buf, MAVLINK_MSG_ID_PID_TUNING_MIN_LEN, MAVLINK_MSG_ID_PID_TUNING_LEN, MAVLINK_MSG_ID_PID_TUNING_CRC);
#else
mavlink_pid_tuning_t *packet = (mavlink_pid_tuning_t *)msgbuf;
packet->desired = desired;
packet->achieved = achieved;
packet->FF = FF;
packet->P = P;
packet->I = I;
packet->D = D;
packet->axis = axis;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PID_TUNING, (const char *)packet, MAVLINK_MSG_ID_PID_TUNING_MIN_LEN, MAVLINK_MSG_ID_PID_TUNING_LEN, MAVLINK_MSG_ID_PID_TUNING_CRC);
#endif
}
#endif
#endif
// MESSAGE PID_TUNING UNPACKING
/**
* @brief Get field axis from pid_tuning message
*
* @return Axis.
*/
static inline uint8_t mavlink_msg_pid_tuning_get_axis(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 24);
}
/**
* @brief Get field desired from pid_tuning message
*
* @return [deg/s] Desired rate.
*/
static inline float mavlink_msg_pid_tuning_get_desired(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 0);
}
/**
* @brief Get field achieved from pid_tuning message
*
* @return [deg/s] Achieved rate.
*/
static inline float mavlink_msg_pid_tuning_get_achieved(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 4);
}
/**
* @brief Get field FF from pid_tuning message
*
* @return FF component.
*/
static inline float mavlink_msg_pid_tuning_get_FF(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
/**
* @brief Get field P from pid_tuning message
*
* @return P component.
*/
static inline float mavlink_msg_pid_tuning_get_P(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
/**
* @brief Get field I from pid_tuning message
*
* @return I component.
*/
static inline float mavlink_msg_pid_tuning_get_I(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 16);
}
/**
* @brief Get field D from pid_tuning message
*
* @return D component.
*/
static inline float mavlink_msg_pid_tuning_get_D(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 20);
}
/**
* @brief Decode a pid_tuning message into a struct
*
* @param msg The message to decode
* @param pid_tuning C-struct to decode the message contents into
*/
static inline void mavlink_msg_pid_tuning_decode(const mavlink_message_t* msg, mavlink_pid_tuning_t* pid_tuning)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
pid_tuning->desired = mavlink_msg_pid_tuning_get_desired(msg);
pid_tuning->achieved = mavlink_msg_pid_tuning_get_achieved(msg);
pid_tuning->FF = mavlink_msg_pid_tuning_get_FF(msg);
pid_tuning->P = mavlink_msg_pid_tuning_get_P(msg);
pid_tuning->I = mavlink_msg_pid_tuning_get_I(msg);
pid_tuning->D = mavlink_msg_pid_tuning_get_D(msg);
pid_tuning->axis = mavlink_msg_pid_tuning_get_axis(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_PID_TUNING_LEN? msg->len : MAVLINK_MSG_ID_PID_TUNING_LEN;
memset(pid_tuning, 0, MAVLINK_MSG_ID_PID_TUNING_LEN);
memcpy(pid_tuning, _MAV_PAYLOAD(msg), len);
#endif
}

View File

@@ -0,0 +1,363 @@
#pragma once
// MESSAGE RADIO PACKING
#define MAVLINK_MSG_ID_RADIO 166
MAVPACKED(
typedef struct __mavlink_radio_t {
uint16_t rxerrors; /*< Receive errors.*/
uint16_t fixed; /*< Count of error corrected packets.*/
uint8_t rssi; /*< Local signal strength.*/
uint8_t remrssi; /*< Remote signal strength.*/
uint8_t txbuf; /*< [%] How full the tx buffer is.*/
uint8_t noise; /*< Background noise level.*/
uint8_t remnoise; /*< Remote background noise level.*/
}) mavlink_radio_t;
#define MAVLINK_MSG_ID_RADIO_LEN 9
#define MAVLINK_MSG_ID_RADIO_MIN_LEN 9
#define MAVLINK_MSG_ID_166_LEN 9
#define MAVLINK_MSG_ID_166_MIN_LEN 9
#define MAVLINK_MSG_ID_RADIO_CRC 21
#define MAVLINK_MSG_ID_166_CRC 21
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_RADIO { \
166, \
"RADIO", \
7, \
{ { "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_radio_t, rssi) }, \
{ "remrssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_radio_t, remrssi) }, \
{ "txbuf", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_radio_t, txbuf) }, \
{ "noise", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_radio_t, noise) }, \
{ "remnoise", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_radio_t, remnoise) }, \
{ "rxerrors", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_radio_t, rxerrors) }, \
{ "fixed", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_radio_t, fixed) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_RADIO { \
"RADIO", \
7, \
{ { "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_radio_t, rssi) }, \
{ "remrssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_radio_t, remrssi) }, \
{ "txbuf", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_radio_t, txbuf) }, \
{ "noise", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_radio_t, noise) }, \
{ "remnoise", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_radio_t, remnoise) }, \
{ "rxerrors", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_radio_t, rxerrors) }, \
{ "fixed", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_radio_t, fixed) }, \
} \
}
#endif
/**
* @brief Pack a radio 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 rssi Local signal strength.
* @param remrssi Remote signal strength.
* @param txbuf [%] How full the tx buffer is.
* @param noise Background noise level.
* @param remnoise Remote background noise level.
* @param rxerrors Receive errors.
* @param fixed Count of error corrected packets.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_radio_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t rssi, uint8_t remrssi, uint8_t txbuf, uint8_t noise, uint8_t remnoise, uint16_t rxerrors, uint16_t fixed)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_RADIO_LEN];
_mav_put_uint16_t(buf, 0, rxerrors);
_mav_put_uint16_t(buf, 2, fixed);
_mav_put_uint8_t(buf, 4, rssi);
_mav_put_uint8_t(buf, 5, remrssi);
_mav_put_uint8_t(buf, 6, txbuf);
_mav_put_uint8_t(buf, 7, noise);
_mav_put_uint8_t(buf, 8, remnoise);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RADIO_LEN);
#else
mavlink_radio_t packet;
packet.rxerrors = rxerrors;
packet.fixed = fixed;
packet.rssi = rssi;
packet.remrssi = remrssi;
packet.txbuf = txbuf;
packet.noise = noise;
packet.remnoise = remnoise;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RADIO_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_RADIO;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RADIO_MIN_LEN, MAVLINK_MSG_ID_RADIO_LEN, MAVLINK_MSG_ID_RADIO_CRC);
}
/**
* @brief Pack a radio message on a channel
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param rssi Local signal strength.
* @param remrssi Remote signal strength.
* @param txbuf [%] How full the tx buffer is.
* @param noise Background noise level.
* @param remnoise Remote background noise level.
* @param rxerrors Receive errors.
* @param fixed Count of error corrected packets.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_radio_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint8_t rssi,uint8_t remrssi,uint8_t txbuf,uint8_t noise,uint8_t remnoise,uint16_t rxerrors,uint16_t fixed)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_RADIO_LEN];
_mav_put_uint16_t(buf, 0, rxerrors);
_mav_put_uint16_t(buf, 2, fixed);
_mav_put_uint8_t(buf, 4, rssi);
_mav_put_uint8_t(buf, 5, remrssi);
_mav_put_uint8_t(buf, 6, txbuf);
_mav_put_uint8_t(buf, 7, noise);
_mav_put_uint8_t(buf, 8, remnoise);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RADIO_LEN);
#else
mavlink_radio_t packet;
packet.rxerrors = rxerrors;
packet.fixed = fixed;
packet.rssi = rssi;
packet.remrssi = remrssi;
packet.txbuf = txbuf;
packet.noise = noise;
packet.remnoise = remnoise;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RADIO_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_RADIO;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RADIO_MIN_LEN, MAVLINK_MSG_ID_RADIO_LEN, MAVLINK_MSG_ID_RADIO_CRC);
}
/**
* @brief Encode a radio struct
*
* @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 radio C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_radio_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_radio_t* radio)
{
return mavlink_msg_radio_pack(system_id, component_id, msg, radio->rssi, radio->remrssi, radio->txbuf, radio->noise, radio->remnoise, radio->rxerrors, radio->fixed);
}
/**
* @brief Encode a radio struct on a channel
*
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param radio C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_radio_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_radio_t* radio)
{
return mavlink_msg_radio_pack_chan(system_id, component_id, chan, msg, radio->rssi, radio->remrssi, radio->txbuf, radio->noise, radio->remnoise, radio->rxerrors, radio->fixed);
}
/**
* @brief Send a radio message
* @param chan MAVLink channel to send the message
*
* @param rssi Local signal strength.
* @param remrssi Remote signal strength.
* @param txbuf [%] How full the tx buffer is.
* @param noise Background noise level.
* @param remnoise Remote background noise level.
* @param rxerrors Receive errors.
* @param fixed Count of error corrected packets.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_radio_send(mavlink_channel_t chan, uint8_t rssi, uint8_t remrssi, uint8_t txbuf, uint8_t noise, uint8_t remnoise, uint16_t rxerrors, uint16_t fixed)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_RADIO_LEN];
_mav_put_uint16_t(buf, 0, rxerrors);
_mav_put_uint16_t(buf, 2, fixed);
_mav_put_uint8_t(buf, 4, rssi);
_mav_put_uint8_t(buf, 5, remrssi);
_mav_put_uint8_t(buf, 6, txbuf);
_mav_put_uint8_t(buf, 7, noise);
_mav_put_uint8_t(buf, 8, remnoise);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO, buf, MAVLINK_MSG_ID_RADIO_MIN_LEN, MAVLINK_MSG_ID_RADIO_LEN, MAVLINK_MSG_ID_RADIO_CRC);
#else
mavlink_radio_t packet;
packet.rxerrors = rxerrors;
packet.fixed = fixed;
packet.rssi = rssi;
packet.remrssi = remrssi;
packet.txbuf = txbuf;
packet.noise = noise;
packet.remnoise = remnoise;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO, (const char *)&packet, MAVLINK_MSG_ID_RADIO_MIN_LEN, MAVLINK_MSG_ID_RADIO_LEN, MAVLINK_MSG_ID_RADIO_CRC);
#endif
}
/**
* @brief Send a radio message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_radio_send_struct(mavlink_channel_t chan, const mavlink_radio_t* radio)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_radio_send(chan, radio->rssi, radio->remrssi, radio->txbuf, radio->noise, radio->remnoise, radio->rxerrors, radio->fixed);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO, (const char *)radio, MAVLINK_MSG_ID_RADIO_MIN_LEN, MAVLINK_MSG_ID_RADIO_LEN, MAVLINK_MSG_ID_RADIO_CRC);
#endif
}
#if MAVLINK_MSG_ID_RADIO_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_radio_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t rssi, uint8_t remrssi, uint8_t txbuf, uint8_t noise, uint8_t remnoise, uint16_t rxerrors, uint16_t fixed)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint16_t(buf, 0, rxerrors);
_mav_put_uint16_t(buf, 2, fixed);
_mav_put_uint8_t(buf, 4, rssi);
_mav_put_uint8_t(buf, 5, remrssi);
_mav_put_uint8_t(buf, 6, txbuf);
_mav_put_uint8_t(buf, 7, noise);
_mav_put_uint8_t(buf, 8, remnoise);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO, buf, MAVLINK_MSG_ID_RADIO_MIN_LEN, MAVLINK_MSG_ID_RADIO_LEN, MAVLINK_MSG_ID_RADIO_CRC);
#else
mavlink_radio_t *packet = (mavlink_radio_t *)msgbuf;
packet->rxerrors = rxerrors;
packet->fixed = fixed;
packet->rssi = rssi;
packet->remrssi = remrssi;
packet->txbuf = txbuf;
packet->noise = noise;
packet->remnoise = remnoise;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO, (const char *)packet, MAVLINK_MSG_ID_RADIO_MIN_LEN, MAVLINK_MSG_ID_RADIO_LEN, MAVLINK_MSG_ID_RADIO_CRC);
#endif
}
#endif
#endif
// MESSAGE RADIO UNPACKING
/**
* @brief Get field rssi from radio message
*
* @return Local signal strength.
*/
static inline uint8_t mavlink_msg_radio_get_rssi(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 4);
}
/**
* @brief Get field remrssi from radio message
*
* @return Remote signal strength.
*/
static inline uint8_t mavlink_msg_radio_get_remrssi(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 5);
}
/**
* @brief Get field txbuf from radio message
*
* @return [%] How full the tx buffer is.
*/
static inline uint8_t mavlink_msg_radio_get_txbuf(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 6);
}
/**
* @brief Get field noise from radio message
*
* @return Background noise level.
*/
static inline uint8_t mavlink_msg_radio_get_noise(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 7);
}
/**
* @brief Get field remnoise from radio message
*
* @return Remote background noise level.
*/
static inline uint8_t mavlink_msg_radio_get_remnoise(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 8);
}
/**
* @brief Get field rxerrors from radio message
*
* @return Receive errors.
*/
static inline uint16_t mavlink_msg_radio_get_rxerrors(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 0);
}
/**
* @brief Get field fixed from radio message
*
* @return Count of error corrected packets.
*/
static inline uint16_t mavlink_msg_radio_get_fixed(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 2);
}
/**
* @brief Decode a radio message into a struct
*
* @param msg The message to decode
* @param radio C-struct to decode the message contents into
*/
static inline void mavlink_msg_radio_decode(const mavlink_message_t* msg, mavlink_radio_t* radio)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
radio->rxerrors = mavlink_msg_radio_get_rxerrors(msg);
radio->fixed = mavlink_msg_radio_get_fixed(msg);
radio->rssi = mavlink_msg_radio_get_rssi(msg);
radio->remrssi = mavlink_msg_radio_get_remrssi(msg);
radio->txbuf = mavlink_msg_radio_get_txbuf(msg);
radio->noise = mavlink_msg_radio_get_noise(msg);
radio->remnoise = mavlink_msg_radio_get_remnoise(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_RADIO_LEN? msg->len : MAVLINK_MSG_ID_RADIO_LEN;
memset(radio, 0, MAVLINK_MSG_ID_RADIO_LEN);
memcpy(radio, _MAV_PAYLOAD(msg), len);
#endif
}

View File

@@ -0,0 +1,263 @@
#pragma once
// MESSAGE RALLY_FETCH_POINT PACKING
#define MAVLINK_MSG_ID_RALLY_FETCH_POINT 176
MAVPACKED(
typedef struct __mavlink_rally_fetch_point_t {
uint8_t target_system; /*< System ID.*/
uint8_t target_component; /*< Component ID.*/
uint8_t idx; /*< Point index (first point is 0).*/
}) mavlink_rally_fetch_point_t;
#define MAVLINK_MSG_ID_RALLY_FETCH_POINT_LEN 3
#define MAVLINK_MSG_ID_RALLY_FETCH_POINT_MIN_LEN 3
#define MAVLINK_MSG_ID_176_LEN 3
#define MAVLINK_MSG_ID_176_MIN_LEN 3
#define MAVLINK_MSG_ID_RALLY_FETCH_POINT_CRC 234
#define MAVLINK_MSG_ID_176_CRC 234
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_RALLY_FETCH_POINT { \
176, \
"RALLY_FETCH_POINT", \
3, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_rally_fetch_point_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_rally_fetch_point_t, target_component) }, \
{ "idx", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_rally_fetch_point_t, idx) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_RALLY_FETCH_POINT { \
"RALLY_FETCH_POINT", \
3, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_rally_fetch_point_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_rally_fetch_point_t, target_component) }, \
{ "idx", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_rally_fetch_point_t, idx) }, \
} \
}
#endif
/**
* @brief Pack a rally_fetch_point 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.
* @param idx Point index (first point is 0).
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_rally_fetch_point_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, uint8_t idx)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_RALLY_FETCH_POINT_LEN];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint8_t(buf, 2, idx);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RALLY_FETCH_POINT_LEN);
#else
mavlink_rally_fetch_point_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.idx = idx;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RALLY_FETCH_POINT_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_RALLY_FETCH_POINT;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RALLY_FETCH_POINT_MIN_LEN, MAVLINK_MSG_ID_RALLY_FETCH_POINT_LEN, MAVLINK_MSG_ID_RALLY_FETCH_POINT_CRC);
}
/**
* @brief Pack a rally_fetch_point message on a channel
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID.
* @param target_component Component ID.
* @param idx Point index (first point is 0).
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_rally_fetch_point_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 idx)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_RALLY_FETCH_POINT_LEN];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint8_t(buf, 2, idx);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RALLY_FETCH_POINT_LEN);
#else
mavlink_rally_fetch_point_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.idx = idx;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RALLY_FETCH_POINT_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_RALLY_FETCH_POINT;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RALLY_FETCH_POINT_MIN_LEN, MAVLINK_MSG_ID_RALLY_FETCH_POINT_LEN, MAVLINK_MSG_ID_RALLY_FETCH_POINT_CRC);
}
/**
* @brief Encode a rally_fetch_point struct
*
* @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 rally_fetch_point C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_rally_fetch_point_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_rally_fetch_point_t* rally_fetch_point)
{
return mavlink_msg_rally_fetch_point_pack(system_id, component_id, msg, rally_fetch_point->target_system, rally_fetch_point->target_component, rally_fetch_point->idx);
}
/**
* @brief Encode a rally_fetch_point struct on a channel
*
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param rally_fetch_point C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_rally_fetch_point_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_rally_fetch_point_t* rally_fetch_point)
{
return mavlink_msg_rally_fetch_point_pack_chan(system_id, component_id, chan, msg, rally_fetch_point->target_system, rally_fetch_point->target_component, rally_fetch_point->idx);
}
/**
* @brief Send a rally_fetch_point message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID.
* @param target_component Component ID.
* @param idx Point index (first point is 0).
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_rally_fetch_point_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t idx)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_RALLY_FETCH_POINT_LEN];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint8_t(buf, 2, idx);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RALLY_FETCH_POINT, buf, MAVLINK_MSG_ID_RALLY_FETCH_POINT_MIN_LEN, MAVLINK_MSG_ID_RALLY_FETCH_POINT_LEN, MAVLINK_MSG_ID_RALLY_FETCH_POINT_CRC);
#else
mavlink_rally_fetch_point_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.idx = idx;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RALLY_FETCH_POINT, (const char *)&packet, MAVLINK_MSG_ID_RALLY_FETCH_POINT_MIN_LEN, MAVLINK_MSG_ID_RALLY_FETCH_POINT_LEN, MAVLINK_MSG_ID_RALLY_FETCH_POINT_CRC);
#endif
}
/**
* @brief Send a rally_fetch_point message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_rally_fetch_point_send_struct(mavlink_channel_t chan, const mavlink_rally_fetch_point_t* rally_fetch_point)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_rally_fetch_point_send(chan, rally_fetch_point->target_system, rally_fetch_point->target_component, rally_fetch_point->idx);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RALLY_FETCH_POINT, (const char *)rally_fetch_point, MAVLINK_MSG_ID_RALLY_FETCH_POINT_MIN_LEN, MAVLINK_MSG_ID_RALLY_FETCH_POINT_LEN, MAVLINK_MSG_ID_RALLY_FETCH_POINT_CRC);
#endif
}
#if MAVLINK_MSG_ID_RALLY_FETCH_POINT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_rally_fetch_point_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t idx)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint8_t(buf, 2, idx);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RALLY_FETCH_POINT, buf, MAVLINK_MSG_ID_RALLY_FETCH_POINT_MIN_LEN, MAVLINK_MSG_ID_RALLY_FETCH_POINT_LEN, MAVLINK_MSG_ID_RALLY_FETCH_POINT_CRC);
#else
mavlink_rally_fetch_point_t *packet = (mavlink_rally_fetch_point_t *)msgbuf;
packet->target_system = target_system;
packet->target_component = target_component;
packet->idx = idx;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RALLY_FETCH_POINT, (const char *)packet, MAVLINK_MSG_ID_RALLY_FETCH_POINT_MIN_LEN, MAVLINK_MSG_ID_RALLY_FETCH_POINT_LEN, MAVLINK_MSG_ID_RALLY_FETCH_POINT_CRC);
#endif
}
#endif
#endif
// MESSAGE RALLY_FETCH_POINT UNPACKING
/**
* @brief Get field target_system from rally_fetch_point message
*
* @return System ID.
*/
static inline uint8_t mavlink_msg_rally_fetch_point_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 0);
}
/**
* @brief Get field target_component from rally_fetch_point message
*
* @return Component ID.
*/
static inline uint8_t mavlink_msg_rally_fetch_point_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 1);
}
/**
* @brief Get field idx from rally_fetch_point message
*
* @return Point index (first point is 0).
*/
static inline uint8_t mavlink_msg_rally_fetch_point_get_idx(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 2);
}
/**
* @brief Decode a rally_fetch_point message into a struct
*
* @param msg The message to decode
* @param rally_fetch_point C-struct to decode the message contents into
*/
static inline void mavlink_msg_rally_fetch_point_decode(const mavlink_message_t* msg, mavlink_rally_fetch_point_t* rally_fetch_point)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
rally_fetch_point->target_system = mavlink_msg_rally_fetch_point_get_target_system(msg);
rally_fetch_point->target_component = mavlink_msg_rally_fetch_point_get_target_component(msg);
rally_fetch_point->idx = mavlink_msg_rally_fetch_point_get_idx(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_RALLY_FETCH_POINT_LEN? msg->len : MAVLINK_MSG_ID_RALLY_FETCH_POINT_LEN;
memset(rally_fetch_point, 0, MAVLINK_MSG_ID_RALLY_FETCH_POINT_LEN);
memcpy(rally_fetch_point, _MAV_PAYLOAD(msg), len);
#endif
}

View File

@@ -0,0 +1,438 @@
#pragma once
// MESSAGE RALLY_POINT PACKING
#define MAVLINK_MSG_ID_RALLY_POINT 175
MAVPACKED(
typedef struct __mavlink_rally_point_t {
int32_t lat; /*< [degE7] Latitude of point.*/
int32_t lng; /*< [degE7] Longitude of point.*/
int16_t alt; /*< [m] Transit / loiter altitude relative to home.*/
int16_t break_alt; /*< [m] Break altitude relative to home.*/
uint16_t land_dir; /*< [cdeg] Heading to aim for when landing.*/
uint8_t target_system; /*< System ID.*/
uint8_t target_component; /*< Component ID.*/
uint8_t idx; /*< Point index (first point is 0).*/
uint8_t count; /*< Total number of points (for sanity checking).*/
uint8_t flags; /*< Configuration flags.*/
}) mavlink_rally_point_t;
#define MAVLINK_MSG_ID_RALLY_POINT_LEN 19
#define MAVLINK_MSG_ID_RALLY_POINT_MIN_LEN 19
#define MAVLINK_MSG_ID_175_LEN 19
#define MAVLINK_MSG_ID_175_MIN_LEN 19
#define MAVLINK_MSG_ID_RALLY_POINT_CRC 138
#define MAVLINK_MSG_ID_175_CRC 138
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_RALLY_POINT { \
175, \
"RALLY_POINT", \
10, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 14, offsetof(mavlink_rally_point_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 15, offsetof(mavlink_rally_point_t, target_component) }, \
{ "idx", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_rally_point_t, idx) }, \
{ "count", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_rally_point_t, count) }, \
{ "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_rally_point_t, lat) }, \
{ "lng", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_rally_point_t, lng) }, \
{ "alt", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_rally_point_t, alt) }, \
{ "break_alt", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_rally_point_t, break_alt) }, \
{ "land_dir", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_rally_point_t, land_dir) }, \
{ "flags", NULL, MAVLINK_TYPE_UINT8_T, 0, 18, offsetof(mavlink_rally_point_t, flags) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_RALLY_POINT { \
"RALLY_POINT", \
10, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 14, offsetof(mavlink_rally_point_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 15, offsetof(mavlink_rally_point_t, target_component) }, \
{ "idx", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_rally_point_t, idx) }, \
{ "count", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_rally_point_t, count) }, \
{ "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_rally_point_t, lat) }, \
{ "lng", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_rally_point_t, lng) }, \
{ "alt", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_rally_point_t, alt) }, \
{ "break_alt", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_rally_point_t, break_alt) }, \
{ "land_dir", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_rally_point_t, land_dir) }, \
{ "flags", NULL, MAVLINK_TYPE_UINT8_T, 0, 18, offsetof(mavlink_rally_point_t, flags) }, \
} \
}
#endif
/**
* @brief Pack a rally_point 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.
* @param idx Point index (first point is 0).
* @param count Total number of points (for sanity checking).
* @param lat [degE7] Latitude of point.
* @param lng [degE7] Longitude of point.
* @param alt [m] Transit / loiter altitude relative to home.
* @param break_alt [m] Break altitude relative to home.
* @param land_dir [cdeg] Heading to aim for when landing.
* @param flags Configuration flags.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_rally_point_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, uint8_t idx, uint8_t count, int32_t lat, int32_t lng, int16_t alt, int16_t break_alt, uint16_t land_dir, uint8_t flags)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_RALLY_POINT_LEN];
_mav_put_int32_t(buf, 0, lat);
_mav_put_int32_t(buf, 4, lng);
_mav_put_int16_t(buf, 8, alt);
_mav_put_int16_t(buf, 10, break_alt);
_mav_put_uint16_t(buf, 12, land_dir);
_mav_put_uint8_t(buf, 14, target_system);
_mav_put_uint8_t(buf, 15, target_component);
_mav_put_uint8_t(buf, 16, idx);
_mav_put_uint8_t(buf, 17, count);
_mav_put_uint8_t(buf, 18, flags);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RALLY_POINT_LEN);
#else
mavlink_rally_point_t packet;
packet.lat = lat;
packet.lng = lng;
packet.alt = alt;
packet.break_alt = break_alt;
packet.land_dir = land_dir;
packet.target_system = target_system;
packet.target_component = target_component;
packet.idx = idx;
packet.count = count;
packet.flags = flags;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RALLY_POINT_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_RALLY_POINT;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RALLY_POINT_MIN_LEN, MAVLINK_MSG_ID_RALLY_POINT_LEN, MAVLINK_MSG_ID_RALLY_POINT_CRC);
}
/**
* @brief Pack a rally_point message on a channel
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID.
* @param target_component Component ID.
* @param idx Point index (first point is 0).
* @param count Total number of points (for sanity checking).
* @param lat [degE7] Latitude of point.
* @param lng [degE7] Longitude of point.
* @param alt [m] Transit / loiter altitude relative to home.
* @param break_alt [m] Break altitude relative to home.
* @param land_dir [cdeg] Heading to aim for when landing.
* @param flags Configuration flags.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_rally_point_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 idx,uint8_t count,int32_t lat,int32_t lng,int16_t alt,int16_t break_alt,uint16_t land_dir,uint8_t flags)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_RALLY_POINT_LEN];
_mav_put_int32_t(buf, 0, lat);
_mav_put_int32_t(buf, 4, lng);
_mav_put_int16_t(buf, 8, alt);
_mav_put_int16_t(buf, 10, break_alt);
_mav_put_uint16_t(buf, 12, land_dir);
_mav_put_uint8_t(buf, 14, target_system);
_mav_put_uint8_t(buf, 15, target_component);
_mav_put_uint8_t(buf, 16, idx);
_mav_put_uint8_t(buf, 17, count);
_mav_put_uint8_t(buf, 18, flags);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RALLY_POINT_LEN);
#else
mavlink_rally_point_t packet;
packet.lat = lat;
packet.lng = lng;
packet.alt = alt;
packet.break_alt = break_alt;
packet.land_dir = land_dir;
packet.target_system = target_system;
packet.target_component = target_component;
packet.idx = idx;
packet.count = count;
packet.flags = flags;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RALLY_POINT_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_RALLY_POINT;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RALLY_POINT_MIN_LEN, MAVLINK_MSG_ID_RALLY_POINT_LEN, MAVLINK_MSG_ID_RALLY_POINT_CRC);
}
/**
* @brief Encode a rally_point struct
*
* @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 rally_point C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_rally_point_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_rally_point_t* rally_point)
{
return mavlink_msg_rally_point_pack(system_id, component_id, msg, rally_point->target_system, rally_point->target_component, rally_point->idx, rally_point->count, rally_point->lat, rally_point->lng, rally_point->alt, rally_point->break_alt, rally_point->land_dir, rally_point->flags);
}
/**
* @brief Encode a rally_point struct on a channel
*
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param rally_point C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_rally_point_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_rally_point_t* rally_point)
{
return mavlink_msg_rally_point_pack_chan(system_id, component_id, chan, msg, rally_point->target_system, rally_point->target_component, rally_point->idx, rally_point->count, rally_point->lat, rally_point->lng, rally_point->alt, rally_point->break_alt, rally_point->land_dir, rally_point->flags);
}
/**
* @brief Send a rally_point message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID.
* @param target_component Component ID.
* @param idx Point index (first point is 0).
* @param count Total number of points (for sanity checking).
* @param lat [degE7] Latitude of point.
* @param lng [degE7] Longitude of point.
* @param alt [m] Transit / loiter altitude relative to home.
* @param break_alt [m] Break altitude relative to home.
* @param land_dir [cdeg] Heading to aim for when landing.
* @param flags Configuration flags.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_rally_point_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t idx, uint8_t count, int32_t lat, int32_t lng, int16_t alt, int16_t break_alt, uint16_t land_dir, uint8_t flags)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_RALLY_POINT_LEN];
_mav_put_int32_t(buf, 0, lat);
_mav_put_int32_t(buf, 4, lng);
_mav_put_int16_t(buf, 8, alt);
_mav_put_int16_t(buf, 10, break_alt);
_mav_put_uint16_t(buf, 12, land_dir);
_mav_put_uint8_t(buf, 14, target_system);
_mav_put_uint8_t(buf, 15, target_component);
_mav_put_uint8_t(buf, 16, idx);
_mav_put_uint8_t(buf, 17, count);
_mav_put_uint8_t(buf, 18, flags);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RALLY_POINT, buf, MAVLINK_MSG_ID_RALLY_POINT_MIN_LEN, MAVLINK_MSG_ID_RALLY_POINT_LEN, MAVLINK_MSG_ID_RALLY_POINT_CRC);
#else
mavlink_rally_point_t packet;
packet.lat = lat;
packet.lng = lng;
packet.alt = alt;
packet.break_alt = break_alt;
packet.land_dir = land_dir;
packet.target_system = target_system;
packet.target_component = target_component;
packet.idx = idx;
packet.count = count;
packet.flags = flags;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RALLY_POINT, (const char *)&packet, MAVLINK_MSG_ID_RALLY_POINT_MIN_LEN, MAVLINK_MSG_ID_RALLY_POINT_LEN, MAVLINK_MSG_ID_RALLY_POINT_CRC);
#endif
}
/**
* @brief Send a rally_point message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_rally_point_send_struct(mavlink_channel_t chan, const mavlink_rally_point_t* rally_point)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_rally_point_send(chan, rally_point->target_system, rally_point->target_component, rally_point->idx, rally_point->count, rally_point->lat, rally_point->lng, rally_point->alt, rally_point->break_alt, rally_point->land_dir, rally_point->flags);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RALLY_POINT, (const char *)rally_point, MAVLINK_MSG_ID_RALLY_POINT_MIN_LEN, MAVLINK_MSG_ID_RALLY_POINT_LEN, MAVLINK_MSG_ID_RALLY_POINT_CRC);
#endif
}
#if MAVLINK_MSG_ID_RALLY_POINT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_rally_point_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t idx, uint8_t count, int32_t lat, int32_t lng, int16_t alt, int16_t break_alt, uint16_t land_dir, uint8_t flags)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_int32_t(buf, 0, lat);
_mav_put_int32_t(buf, 4, lng);
_mav_put_int16_t(buf, 8, alt);
_mav_put_int16_t(buf, 10, break_alt);
_mav_put_uint16_t(buf, 12, land_dir);
_mav_put_uint8_t(buf, 14, target_system);
_mav_put_uint8_t(buf, 15, target_component);
_mav_put_uint8_t(buf, 16, idx);
_mav_put_uint8_t(buf, 17, count);
_mav_put_uint8_t(buf, 18, flags);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RALLY_POINT, buf, MAVLINK_MSG_ID_RALLY_POINT_MIN_LEN, MAVLINK_MSG_ID_RALLY_POINT_LEN, MAVLINK_MSG_ID_RALLY_POINT_CRC);
#else
mavlink_rally_point_t *packet = (mavlink_rally_point_t *)msgbuf;
packet->lat = lat;
packet->lng = lng;
packet->alt = alt;
packet->break_alt = break_alt;
packet->land_dir = land_dir;
packet->target_system = target_system;
packet->target_component = target_component;
packet->idx = idx;
packet->count = count;
packet->flags = flags;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RALLY_POINT, (const char *)packet, MAVLINK_MSG_ID_RALLY_POINT_MIN_LEN, MAVLINK_MSG_ID_RALLY_POINT_LEN, MAVLINK_MSG_ID_RALLY_POINT_CRC);
#endif
}
#endif
#endif
// MESSAGE RALLY_POINT UNPACKING
/**
* @brief Get field target_system from rally_point message
*
* @return System ID.
*/
static inline uint8_t mavlink_msg_rally_point_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 14);
}
/**
* @brief Get field target_component from rally_point message
*
* @return Component ID.
*/
static inline uint8_t mavlink_msg_rally_point_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 15);
}
/**
* @brief Get field idx from rally_point message
*
* @return Point index (first point is 0).
*/
static inline uint8_t mavlink_msg_rally_point_get_idx(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 16);
}
/**
* @brief Get field count from rally_point message
*
* @return Total number of points (for sanity checking).
*/
static inline uint8_t mavlink_msg_rally_point_get_count(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 17);
}
/**
* @brief Get field lat from rally_point message
*
* @return [degE7] Latitude of point.
*/
static inline int32_t mavlink_msg_rally_point_get_lat(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 0);
}
/**
* @brief Get field lng from rally_point message
*
* @return [degE7] Longitude of point.
*/
static inline int32_t mavlink_msg_rally_point_get_lng(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 4);
}
/**
* @brief Get field alt from rally_point message
*
* @return [m] Transit / loiter altitude relative to home.
*/
static inline int16_t mavlink_msg_rally_point_get_alt(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 8);
}
/**
* @brief Get field break_alt from rally_point message
*
* @return [m] Break altitude relative to home.
*/
static inline int16_t mavlink_msg_rally_point_get_break_alt(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 10);
}
/**
* @brief Get field land_dir from rally_point message
*
* @return [cdeg] Heading to aim for when landing.
*/
static inline uint16_t mavlink_msg_rally_point_get_land_dir(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 12);
}
/**
* @brief Get field flags from rally_point message
*
* @return Configuration flags.
*/
static inline uint8_t mavlink_msg_rally_point_get_flags(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 18);
}
/**
* @brief Decode a rally_point message into a struct
*
* @param msg The message to decode
* @param rally_point C-struct to decode the message contents into
*/
static inline void mavlink_msg_rally_point_decode(const mavlink_message_t* msg, mavlink_rally_point_t* rally_point)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
rally_point->lat = mavlink_msg_rally_point_get_lat(msg);
rally_point->lng = mavlink_msg_rally_point_get_lng(msg);
rally_point->alt = mavlink_msg_rally_point_get_alt(msg);
rally_point->break_alt = mavlink_msg_rally_point_get_break_alt(msg);
rally_point->land_dir = mavlink_msg_rally_point_get_land_dir(msg);
rally_point->target_system = mavlink_msg_rally_point_get_target_system(msg);
rally_point->target_component = mavlink_msg_rally_point_get_target_component(msg);
rally_point->idx = mavlink_msg_rally_point_get_idx(msg);
rally_point->count = mavlink_msg_rally_point_get_count(msg);
rally_point->flags = mavlink_msg_rally_point_get_flags(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_RALLY_POINT_LEN? msg->len : MAVLINK_MSG_ID_RALLY_POINT_LEN;
memset(rally_point, 0, MAVLINK_MSG_ID_RALLY_POINT_LEN);
memcpy(rally_point, _MAV_PAYLOAD(msg), len);
#endif
}

View File

@@ -0,0 +1,238 @@
#pragma once
// MESSAGE RANGEFINDER PACKING
#define MAVLINK_MSG_ID_RANGEFINDER 173
MAVPACKED(
typedef struct __mavlink_rangefinder_t {
float distance; /*< [m] Distance.*/
float voltage; /*< [V] Raw voltage if available, zero otherwise.*/
}) mavlink_rangefinder_t;
#define MAVLINK_MSG_ID_RANGEFINDER_LEN 8
#define MAVLINK_MSG_ID_RANGEFINDER_MIN_LEN 8
#define MAVLINK_MSG_ID_173_LEN 8
#define MAVLINK_MSG_ID_173_MIN_LEN 8
#define MAVLINK_MSG_ID_RANGEFINDER_CRC 83
#define MAVLINK_MSG_ID_173_CRC 83
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_RANGEFINDER { \
173, \
"RANGEFINDER", \
2, \
{ { "distance", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_rangefinder_t, distance) }, \
{ "voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_rangefinder_t, voltage) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_RANGEFINDER { \
"RANGEFINDER", \
2, \
{ { "distance", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_rangefinder_t, distance) }, \
{ "voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_rangefinder_t, voltage) }, \
} \
}
#endif
/**
* @brief Pack a rangefinder 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 distance [m] Distance.
* @param voltage [V] Raw voltage if available, zero otherwise.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_rangefinder_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
float distance, float voltage)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_RANGEFINDER_LEN];
_mav_put_float(buf, 0, distance);
_mav_put_float(buf, 4, voltage);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RANGEFINDER_LEN);
#else
mavlink_rangefinder_t packet;
packet.distance = distance;
packet.voltage = voltage;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RANGEFINDER_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_RANGEFINDER;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RANGEFINDER_MIN_LEN, MAVLINK_MSG_ID_RANGEFINDER_LEN, MAVLINK_MSG_ID_RANGEFINDER_CRC);
}
/**
* @brief Pack a rangefinder message on a channel
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param distance [m] Distance.
* @param voltage [V] Raw voltage if available, zero otherwise.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_rangefinder_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
float distance,float voltage)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_RANGEFINDER_LEN];
_mav_put_float(buf, 0, distance);
_mav_put_float(buf, 4, voltage);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RANGEFINDER_LEN);
#else
mavlink_rangefinder_t packet;
packet.distance = distance;
packet.voltage = voltage;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RANGEFINDER_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_RANGEFINDER;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RANGEFINDER_MIN_LEN, MAVLINK_MSG_ID_RANGEFINDER_LEN, MAVLINK_MSG_ID_RANGEFINDER_CRC);
}
/**
* @brief Encode a rangefinder struct
*
* @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 rangefinder C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_rangefinder_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_rangefinder_t* rangefinder)
{
return mavlink_msg_rangefinder_pack(system_id, component_id, msg, rangefinder->distance, rangefinder->voltage);
}
/**
* @brief Encode a rangefinder struct on a channel
*
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param rangefinder C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_rangefinder_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_rangefinder_t* rangefinder)
{
return mavlink_msg_rangefinder_pack_chan(system_id, component_id, chan, msg, rangefinder->distance, rangefinder->voltage);
}
/**
* @brief Send a rangefinder message
* @param chan MAVLink channel to send the message
*
* @param distance [m] Distance.
* @param voltage [V] Raw voltage if available, zero otherwise.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_rangefinder_send(mavlink_channel_t chan, float distance, float voltage)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_RANGEFINDER_LEN];
_mav_put_float(buf, 0, distance);
_mav_put_float(buf, 4, voltage);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RANGEFINDER, buf, MAVLINK_MSG_ID_RANGEFINDER_MIN_LEN, MAVLINK_MSG_ID_RANGEFINDER_LEN, MAVLINK_MSG_ID_RANGEFINDER_CRC);
#else
mavlink_rangefinder_t packet;
packet.distance = distance;
packet.voltage = voltage;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RANGEFINDER, (const char *)&packet, MAVLINK_MSG_ID_RANGEFINDER_MIN_LEN, MAVLINK_MSG_ID_RANGEFINDER_LEN, MAVLINK_MSG_ID_RANGEFINDER_CRC);
#endif
}
/**
* @brief Send a rangefinder message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_rangefinder_send_struct(mavlink_channel_t chan, const mavlink_rangefinder_t* rangefinder)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_rangefinder_send(chan, rangefinder->distance, rangefinder->voltage);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RANGEFINDER, (const char *)rangefinder, MAVLINK_MSG_ID_RANGEFINDER_MIN_LEN, MAVLINK_MSG_ID_RANGEFINDER_LEN, MAVLINK_MSG_ID_RANGEFINDER_CRC);
#endif
}
#if MAVLINK_MSG_ID_RANGEFINDER_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_rangefinder_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float distance, float voltage)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_float(buf, 0, distance);
_mav_put_float(buf, 4, voltage);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RANGEFINDER, buf, MAVLINK_MSG_ID_RANGEFINDER_MIN_LEN, MAVLINK_MSG_ID_RANGEFINDER_LEN, MAVLINK_MSG_ID_RANGEFINDER_CRC);
#else
mavlink_rangefinder_t *packet = (mavlink_rangefinder_t *)msgbuf;
packet->distance = distance;
packet->voltage = voltage;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RANGEFINDER, (const char *)packet, MAVLINK_MSG_ID_RANGEFINDER_MIN_LEN, MAVLINK_MSG_ID_RANGEFINDER_LEN, MAVLINK_MSG_ID_RANGEFINDER_CRC);
#endif
}
#endif
#endif
// MESSAGE RANGEFINDER UNPACKING
/**
* @brief Get field distance from rangefinder message
*
* @return [m] Distance.
*/
static inline float mavlink_msg_rangefinder_get_distance(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 0);
}
/**
* @brief Get field voltage from rangefinder message
*
* @return [V] Raw voltage if available, zero otherwise.
*/
static inline float mavlink_msg_rangefinder_get_voltage(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 4);
}
/**
* @brief Decode a rangefinder message into a struct
*
* @param msg The message to decode
* @param rangefinder C-struct to decode the message contents into
*/
static inline void mavlink_msg_rangefinder_decode(const mavlink_message_t* msg, mavlink_rangefinder_t* rangefinder)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
rangefinder->distance = mavlink_msg_rangefinder_get_distance(msg);
rangefinder->voltage = mavlink_msg_rangefinder_get_voltage(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_RANGEFINDER_LEN? msg->len : MAVLINK_MSG_ID_RANGEFINDER_LEN;
memset(rangefinder, 0, MAVLINK_MSG_ID_RANGEFINDER_LEN);
memcpy(rangefinder, _MAV_PAYLOAD(msg), len);
#endif
}

View File

@@ -0,0 +1,288 @@
#pragma once
// MESSAGE REMOTE_LOG_BLOCK_STATUS PACKING
#define MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS 185
MAVPACKED(
typedef struct __mavlink_remote_log_block_status_t {
uint32_t seqno; /*< Log data block sequence number.*/
uint8_t target_system; /*< System ID.*/
uint8_t target_component; /*< Component ID.*/
uint8_t status; /*< Log data block status.*/
}) mavlink_remote_log_block_status_t;
#define MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS_LEN 7
#define MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS_MIN_LEN 7
#define MAVLINK_MSG_ID_185_LEN 7
#define MAVLINK_MSG_ID_185_MIN_LEN 7
#define MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS_CRC 186
#define MAVLINK_MSG_ID_185_CRC 186
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_REMOTE_LOG_BLOCK_STATUS { \
185, \
"REMOTE_LOG_BLOCK_STATUS", \
4, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_remote_log_block_status_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_remote_log_block_status_t, target_component) }, \
{ "seqno", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_remote_log_block_status_t, seqno) }, \
{ "status", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_remote_log_block_status_t, status) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_REMOTE_LOG_BLOCK_STATUS { \
"REMOTE_LOG_BLOCK_STATUS", \
4, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_remote_log_block_status_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_remote_log_block_status_t, target_component) }, \
{ "seqno", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_remote_log_block_status_t, seqno) }, \
{ "status", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_remote_log_block_status_t, status) }, \
} \
}
#endif
/**
* @brief Pack a remote_log_block_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 target_system System ID.
* @param target_component Component ID.
* @param seqno Log data block sequence number.
* @param status Log data block status.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_remote_log_block_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, uint32_t seqno, uint8_t status)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS_LEN];
_mav_put_uint32_t(buf, 0, seqno);
_mav_put_uint8_t(buf, 4, target_system);
_mav_put_uint8_t(buf, 5, target_component);
_mav_put_uint8_t(buf, 6, status);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS_LEN);
#else
mavlink_remote_log_block_status_t packet;
packet.seqno = seqno;
packet.target_system = target_system;
packet.target_component = target_component;
packet.status = status;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS_MIN_LEN, MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS_LEN, MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS_CRC);
}
/**
* @brief Pack a remote_log_block_status message on a channel
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID.
* @param target_component Component ID.
* @param seqno Log data block sequence number.
* @param status Log data block status.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_remote_log_block_status_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,uint32_t seqno,uint8_t status)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS_LEN];
_mav_put_uint32_t(buf, 0, seqno);
_mav_put_uint8_t(buf, 4, target_system);
_mav_put_uint8_t(buf, 5, target_component);
_mav_put_uint8_t(buf, 6, status);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS_LEN);
#else
mavlink_remote_log_block_status_t packet;
packet.seqno = seqno;
packet.target_system = target_system;
packet.target_component = target_component;
packet.status = status;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS_MIN_LEN, MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS_LEN, MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS_CRC);
}
/**
* @brief Encode a remote_log_block_status struct
*
* @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 remote_log_block_status C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_remote_log_block_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_remote_log_block_status_t* remote_log_block_status)
{
return mavlink_msg_remote_log_block_status_pack(system_id, component_id, msg, remote_log_block_status->target_system, remote_log_block_status->target_component, remote_log_block_status->seqno, remote_log_block_status->status);
}
/**
* @brief Encode a remote_log_block_status struct on a channel
*
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param remote_log_block_status C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_remote_log_block_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_remote_log_block_status_t* remote_log_block_status)
{
return mavlink_msg_remote_log_block_status_pack_chan(system_id, component_id, chan, msg, remote_log_block_status->target_system, remote_log_block_status->target_component, remote_log_block_status->seqno, remote_log_block_status->status);
}
/**
* @brief Send a remote_log_block_status message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID.
* @param target_component Component ID.
* @param seqno Log data block sequence number.
* @param status Log data block status.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_remote_log_block_status_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint32_t seqno, uint8_t status)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS_LEN];
_mav_put_uint32_t(buf, 0, seqno);
_mav_put_uint8_t(buf, 4, target_system);
_mav_put_uint8_t(buf, 5, target_component);
_mav_put_uint8_t(buf, 6, status);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS, buf, MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS_MIN_LEN, MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS_LEN, MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS_CRC);
#else
mavlink_remote_log_block_status_t packet;
packet.seqno = seqno;
packet.target_system = target_system;
packet.target_component = target_component;
packet.status = status;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS, (const char *)&packet, MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS_MIN_LEN, MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS_LEN, MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS_CRC);
#endif
}
/**
* @brief Send a remote_log_block_status message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_remote_log_block_status_send_struct(mavlink_channel_t chan, const mavlink_remote_log_block_status_t* remote_log_block_status)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_remote_log_block_status_send(chan, remote_log_block_status->target_system, remote_log_block_status->target_component, remote_log_block_status->seqno, remote_log_block_status->status);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS, (const char *)remote_log_block_status, MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS_MIN_LEN, MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS_LEN, MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS_CRC);
#endif
}
#if MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_remote_log_block_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint32_t seqno, uint8_t status)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint32_t(buf, 0, seqno);
_mav_put_uint8_t(buf, 4, target_system);
_mav_put_uint8_t(buf, 5, target_component);
_mav_put_uint8_t(buf, 6, status);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS, buf, MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS_MIN_LEN, MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS_LEN, MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS_CRC);
#else
mavlink_remote_log_block_status_t *packet = (mavlink_remote_log_block_status_t *)msgbuf;
packet->seqno = seqno;
packet->target_system = target_system;
packet->target_component = target_component;
packet->status = status;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS, (const char *)packet, MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS_MIN_LEN, MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS_LEN, MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS_CRC);
#endif
}
#endif
#endif
// MESSAGE REMOTE_LOG_BLOCK_STATUS UNPACKING
/**
* @brief Get field target_system from remote_log_block_status message
*
* @return System ID.
*/
static inline uint8_t mavlink_msg_remote_log_block_status_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 4);
}
/**
* @brief Get field target_component from remote_log_block_status message
*
* @return Component ID.
*/
static inline uint8_t mavlink_msg_remote_log_block_status_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 5);
}
/**
* @brief Get field seqno from remote_log_block_status message
*
* @return Log data block sequence number.
*/
static inline uint32_t mavlink_msg_remote_log_block_status_get_seqno(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 0);
}
/**
* @brief Get field status from remote_log_block_status message
*
* @return Log data block status.
*/
static inline uint8_t mavlink_msg_remote_log_block_status_get_status(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 6);
}
/**
* @brief Decode a remote_log_block_status message into a struct
*
* @param msg The message to decode
* @param remote_log_block_status C-struct to decode the message contents into
*/
static inline void mavlink_msg_remote_log_block_status_decode(const mavlink_message_t* msg, mavlink_remote_log_block_status_t* remote_log_block_status)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
remote_log_block_status->seqno = mavlink_msg_remote_log_block_status_get_seqno(msg);
remote_log_block_status->target_system = mavlink_msg_remote_log_block_status_get_target_system(msg);
remote_log_block_status->target_component = mavlink_msg_remote_log_block_status_get_target_component(msg);
remote_log_block_status->status = mavlink_msg_remote_log_block_status_get_status(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS_LEN? msg->len : MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS_LEN;
memset(remote_log_block_status, 0, MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS_LEN);
memcpy(remote_log_block_status, _MAV_PAYLOAD(msg), len);
#endif
}

View File

@@ -0,0 +1,280 @@
#pragma once
// MESSAGE REMOTE_LOG_DATA_BLOCK PACKING
#define MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK 184
MAVPACKED(
typedef struct __mavlink_remote_log_data_block_t {
uint32_t seqno; /*< Log data block sequence number.*/
uint8_t target_system; /*< System ID.*/
uint8_t target_component; /*< Component ID.*/
uint8_t data[200]; /*< Log data block.*/
}) mavlink_remote_log_data_block_t;
#define MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK_LEN 206
#define MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK_MIN_LEN 206
#define MAVLINK_MSG_ID_184_LEN 206
#define MAVLINK_MSG_ID_184_MIN_LEN 206
#define MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK_CRC 159
#define MAVLINK_MSG_ID_184_CRC 159
#define MAVLINK_MSG_REMOTE_LOG_DATA_BLOCK_FIELD_DATA_LEN 200
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_REMOTE_LOG_DATA_BLOCK { \
184, \
"REMOTE_LOG_DATA_BLOCK", \
4, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_remote_log_data_block_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_remote_log_data_block_t, target_component) }, \
{ "seqno", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_remote_log_data_block_t, seqno) }, \
{ "data", NULL, MAVLINK_TYPE_UINT8_T, 200, 6, offsetof(mavlink_remote_log_data_block_t, data) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_REMOTE_LOG_DATA_BLOCK { \
"REMOTE_LOG_DATA_BLOCK", \
4, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_remote_log_data_block_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_remote_log_data_block_t, target_component) }, \
{ "seqno", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_remote_log_data_block_t, seqno) }, \
{ "data", NULL, MAVLINK_TYPE_UINT8_T, 200, 6, offsetof(mavlink_remote_log_data_block_t, data) }, \
} \
}
#endif
/**
* @brief Pack a remote_log_data_block 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.
* @param seqno Log data block sequence number.
* @param data Log data block.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_remote_log_data_block_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, uint32_t seqno, const uint8_t *data)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK_LEN];
_mav_put_uint32_t(buf, 0, seqno);
_mav_put_uint8_t(buf, 4, target_system);
_mav_put_uint8_t(buf, 5, target_component);
_mav_put_uint8_t_array(buf, 6, data, 200);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK_LEN);
#else
mavlink_remote_log_data_block_t packet;
packet.seqno = seqno;
packet.target_system = target_system;
packet.target_component = target_component;
mav_array_memcpy(packet.data, data, sizeof(uint8_t)*200);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK_MIN_LEN, MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK_LEN, MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK_CRC);
}
/**
* @brief Pack a remote_log_data_block message on a channel
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID.
* @param target_component Component ID.
* @param seqno Log data block sequence number.
* @param data Log data block.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_remote_log_data_block_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,uint32_t seqno,const uint8_t *data)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK_LEN];
_mav_put_uint32_t(buf, 0, seqno);
_mav_put_uint8_t(buf, 4, target_system);
_mav_put_uint8_t(buf, 5, target_component);
_mav_put_uint8_t_array(buf, 6, data, 200);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK_LEN);
#else
mavlink_remote_log_data_block_t packet;
packet.seqno = seqno;
packet.target_system = target_system;
packet.target_component = target_component;
mav_array_memcpy(packet.data, data, sizeof(uint8_t)*200);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK_MIN_LEN, MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK_LEN, MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK_CRC);
}
/**
* @brief Encode a remote_log_data_block struct
*
* @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 remote_log_data_block C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_remote_log_data_block_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_remote_log_data_block_t* remote_log_data_block)
{
return mavlink_msg_remote_log_data_block_pack(system_id, component_id, msg, remote_log_data_block->target_system, remote_log_data_block->target_component, remote_log_data_block->seqno, remote_log_data_block->data);
}
/**
* @brief Encode a remote_log_data_block struct on a channel
*
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param remote_log_data_block C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_remote_log_data_block_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_remote_log_data_block_t* remote_log_data_block)
{
return mavlink_msg_remote_log_data_block_pack_chan(system_id, component_id, chan, msg, remote_log_data_block->target_system, remote_log_data_block->target_component, remote_log_data_block->seqno, remote_log_data_block->data);
}
/**
* @brief Send a remote_log_data_block message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID.
* @param target_component Component ID.
* @param seqno Log data block sequence number.
* @param data Log data block.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_remote_log_data_block_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint32_t seqno, const uint8_t *data)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK_LEN];
_mav_put_uint32_t(buf, 0, seqno);
_mav_put_uint8_t(buf, 4, target_system);
_mav_put_uint8_t(buf, 5, target_component);
_mav_put_uint8_t_array(buf, 6, data, 200);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK, buf, MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK_MIN_LEN, MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK_LEN, MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK_CRC);
#else
mavlink_remote_log_data_block_t packet;
packet.seqno = seqno;
packet.target_system = target_system;
packet.target_component = target_component;
mav_array_memcpy(packet.data, data, sizeof(uint8_t)*200);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK, (const char *)&packet, MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK_MIN_LEN, MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK_LEN, MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK_CRC);
#endif
}
/**
* @brief Send a remote_log_data_block message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_remote_log_data_block_send_struct(mavlink_channel_t chan, const mavlink_remote_log_data_block_t* remote_log_data_block)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_remote_log_data_block_send(chan, remote_log_data_block->target_system, remote_log_data_block->target_component, remote_log_data_block->seqno, remote_log_data_block->data);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK, (const char *)remote_log_data_block, MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK_MIN_LEN, MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK_LEN, MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK_CRC);
#endif
}
#if MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_remote_log_data_block_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint32_t seqno, const uint8_t *data)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint32_t(buf, 0, seqno);
_mav_put_uint8_t(buf, 4, target_system);
_mav_put_uint8_t(buf, 5, target_component);
_mav_put_uint8_t_array(buf, 6, data, 200);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK, buf, MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK_MIN_LEN, MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK_LEN, MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK_CRC);
#else
mavlink_remote_log_data_block_t *packet = (mavlink_remote_log_data_block_t *)msgbuf;
packet->seqno = seqno;
packet->target_system = target_system;
packet->target_component = target_component;
mav_array_memcpy(packet->data, data, sizeof(uint8_t)*200);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK, (const char *)packet, MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK_MIN_LEN, MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK_LEN, MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK_CRC);
#endif
}
#endif
#endif
// MESSAGE REMOTE_LOG_DATA_BLOCK UNPACKING
/**
* @brief Get field target_system from remote_log_data_block message
*
* @return System ID.
*/
static inline uint8_t mavlink_msg_remote_log_data_block_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 4);
}
/**
* @brief Get field target_component from remote_log_data_block message
*
* @return Component ID.
*/
static inline uint8_t mavlink_msg_remote_log_data_block_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 5);
}
/**
* @brief Get field seqno from remote_log_data_block message
*
* @return Log data block sequence number.
*/
static inline uint32_t mavlink_msg_remote_log_data_block_get_seqno(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 0);
}
/**
* @brief Get field data from remote_log_data_block message
*
* @return Log data block.
*/
static inline uint16_t mavlink_msg_remote_log_data_block_get_data(const mavlink_message_t* msg, uint8_t *data)
{
return _MAV_RETURN_uint8_t_array(msg, data, 200, 6);
}
/**
* @brief Decode a remote_log_data_block message into a struct
*
* @param msg The message to decode
* @param remote_log_data_block C-struct to decode the message contents into
*/
static inline void mavlink_msg_remote_log_data_block_decode(const mavlink_message_t* msg, mavlink_remote_log_data_block_t* remote_log_data_block)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
remote_log_data_block->seqno = mavlink_msg_remote_log_data_block_get_seqno(msg);
remote_log_data_block->target_system = mavlink_msg_remote_log_data_block_get_target_system(msg);
remote_log_data_block->target_component = mavlink_msg_remote_log_data_block_get_target_component(msg);
mavlink_msg_remote_log_data_block_get_data(msg, remote_log_data_block->data);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK_LEN? msg->len : MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK_LEN;
memset(remote_log_data_block, 0, MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK_LEN);
memcpy(remote_log_data_block, _MAV_PAYLOAD(msg), len);
#endif
}

View File

@@ -0,0 +1,238 @@
#pragma once
// MESSAGE RPM PACKING
#define MAVLINK_MSG_ID_RPM 226
MAVPACKED(
typedef struct __mavlink_rpm_t {
float rpm1; /*< RPM Sensor1.*/
float rpm2; /*< RPM Sensor2.*/
}) mavlink_rpm_t;
#define MAVLINK_MSG_ID_RPM_LEN 8
#define MAVLINK_MSG_ID_RPM_MIN_LEN 8
#define MAVLINK_MSG_ID_226_LEN 8
#define MAVLINK_MSG_ID_226_MIN_LEN 8
#define MAVLINK_MSG_ID_RPM_CRC 207
#define MAVLINK_MSG_ID_226_CRC 207
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_RPM { \
226, \
"RPM", \
2, \
{ { "rpm1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_rpm_t, rpm1) }, \
{ "rpm2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_rpm_t, rpm2) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_RPM { \
"RPM", \
2, \
{ { "rpm1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_rpm_t, rpm1) }, \
{ "rpm2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_rpm_t, rpm2) }, \
} \
}
#endif
/**
* @brief Pack a rpm 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 rpm1 RPM Sensor1.
* @param rpm2 RPM Sensor2.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_rpm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
float rpm1, float rpm2)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_RPM_LEN];
_mav_put_float(buf, 0, rpm1);
_mav_put_float(buf, 4, rpm2);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RPM_LEN);
#else
mavlink_rpm_t packet;
packet.rpm1 = rpm1;
packet.rpm2 = rpm2;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RPM_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_RPM;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RPM_MIN_LEN, MAVLINK_MSG_ID_RPM_LEN, MAVLINK_MSG_ID_RPM_CRC);
}
/**
* @brief Pack a rpm message on a channel
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param rpm1 RPM Sensor1.
* @param rpm2 RPM Sensor2.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_rpm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
float rpm1,float rpm2)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_RPM_LEN];
_mav_put_float(buf, 0, rpm1);
_mav_put_float(buf, 4, rpm2);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RPM_LEN);
#else
mavlink_rpm_t packet;
packet.rpm1 = rpm1;
packet.rpm2 = rpm2;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RPM_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_RPM;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RPM_MIN_LEN, MAVLINK_MSG_ID_RPM_LEN, MAVLINK_MSG_ID_RPM_CRC);
}
/**
* @brief Encode a rpm struct
*
* @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 rpm C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_rpm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_rpm_t* rpm)
{
return mavlink_msg_rpm_pack(system_id, component_id, msg, rpm->rpm1, rpm->rpm2);
}
/**
* @brief Encode a rpm struct on a channel
*
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param rpm C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_rpm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_rpm_t* rpm)
{
return mavlink_msg_rpm_pack_chan(system_id, component_id, chan, msg, rpm->rpm1, rpm->rpm2);
}
/**
* @brief Send a rpm message
* @param chan MAVLink channel to send the message
*
* @param rpm1 RPM Sensor1.
* @param rpm2 RPM Sensor2.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_rpm_send(mavlink_channel_t chan, float rpm1, float rpm2)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_RPM_LEN];
_mav_put_float(buf, 0, rpm1);
_mav_put_float(buf, 4, rpm2);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RPM, buf, MAVLINK_MSG_ID_RPM_MIN_LEN, MAVLINK_MSG_ID_RPM_LEN, MAVLINK_MSG_ID_RPM_CRC);
#else
mavlink_rpm_t packet;
packet.rpm1 = rpm1;
packet.rpm2 = rpm2;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RPM, (const char *)&packet, MAVLINK_MSG_ID_RPM_MIN_LEN, MAVLINK_MSG_ID_RPM_LEN, MAVLINK_MSG_ID_RPM_CRC);
#endif
}
/**
* @brief Send a rpm message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_rpm_send_struct(mavlink_channel_t chan, const mavlink_rpm_t* rpm)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_rpm_send(chan, rpm->rpm1, rpm->rpm2);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RPM, (const char *)rpm, MAVLINK_MSG_ID_RPM_MIN_LEN, MAVLINK_MSG_ID_RPM_LEN, MAVLINK_MSG_ID_RPM_CRC);
#endif
}
#if MAVLINK_MSG_ID_RPM_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_rpm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float rpm1, float rpm2)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_float(buf, 0, rpm1);
_mav_put_float(buf, 4, rpm2);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RPM, buf, MAVLINK_MSG_ID_RPM_MIN_LEN, MAVLINK_MSG_ID_RPM_LEN, MAVLINK_MSG_ID_RPM_CRC);
#else
mavlink_rpm_t *packet = (mavlink_rpm_t *)msgbuf;
packet->rpm1 = rpm1;
packet->rpm2 = rpm2;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RPM, (const char *)packet, MAVLINK_MSG_ID_RPM_MIN_LEN, MAVLINK_MSG_ID_RPM_LEN, MAVLINK_MSG_ID_RPM_CRC);
#endif
}
#endif
#endif
// MESSAGE RPM UNPACKING
/**
* @brief Get field rpm1 from rpm message
*
* @return RPM Sensor1.
*/
static inline float mavlink_msg_rpm_get_rpm1(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 0);
}
/**
* @brief Get field rpm2 from rpm message
*
* @return RPM Sensor2.
*/
static inline float mavlink_msg_rpm_get_rpm2(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 4);
}
/**
* @brief Decode a rpm message into a struct
*
* @param msg The message to decode
* @param rpm C-struct to decode the message contents into
*/
static inline void mavlink_msg_rpm_decode(const mavlink_message_t* msg, mavlink_rpm_t* rpm)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
rpm->rpm1 = mavlink_msg_rpm_get_rpm1(msg);
rpm->rpm2 = mavlink_msg_rpm_get_rpm2(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_RPM_LEN? msg->len : MAVLINK_MSG_ID_RPM_LEN;
memset(rpm, 0, MAVLINK_MSG_ID_RPM_LEN);
memcpy(rpm, _MAV_PAYLOAD(msg), len);
#endif
}

View File

@@ -0,0 +1,488 @@
#pragma once
// MESSAGE SENSOR_OFFSETS PACKING
#define MAVLINK_MSG_ID_SENSOR_OFFSETS 150
MAVPACKED(
typedef struct __mavlink_sensor_offsets_t {
float mag_declination; /*< [rad] Magnetic declination.*/
int32_t raw_press; /*< Raw pressure from barometer.*/
int32_t raw_temp; /*< Raw temperature from barometer.*/
float gyro_cal_x; /*< Gyro X calibration.*/
float gyro_cal_y; /*< Gyro Y calibration.*/
float gyro_cal_z; /*< Gyro Z calibration.*/
float accel_cal_x; /*< Accel X calibration.*/
float accel_cal_y; /*< Accel Y calibration.*/
float accel_cal_z; /*< Accel Z calibration.*/
int16_t mag_ofs_x; /*< Magnetometer X offset.*/
int16_t mag_ofs_y; /*< Magnetometer Y offset.*/
int16_t mag_ofs_z; /*< Magnetometer Z offset.*/
}) mavlink_sensor_offsets_t;
#define MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN 42
#define MAVLINK_MSG_ID_SENSOR_OFFSETS_MIN_LEN 42
#define MAVLINK_MSG_ID_150_LEN 42
#define MAVLINK_MSG_ID_150_MIN_LEN 42
#define MAVLINK_MSG_ID_SENSOR_OFFSETS_CRC 134
#define MAVLINK_MSG_ID_150_CRC 134
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_SENSOR_OFFSETS { \
150, \
"SENSOR_OFFSETS", \
12, \
{ { "mag_ofs_x", NULL, MAVLINK_TYPE_INT16_T, 0, 36, offsetof(mavlink_sensor_offsets_t, mag_ofs_x) }, \
{ "mag_ofs_y", NULL, MAVLINK_TYPE_INT16_T, 0, 38, offsetof(mavlink_sensor_offsets_t, mag_ofs_y) }, \
{ "mag_ofs_z", NULL, MAVLINK_TYPE_INT16_T, 0, 40, offsetof(mavlink_sensor_offsets_t, mag_ofs_z) }, \
{ "mag_declination", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_sensor_offsets_t, mag_declination) }, \
{ "raw_press", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_sensor_offsets_t, raw_press) }, \
{ "raw_temp", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_sensor_offsets_t, raw_temp) }, \
{ "gyro_cal_x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_sensor_offsets_t, gyro_cal_x) }, \
{ "gyro_cal_y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_sensor_offsets_t, gyro_cal_y) }, \
{ "gyro_cal_z", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_sensor_offsets_t, gyro_cal_z) }, \
{ "accel_cal_x", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_sensor_offsets_t, accel_cal_x) }, \
{ "accel_cal_y", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_sensor_offsets_t, accel_cal_y) }, \
{ "accel_cal_z", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_sensor_offsets_t, accel_cal_z) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_SENSOR_OFFSETS { \
"SENSOR_OFFSETS", \
12, \
{ { "mag_ofs_x", NULL, MAVLINK_TYPE_INT16_T, 0, 36, offsetof(mavlink_sensor_offsets_t, mag_ofs_x) }, \
{ "mag_ofs_y", NULL, MAVLINK_TYPE_INT16_T, 0, 38, offsetof(mavlink_sensor_offsets_t, mag_ofs_y) }, \
{ "mag_ofs_z", NULL, MAVLINK_TYPE_INT16_T, 0, 40, offsetof(mavlink_sensor_offsets_t, mag_ofs_z) }, \
{ "mag_declination", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_sensor_offsets_t, mag_declination) }, \
{ "raw_press", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_sensor_offsets_t, raw_press) }, \
{ "raw_temp", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_sensor_offsets_t, raw_temp) }, \
{ "gyro_cal_x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_sensor_offsets_t, gyro_cal_x) }, \
{ "gyro_cal_y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_sensor_offsets_t, gyro_cal_y) }, \
{ "gyro_cal_z", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_sensor_offsets_t, gyro_cal_z) }, \
{ "accel_cal_x", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_sensor_offsets_t, accel_cal_x) }, \
{ "accel_cal_y", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_sensor_offsets_t, accel_cal_y) }, \
{ "accel_cal_z", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_sensor_offsets_t, accel_cal_z) }, \
} \
}
#endif
/**
* @brief Pack a sensor_offsets 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 mag_ofs_x Magnetometer X offset.
* @param mag_ofs_y Magnetometer Y offset.
* @param mag_ofs_z Magnetometer Z offset.
* @param mag_declination [rad] Magnetic declination.
* @param raw_press Raw pressure from barometer.
* @param raw_temp Raw temperature from barometer.
* @param gyro_cal_x Gyro X calibration.
* @param gyro_cal_y Gyro Y calibration.
* @param gyro_cal_z Gyro Z calibration.
* @param accel_cal_x Accel X calibration.
* @param accel_cal_y Accel Y calibration.
* @param accel_cal_z Accel Z calibration.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_sensor_offsets_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
int16_t mag_ofs_x, int16_t mag_ofs_y, int16_t mag_ofs_z, float mag_declination, int32_t raw_press, int32_t raw_temp, float gyro_cal_x, float gyro_cal_y, float gyro_cal_z, float accel_cal_x, float accel_cal_y, float accel_cal_z)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN];
_mav_put_float(buf, 0, mag_declination);
_mav_put_int32_t(buf, 4, raw_press);
_mav_put_int32_t(buf, 8, raw_temp);
_mav_put_float(buf, 12, gyro_cal_x);
_mav_put_float(buf, 16, gyro_cal_y);
_mav_put_float(buf, 20, gyro_cal_z);
_mav_put_float(buf, 24, accel_cal_x);
_mav_put_float(buf, 28, accel_cal_y);
_mav_put_float(buf, 32, accel_cal_z);
_mav_put_int16_t(buf, 36, mag_ofs_x);
_mav_put_int16_t(buf, 38, mag_ofs_y);
_mav_put_int16_t(buf, 40, mag_ofs_z);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN);
#else
mavlink_sensor_offsets_t packet;
packet.mag_declination = mag_declination;
packet.raw_press = raw_press;
packet.raw_temp = raw_temp;
packet.gyro_cal_x = gyro_cal_x;
packet.gyro_cal_y = gyro_cal_y;
packet.gyro_cal_z = gyro_cal_z;
packet.accel_cal_x = accel_cal_x;
packet.accel_cal_y = accel_cal_y;
packet.accel_cal_z = accel_cal_z;
packet.mag_ofs_x = mag_ofs_x;
packet.mag_ofs_y = mag_ofs_y;
packet.mag_ofs_z = mag_ofs_z;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_SENSOR_OFFSETS;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SENSOR_OFFSETS_MIN_LEN, MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN, MAVLINK_MSG_ID_SENSOR_OFFSETS_CRC);
}
/**
* @brief Pack a sensor_offsets message on a channel
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param mag_ofs_x Magnetometer X offset.
* @param mag_ofs_y Magnetometer Y offset.
* @param mag_ofs_z Magnetometer Z offset.
* @param mag_declination [rad] Magnetic declination.
* @param raw_press Raw pressure from barometer.
* @param raw_temp Raw temperature from barometer.
* @param gyro_cal_x Gyro X calibration.
* @param gyro_cal_y Gyro Y calibration.
* @param gyro_cal_z Gyro Z calibration.
* @param accel_cal_x Accel X calibration.
* @param accel_cal_y Accel Y calibration.
* @param accel_cal_z Accel Z calibration.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_sensor_offsets_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
int16_t mag_ofs_x,int16_t mag_ofs_y,int16_t mag_ofs_z,float mag_declination,int32_t raw_press,int32_t raw_temp,float gyro_cal_x,float gyro_cal_y,float gyro_cal_z,float accel_cal_x,float accel_cal_y,float accel_cal_z)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN];
_mav_put_float(buf, 0, mag_declination);
_mav_put_int32_t(buf, 4, raw_press);
_mav_put_int32_t(buf, 8, raw_temp);
_mav_put_float(buf, 12, gyro_cal_x);
_mav_put_float(buf, 16, gyro_cal_y);
_mav_put_float(buf, 20, gyro_cal_z);
_mav_put_float(buf, 24, accel_cal_x);
_mav_put_float(buf, 28, accel_cal_y);
_mav_put_float(buf, 32, accel_cal_z);
_mav_put_int16_t(buf, 36, mag_ofs_x);
_mav_put_int16_t(buf, 38, mag_ofs_y);
_mav_put_int16_t(buf, 40, mag_ofs_z);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN);
#else
mavlink_sensor_offsets_t packet;
packet.mag_declination = mag_declination;
packet.raw_press = raw_press;
packet.raw_temp = raw_temp;
packet.gyro_cal_x = gyro_cal_x;
packet.gyro_cal_y = gyro_cal_y;
packet.gyro_cal_z = gyro_cal_z;
packet.accel_cal_x = accel_cal_x;
packet.accel_cal_y = accel_cal_y;
packet.accel_cal_z = accel_cal_z;
packet.mag_ofs_x = mag_ofs_x;
packet.mag_ofs_y = mag_ofs_y;
packet.mag_ofs_z = mag_ofs_z;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_SENSOR_OFFSETS;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SENSOR_OFFSETS_MIN_LEN, MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN, MAVLINK_MSG_ID_SENSOR_OFFSETS_CRC);
}
/**
* @brief Encode a sensor_offsets struct
*
* @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 sensor_offsets C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_sensor_offsets_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_sensor_offsets_t* sensor_offsets)
{
return mavlink_msg_sensor_offsets_pack(system_id, component_id, msg, sensor_offsets->mag_ofs_x, sensor_offsets->mag_ofs_y, sensor_offsets->mag_ofs_z, sensor_offsets->mag_declination, sensor_offsets->raw_press, sensor_offsets->raw_temp, sensor_offsets->gyro_cal_x, sensor_offsets->gyro_cal_y, sensor_offsets->gyro_cal_z, sensor_offsets->accel_cal_x, sensor_offsets->accel_cal_y, sensor_offsets->accel_cal_z);
}
/**
* @brief Encode a sensor_offsets struct on a channel
*
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param sensor_offsets C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_sensor_offsets_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_sensor_offsets_t* sensor_offsets)
{
return mavlink_msg_sensor_offsets_pack_chan(system_id, component_id, chan, msg, sensor_offsets->mag_ofs_x, sensor_offsets->mag_ofs_y, sensor_offsets->mag_ofs_z, sensor_offsets->mag_declination, sensor_offsets->raw_press, sensor_offsets->raw_temp, sensor_offsets->gyro_cal_x, sensor_offsets->gyro_cal_y, sensor_offsets->gyro_cal_z, sensor_offsets->accel_cal_x, sensor_offsets->accel_cal_y, sensor_offsets->accel_cal_z);
}
/**
* @brief Send a sensor_offsets message
* @param chan MAVLink channel to send the message
*
* @param mag_ofs_x Magnetometer X offset.
* @param mag_ofs_y Magnetometer Y offset.
* @param mag_ofs_z Magnetometer Z offset.
* @param mag_declination [rad] Magnetic declination.
* @param raw_press Raw pressure from barometer.
* @param raw_temp Raw temperature from barometer.
* @param gyro_cal_x Gyro X calibration.
* @param gyro_cal_y Gyro Y calibration.
* @param gyro_cal_z Gyro Z calibration.
* @param accel_cal_x Accel X calibration.
* @param accel_cal_y Accel Y calibration.
* @param accel_cal_z Accel Z calibration.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_sensor_offsets_send(mavlink_channel_t chan, int16_t mag_ofs_x, int16_t mag_ofs_y, int16_t mag_ofs_z, float mag_declination, int32_t raw_press, int32_t raw_temp, float gyro_cal_x, float gyro_cal_y, float gyro_cal_z, float accel_cal_x, float accel_cal_y, float accel_cal_z)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN];
_mav_put_float(buf, 0, mag_declination);
_mav_put_int32_t(buf, 4, raw_press);
_mav_put_int32_t(buf, 8, raw_temp);
_mav_put_float(buf, 12, gyro_cal_x);
_mav_put_float(buf, 16, gyro_cal_y);
_mav_put_float(buf, 20, gyro_cal_z);
_mav_put_float(buf, 24, accel_cal_x);
_mav_put_float(buf, 28, accel_cal_y);
_mav_put_float(buf, 32, accel_cal_z);
_mav_put_int16_t(buf, 36, mag_ofs_x);
_mav_put_int16_t(buf, 38, mag_ofs_y);
_mav_put_int16_t(buf, 40, mag_ofs_z);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENSOR_OFFSETS, buf, MAVLINK_MSG_ID_SENSOR_OFFSETS_MIN_LEN, MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN, MAVLINK_MSG_ID_SENSOR_OFFSETS_CRC);
#else
mavlink_sensor_offsets_t packet;
packet.mag_declination = mag_declination;
packet.raw_press = raw_press;
packet.raw_temp = raw_temp;
packet.gyro_cal_x = gyro_cal_x;
packet.gyro_cal_y = gyro_cal_y;
packet.gyro_cal_z = gyro_cal_z;
packet.accel_cal_x = accel_cal_x;
packet.accel_cal_y = accel_cal_y;
packet.accel_cal_z = accel_cal_z;
packet.mag_ofs_x = mag_ofs_x;
packet.mag_ofs_y = mag_ofs_y;
packet.mag_ofs_z = mag_ofs_z;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENSOR_OFFSETS, (const char *)&packet, MAVLINK_MSG_ID_SENSOR_OFFSETS_MIN_LEN, MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN, MAVLINK_MSG_ID_SENSOR_OFFSETS_CRC);
#endif
}
/**
* @brief Send a sensor_offsets message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_sensor_offsets_send_struct(mavlink_channel_t chan, const mavlink_sensor_offsets_t* sensor_offsets)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_sensor_offsets_send(chan, sensor_offsets->mag_ofs_x, sensor_offsets->mag_ofs_y, sensor_offsets->mag_ofs_z, sensor_offsets->mag_declination, sensor_offsets->raw_press, sensor_offsets->raw_temp, sensor_offsets->gyro_cal_x, sensor_offsets->gyro_cal_y, sensor_offsets->gyro_cal_z, sensor_offsets->accel_cal_x, sensor_offsets->accel_cal_y, sensor_offsets->accel_cal_z);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENSOR_OFFSETS, (const char *)sensor_offsets, MAVLINK_MSG_ID_SENSOR_OFFSETS_MIN_LEN, MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN, MAVLINK_MSG_ID_SENSOR_OFFSETS_CRC);
#endif
}
#if MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_sensor_offsets_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, int16_t mag_ofs_x, int16_t mag_ofs_y, int16_t mag_ofs_z, float mag_declination, int32_t raw_press, int32_t raw_temp, float gyro_cal_x, float gyro_cal_y, float gyro_cal_z, float accel_cal_x, float accel_cal_y, float accel_cal_z)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_float(buf, 0, mag_declination);
_mav_put_int32_t(buf, 4, raw_press);
_mav_put_int32_t(buf, 8, raw_temp);
_mav_put_float(buf, 12, gyro_cal_x);
_mav_put_float(buf, 16, gyro_cal_y);
_mav_put_float(buf, 20, gyro_cal_z);
_mav_put_float(buf, 24, accel_cal_x);
_mav_put_float(buf, 28, accel_cal_y);
_mav_put_float(buf, 32, accel_cal_z);
_mav_put_int16_t(buf, 36, mag_ofs_x);
_mav_put_int16_t(buf, 38, mag_ofs_y);
_mav_put_int16_t(buf, 40, mag_ofs_z);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENSOR_OFFSETS, buf, MAVLINK_MSG_ID_SENSOR_OFFSETS_MIN_LEN, MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN, MAVLINK_MSG_ID_SENSOR_OFFSETS_CRC);
#else
mavlink_sensor_offsets_t *packet = (mavlink_sensor_offsets_t *)msgbuf;
packet->mag_declination = mag_declination;
packet->raw_press = raw_press;
packet->raw_temp = raw_temp;
packet->gyro_cal_x = gyro_cal_x;
packet->gyro_cal_y = gyro_cal_y;
packet->gyro_cal_z = gyro_cal_z;
packet->accel_cal_x = accel_cal_x;
packet->accel_cal_y = accel_cal_y;
packet->accel_cal_z = accel_cal_z;
packet->mag_ofs_x = mag_ofs_x;
packet->mag_ofs_y = mag_ofs_y;
packet->mag_ofs_z = mag_ofs_z;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENSOR_OFFSETS, (const char *)packet, MAVLINK_MSG_ID_SENSOR_OFFSETS_MIN_LEN, MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN, MAVLINK_MSG_ID_SENSOR_OFFSETS_CRC);
#endif
}
#endif
#endif
// MESSAGE SENSOR_OFFSETS UNPACKING
/**
* @brief Get field mag_ofs_x from sensor_offsets message
*
* @return Magnetometer X offset.
*/
static inline int16_t mavlink_msg_sensor_offsets_get_mag_ofs_x(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 36);
}
/**
* @brief Get field mag_ofs_y from sensor_offsets message
*
* @return Magnetometer Y offset.
*/
static inline int16_t mavlink_msg_sensor_offsets_get_mag_ofs_y(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 38);
}
/**
* @brief Get field mag_ofs_z from sensor_offsets message
*
* @return Magnetometer Z offset.
*/
static inline int16_t mavlink_msg_sensor_offsets_get_mag_ofs_z(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 40);
}
/**
* @brief Get field mag_declination from sensor_offsets message
*
* @return [rad] Magnetic declination.
*/
static inline float mavlink_msg_sensor_offsets_get_mag_declination(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 0);
}
/**
* @brief Get field raw_press from sensor_offsets message
*
* @return Raw pressure from barometer.
*/
static inline int32_t mavlink_msg_sensor_offsets_get_raw_press(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 4);
}
/**
* @brief Get field raw_temp from sensor_offsets message
*
* @return Raw temperature from barometer.
*/
static inline int32_t mavlink_msg_sensor_offsets_get_raw_temp(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 8);
}
/**
* @brief Get field gyro_cal_x from sensor_offsets message
*
* @return Gyro X calibration.
*/
static inline float mavlink_msg_sensor_offsets_get_gyro_cal_x(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
/**
* @brief Get field gyro_cal_y from sensor_offsets message
*
* @return Gyro Y calibration.
*/
static inline float mavlink_msg_sensor_offsets_get_gyro_cal_y(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 16);
}
/**
* @brief Get field gyro_cal_z from sensor_offsets message
*
* @return Gyro Z calibration.
*/
static inline float mavlink_msg_sensor_offsets_get_gyro_cal_z(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 20);
}
/**
* @brief Get field accel_cal_x from sensor_offsets message
*
* @return Accel X calibration.
*/
static inline float mavlink_msg_sensor_offsets_get_accel_cal_x(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 24);
}
/**
* @brief Get field accel_cal_y from sensor_offsets message
*
* @return Accel Y calibration.
*/
static inline float mavlink_msg_sensor_offsets_get_accel_cal_y(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 28);
}
/**
* @brief Get field accel_cal_z from sensor_offsets message
*
* @return Accel Z calibration.
*/
static inline float mavlink_msg_sensor_offsets_get_accel_cal_z(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 32);
}
/**
* @brief Decode a sensor_offsets message into a struct
*
* @param msg The message to decode
* @param sensor_offsets C-struct to decode the message contents into
*/
static inline void mavlink_msg_sensor_offsets_decode(const mavlink_message_t* msg, mavlink_sensor_offsets_t* sensor_offsets)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
sensor_offsets->mag_declination = mavlink_msg_sensor_offsets_get_mag_declination(msg);
sensor_offsets->raw_press = mavlink_msg_sensor_offsets_get_raw_press(msg);
sensor_offsets->raw_temp = mavlink_msg_sensor_offsets_get_raw_temp(msg);
sensor_offsets->gyro_cal_x = mavlink_msg_sensor_offsets_get_gyro_cal_x(msg);
sensor_offsets->gyro_cal_y = mavlink_msg_sensor_offsets_get_gyro_cal_y(msg);
sensor_offsets->gyro_cal_z = mavlink_msg_sensor_offsets_get_gyro_cal_z(msg);
sensor_offsets->accel_cal_x = mavlink_msg_sensor_offsets_get_accel_cal_x(msg);
sensor_offsets->accel_cal_y = mavlink_msg_sensor_offsets_get_accel_cal_y(msg);
sensor_offsets->accel_cal_z = mavlink_msg_sensor_offsets_get_accel_cal_z(msg);
sensor_offsets->mag_ofs_x = mavlink_msg_sensor_offsets_get_mag_ofs_x(msg);
sensor_offsets->mag_ofs_y = mavlink_msg_sensor_offsets_get_mag_ofs_y(msg);
sensor_offsets->mag_ofs_z = mavlink_msg_sensor_offsets_get_mag_ofs_z(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN? msg->len : MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN;
memset(sensor_offsets, 0, MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN);
memcpy(sensor_offsets, _MAV_PAYLOAD(msg), len);
#endif
}

View File

@@ -0,0 +1,313 @@
#pragma once
// MESSAGE SET_MAG_OFFSETS PACKING
#define MAVLINK_MSG_ID_SET_MAG_OFFSETS 151
MAVPACKED(
typedef struct __mavlink_set_mag_offsets_t {
int16_t mag_ofs_x; /*< Magnetometer X offset.*/
int16_t mag_ofs_y; /*< Magnetometer Y offset.*/
int16_t mag_ofs_z; /*< Magnetometer Z offset.*/
uint8_t target_system; /*< System ID.*/
uint8_t target_component; /*< Component ID.*/
}) mavlink_set_mag_offsets_t;
#define MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN 8
#define MAVLINK_MSG_ID_SET_MAG_OFFSETS_MIN_LEN 8
#define MAVLINK_MSG_ID_151_LEN 8
#define MAVLINK_MSG_ID_151_MIN_LEN 8
#define MAVLINK_MSG_ID_SET_MAG_OFFSETS_CRC 219
#define MAVLINK_MSG_ID_151_CRC 219
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_SET_MAG_OFFSETS { \
151, \
"SET_MAG_OFFSETS", \
5, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_set_mag_offsets_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_set_mag_offsets_t, target_component) }, \
{ "mag_ofs_x", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_set_mag_offsets_t, mag_ofs_x) }, \
{ "mag_ofs_y", NULL, MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_set_mag_offsets_t, mag_ofs_y) }, \
{ "mag_ofs_z", NULL, MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_set_mag_offsets_t, mag_ofs_z) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_SET_MAG_OFFSETS { \
"SET_MAG_OFFSETS", \
5, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_set_mag_offsets_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_set_mag_offsets_t, target_component) }, \
{ "mag_ofs_x", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_set_mag_offsets_t, mag_ofs_x) }, \
{ "mag_ofs_y", NULL, MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_set_mag_offsets_t, mag_ofs_y) }, \
{ "mag_ofs_z", NULL, MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_set_mag_offsets_t, mag_ofs_z) }, \
} \
}
#endif
/**
* @brief Pack a set_mag_offsets 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.
* @param mag_ofs_x Magnetometer X offset.
* @param mag_ofs_y Magnetometer Y offset.
* @param mag_ofs_z Magnetometer Z offset.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_set_mag_offsets_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, int16_t mag_ofs_x, int16_t mag_ofs_y, int16_t mag_ofs_z)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN];
_mav_put_int16_t(buf, 0, mag_ofs_x);
_mav_put_int16_t(buf, 2, mag_ofs_y);
_mav_put_int16_t(buf, 4, mag_ofs_z);
_mav_put_uint8_t(buf, 6, target_system);
_mav_put_uint8_t(buf, 7, target_component);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN);
#else
mavlink_set_mag_offsets_t packet;
packet.mag_ofs_x = mag_ofs_x;
packet.mag_ofs_y = mag_ofs_y;
packet.mag_ofs_z = mag_ofs_z;
packet.target_system = target_system;
packet.target_component = target_component;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_SET_MAG_OFFSETS;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_MAG_OFFSETS_MIN_LEN, MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN, MAVLINK_MSG_ID_SET_MAG_OFFSETS_CRC);
}
/**
* @brief Pack a set_mag_offsets message on a channel
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID.
* @param target_component Component ID.
* @param mag_ofs_x Magnetometer X offset.
* @param mag_ofs_y Magnetometer Y offset.
* @param mag_ofs_z Magnetometer Z offset.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_set_mag_offsets_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,int16_t mag_ofs_x,int16_t mag_ofs_y,int16_t mag_ofs_z)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN];
_mav_put_int16_t(buf, 0, mag_ofs_x);
_mav_put_int16_t(buf, 2, mag_ofs_y);
_mav_put_int16_t(buf, 4, mag_ofs_z);
_mav_put_uint8_t(buf, 6, target_system);
_mav_put_uint8_t(buf, 7, target_component);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN);
#else
mavlink_set_mag_offsets_t packet;
packet.mag_ofs_x = mag_ofs_x;
packet.mag_ofs_y = mag_ofs_y;
packet.mag_ofs_z = mag_ofs_z;
packet.target_system = target_system;
packet.target_component = target_component;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_SET_MAG_OFFSETS;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_MAG_OFFSETS_MIN_LEN, MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN, MAVLINK_MSG_ID_SET_MAG_OFFSETS_CRC);
}
/**
* @brief Encode a set_mag_offsets struct
*
* @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_mag_offsets C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_set_mag_offsets_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_mag_offsets_t* set_mag_offsets)
{
return mavlink_msg_set_mag_offsets_pack(system_id, component_id, msg, set_mag_offsets->target_system, set_mag_offsets->target_component, set_mag_offsets->mag_ofs_x, set_mag_offsets->mag_ofs_y, set_mag_offsets->mag_ofs_z);
}
/**
* @brief Encode a set_mag_offsets struct on a channel
*
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param set_mag_offsets C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_set_mag_offsets_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_mag_offsets_t* set_mag_offsets)
{
return mavlink_msg_set_mag_offsets_pack_chan(system_id, component_id, chan, msg, set_mag_offsets->target_system, set_mag_offsets->target_component, set_mag_offsets->mag_ofs_x, set_mag_offsets->mag_ofs_y, set_mag_offsets->mag_ofs_z);
}
/**
* @brief Send a set_mag_offsets message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID.
* @param target_component Component ID.
* @param mag_ofs_x Magnetometer X offset.
* @param mag_ofs_y Magnetometer Y offset.
* @param mag_ofs_z Magnetometer Z offset.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_set_mag_offsets_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, int16_t mag_ofs_x, int16_t mag_ofs_y, int16_t mag_ofs_z)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN];
_mav_put_int16_t(buf, 0, mag_ofs_x);
_mav_put_int16_t(buf, 2, mag_ofs_y);
_mav_put_int16_t(buf, 4, mag_ofs_z);
_mav_put_uint8_t(buf, 6, target_system);
_mav_put_uint8_t(buf, 7, target_component);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MAG_OFFSETS, buf, MAVLINK_MSG_ID_SET_MAG_OFFSETS_MIN_LEN, MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN, MAVLINK_MSG_ID_SET_MAG_OFFSETS_CRC);
#else
mavlink_set_mag_offsets_t packet;
packet.mag_ofs_x = mag_ofs_x;
packet.mag_ofs_y = mag_ofs_y;
packet.mag_ofs_z = mag_ofs_z;
packet.target_system = target_system;
packet.target_component = target_component;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MAG_OFFSETS, (const char *)&packet, MAVLINK_MSG_ID_SET_MAG_OFFSETS_MIN_LEN, MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN, MAVLINK_MSG_ID_SET_MAG_OFFSETS_CRC);
#endif
}
/**
* @brief Send a set_mag_offsets message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_set_mag_offsets_send_struct(mavlink_channel_t chan, const mavlink_set_mag_offsets_t* set_mag_offsets)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_set_mag_offsets_send(chan, set_mag_offsets->target_system, set_mag_offsets->target_component, set_mag_offsets->mag_ofs_x, set_mag_offsets->mag_ofs_y, set_mag_offsets->mag_ofs_z);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MAG_OFFSETS, (const char *)set_mag_offsets, MAVLINK_MSG_ID_SET_MAG_OFFSETS_MIN_LEN, MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN, MAVLINK_MSG_ID_SET_MAG_OFFSETS_CRC);
#endif
}
#if MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_set_mag_offsets_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, int16_t mag_ofs_x, int16_t mag_ofs_y, int16_t mag_ofs_z)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_int16_t(buf, 0, mag_ofs_x);
_mav_put_int16_t(buf, 2, mag_ofs_y);
_mav_put_int16_t(buf, 4, mag_ofs_z);
_mav_put_uint8_t(buf, 6, target_system);
_mav_put_uint8_t(buf, 7, target_component);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MAG_OFFSETS, buf, MAVLINK_MSG_ID_SET_MAG_OFFSETS_MIN_LEN, MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN, MAVLINK_MSG_ID_SET_MAG_OFFSETS_CRC);
#else
mavlink_set_mag_offsets_t *packet = (mavlink_set_mag_offsets_t *)msgbuf;
packet->mag_ofs_x = mag_ofs_x;
packet->mag_ofs_y = mag_ofs_y;
packet->mag_ofs_z = mag_ofs_z;
packet->target_system = target_system;
packet->target_component = target_component;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MAG_OFFSETS, (const char *)packet, MAVLINK_MSG_ID_SET_MAG_OFFSETS_MIN_LEN, MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN, MAVLINK_MSG_ID_SET_MAG_OFFSETS_CRC);
#endif
}
#endif
#endif
// MESSAGE SET_MAG_OFFSETS UNPACKING
/**
* @brief Get field target_system from set_mag_offsets message
*
* @return System ID.
*/
static inline uint8_t mavlink_msg_set_mag_offsets_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 6);
}
/**
* @brief Get field target_component from set_mag_offsets message
*
* @return Component ID.
*/
static inline uint8_t mavlink_msg_set_mag_offsets_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 7);
}
/**
* @brief Get field mag_ofs_x from set_mag_offsets message
*
* @return Magnetometer X offset.
*/
static inline int16_t mavlink_msg_set_mag_offsets_get_mag_ofs_x(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 0);
}
/**
* @brief Get field mag_ofs_y from set_mag_offsets message
*
* @return Magnetometer Y offset.
*/
static inline int16_t mavlink_msg_set_mag_offsets_get_mag_ofs_y(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 2);
}
/**
* @brief Get field mag_ofs_z from set_mag_offsets message
*
* @return Magnetometer Z offset.
*/
static inline int16_t mavlink_msg_set_mag_offsets_get_mag_ofs_z(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 4);
}
/**
* @brief Decode a set_mag_offsets message into a struct
*
* @param msg The message to decode
* @param set_mag_offsets C-struct to decode the message contents into
*/
static inline void mavlink_msg_set_mag_offsets_decode(const mavlink_message_t* msg, mavlink_set_mag_offsets_t* set_mag_offsets)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
set_mag_offsets->mag_ofs_x = mavlink_msg_set_mag_offsets_get_mag_ofs_x(msg);
set_mag_offsets->mag_ofs_y = mavlink_msg_set_mag_offsets_get_mag_ofs_y(msg);
set_mag_offsets->mag_ofs_z = mavlink_msg_set_mag_offsets_get_mag_ofs_z(msg);
set_mag_offsets->target_system = mavlink_msg_set_mag_offsets_get_target_system(msg);
set_mag_offsets->target_component = mavlink_msg_set_mag_offsets_get_target_component(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN? msg->len : MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN;
memset(set_mag_offsets, 0, MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN);
memcpy(set_mag_offsets, _MAV_PAYLOAD(msg), len);
#endif
}

View File

@@ -0,0 +1,463 @@
#pragma once
// MESSAGE SIMSTATE PACKING
#define MAVLINK_MSG_ID_SIMSTATE 164
MAVPACKED(
typedef struct __mavlink_simstate_t {
float roll; /*< [rad] Roll angle.*/
float pitch; /*< [rad] Pitch angle.*/
float yaw; /*< [rad] Yaw angle.*/
float xacc; /*< [m/s/s] X acceleration.*/
float yacc; /*< [m/s/s] Y acceleration.*/
float zacc; /*< [m/s/s] Z acceleration.*/
float xgyro; /*< [rad/s] Angular speed around X axis.*/
float ygyro; /*< [rad/s] Angular speed around Y axis.*/
float zgyro; /*< [rad/s] Angular speed around Z axis.*/
int32_t lat; /*< [degE7] Latitude.*/
int32_t lng; /*< [degE7] Longitude.*/
}) mavlink_simstate_t;
#define MAVLINK_MSG_ID_SIMSTATE_LEN 44
#define MAVLINK_MSG_ID_SIMSTATE_MIN_LEN 44
#define MAVLINK_MSG_ID_164_LEN 44
#define MAVLINK_MSG_ID_164_MIN_LEN 44
#define MAVLINK_MSG_ID_SIMSTATE_CRC 154
#define MAVLINK_MSG_ID_164_CRC 154
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_SIMSTATE { \
164, \
"SIMSTATE", \
11, \
{ { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_simstate_t, roll) }, \
{ "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_simstate_t, pitch) }, \
{ "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_simstate_t, yaw) }, \
{ "xacc", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_simstate_t, xacc) }, \
{ "yacc", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_simstate_t, yacc) }, \
{ "zacc", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_simstate_t, zacc) }, \
{ "xgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_simstate_t, xgyro) }, \
{ "ygyro", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_simstate_t, ygyro) }, \
{ "zgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_simstate_t, zgyro) }, \
{ "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 36, offsetof(mavlink_simstate_t, lat) }, \
{ "lng", NULL, MAVLINK_TYPE_INT32_T, 0, 40, offsetof(mavlink_simstate_t, lng) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_SIMSTATE { \
"SIMSTATE", \
11, \
{ { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_simstate_t, roll) }, \
{ "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_simstate_t, pitch) }, \
{ "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_simstate_t, yaw) }, \
{ "xacc", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_simstate_t, xacc) }, \
{ "yacc", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_simstate_t, yacc) }, \
{ "zacc", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_simstate_t, zacc) }, \
{ "xgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_simstate_t, xgyro) }, \
{ "ygyro", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_simstate_t, ygyro) }, \
{ "zgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_simstate_t, zgyro) }, \
{ "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 36, offsetof(mavlink_simstate_t, lat) }, \
{ "lng", NULL, MAVLINK_TYPE_INT32_T, 0, 40, offsetof(mavlink_simstate_t, lng) }, \
} \
}
#endif
/**
* @brief Pack a simstate 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 roll [rad] Roll angle.
* @param pitch [rad] Pitch angle.
* @param yaw [rad] Yaw angle.
* @param xacc [m/s/s] X acceleration.
* @param yacc [m/s/s] Y acceleration.
* @param zacc [m/s/s] Z acceleration.
* @param xgyro [rad/s] Angular speed around X axis.
* @param ygyro [rad/s] Angular speed around Y axis.
* @param zgyro [rad/s] Angular speed around Z axis.
* @param lat [degE7] Latitude.
* @param lng [degE7] Longitude.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_simstate_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
float roll, float pitch, float yaw, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, int32_t lat, int32_t lng)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_SIMSTATE_LEN];
_mav_put_float(buf, 0, roll);
_mav_put_float(buf, 4, pitch);
_mav_put_float(buf, 8, yaw);
_mav_put_float(buf, 12, xacc);
_mav_put_float(buf, 16, yacc);
_mav_put_float(buf, 20, zacc);
_mav_put_float(buf, 24, xgyro);
_mav_put_float(buf, 28, ygyro);
_mav_put_float(buf, 32, zgyro);
_mav_put_int32_t(buf, 36, lat);
_mav_put_int32_t(buf, 40, lng);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SIMSTATE_LEN);
#else
mavlink_simstate_t packet;
packet.roll = roll;
packet.pitch = pitch;
packet.yaw = yaw;
packet.xacc = xacc;
packet.yacc = yacc;
packet.zacc = zacc;
packet.xgyro = xgyro;
packet.ygyro = ygyro;
packet.zgyro = zgyro;
packet.lat = lat;
packet.lng = lng;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SIMSTATE_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_SIMSTATE;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SIMSTATE_MIN_LEN, MAVLINK_MSG_ID_SIMSTATE_LEN, MAVLINK_MSG_ID_SIMSTATE_CRC);
}
/**
* @brief Pack a simstate message on a channel
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param roll [rad] Roll angle.
* @param pitch [rad] Pitch angle.
* @param yaw [rad] Yaw angle.
* @param xacc [m/s/s] X acceleration.
* @param yacc [m/s/s] Y acceleration.
* @param zacc [m/s/s] Z acceleration.
* @param xgyro [rad/s] Angular speed around X axis.
* @param ygyro [rad/s] Angular speed around Y axis.
* @param zgyro [rad/s] Angular speed around Z axis.
* @param lat [degE7] Latitude.
* @param lng [degE7] Longitude.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_simstate_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
float roll,float pitch,float yaw,float xacc,float yacc,float zacc,float xgyro,float ygyro,float zgyro,int32_t lat,int32_t lng)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_SIMSTATE_LEN];
_mav_put_float(buf, 0, roll);
_mav_put_float(buf, 4, pitch);
_mav_put_float(buf, 8, yaw);
_mav_put_float(buf, 12, xacc);
_mav_put_float(buf, 16, yacc);
_mav_put_float(buf, 20, zacc);
_mav_put_float(buf, 24, xgyro);
_mav_put_float(buf, 28, ygyro);
_mav_put_float(buf, 32, zgyro);
_mav_put_int32_t(buf, 36, lat);
_mav_put_int32_t(buf, 40, lng);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SIMSTATE_LEN);
#else
mavlink_simstate_t packet;
packet.roll = roll;
packet.pitch = pitch;
packet.yaw = yaw;
packet.xacc = xacc;
packet.yacc = yacc;
packet.zacc = zacc;
packet.xgyro = xgyro;
packet.ygyro = ygyro;
packet.zgyro = zgyro;
packet.lat = lat;
packet.lng = lng;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SIMSTATE_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_SIMSTATE;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SIMSTATE_MIN_LEN, MAVLINK_MSG_ID_SIMSTATE_LEN, MAVLINK_MSG_ID_SIMSTATE_CRC);
}
/**
* @brief Encode a simstate struct
*
* @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 simstate C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_simstate_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_simstate_t* simstate)
{
return mavlink_msg_simstate_pack(system_id, component_id, msg, simstate->roll, simstate->pitch, simstate->yaw, simstate->xacc, simstate->yacc, simstate->zacc, simstate->xgyro, simstate->ygyro, simstate->zgyro, simstate->lat, simstate->lng);
}
/**
* @brief Encode a simstate struct on a channel
*
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param simstate C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_simstate_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_simstate_t* simstate)
{
return mavlink_msg_simstate_pack_chan(system_id, component_id, chan, msg, simstate->roll, simstate->pitch, simstate->yaw, simstate->xacc, simstate->yacc, simstate->zacc, simstate->xgyro, simstate->ygyro, simstate->zgyro, simstate->lat, simstate->lng);
}
/**
* @brief Send a simstate message
* @param chan MAVLink channel to send the message
*
* @param roll [rad] Roll angle.
* @param pitch [rad] Pitch angle.
* @param yaw [rad] Yaw angle.
* @param xacc [m/s/s] X acceleration.
* @param yacc [m/s/s] Y acceleration.
* @param zacc [m/s/s] Z acceleration.
* @param xgyro [rad/s] Angular speed around X axis.
* @param ygyro [rad/s] Angular speed around Y axis.
* @param zgyro [rad/s] Angular speed around Z axis.
* @param lat [degE7] Latitude.
* @param lng [degE7] Longitude.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_simstate_send(mavlink_channel_t chan, float roll, float pitch, float yaw, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, int32_t lat, int32_t lng)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_SIMSTATE_LEN];
_mav_put_float(buf, 0, roll);
_mav_put_float(buf, 4, pitch);
_mav_put_float(buf, 8, yaw);
_mav_put_float(buf, 12, xacc);
_mav_put_float(buf, 16, yacc);
_mav_put_float(buf, 20, zacc);
_mav_put_float(buf, 24, xgyro);
_mav_put_float(buf, 28, ygyro);
_mav_put_float(buf, 32, zgyro);
_mav_put_int32_t(buf, 36, lat);
_mav_put_int32_t(buf, 40, lng);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIMSTATE, buf, MAVLINK_MSG_ID_SIMSTATE_MIN_LEN, MAVLINK_MSG_ID_SIMSTATE_LEN, MAVLINK_MSG_ID_SIMSTATE_CRC);
#else
mavlink_simstate_t packet;
packet.roll = roll;
packet.pitch = pitch;
packet.yaw = yaw;
packet.xacc = xacc;
packet.yacc = yacc;
packet.zacc = zacc;
packet.xgyro = xgyro;
packet.ygyro = ygyro;
packet.zgyro = zgyro;
packet.lat = lat;
packet.lng = lng;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIMSTATE, (const char *)&packet, MAVLINK_MSG_ID_SIMSTATE_MIN_LEN, MAVLINK_MSG_ID_SIMSTATE_LEN, MAVLINK_MSG_ID_SIMSTATE_CRC);
#endif
}
/**
* @brief Send a simstate message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_simstate_send_struct(mavlink_channel_t chan, const mavlink_simstate_t* simstate)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_simstate_send(chan, simstate->roll, simstate->pitch, simstate->yaw, simstate->xacc, simstate->yacc, simstate->zacc, simstate->xgyro, simstate->ygyro, simstate->zgyro, simstate->lat, simstate->lng);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIMSTATE, (const char *)simstate, MAVLINK_MSG_ID_SIMSTATE_MIN_LEN, MAVLINK_MSG_ID_SIMSTATE_LEN, MAVLINK_MSG_ID_SIMSTATE_CRC);
#endif
}
#if MAVLINK_MSG_ID_SIMSTATE_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_simstate_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float roll, float pitch, float yaw, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, int32_t lat, int32_t lng)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_float(buf, 0, roll);
_mav_put_float(buf, 4, pitch);
_mav_put_float(buf, 8, yaw);
_mav_put_float(buf, 12, xacc);
_mav_put_float(buf, 16, yacc);
_mav_put_float(buf, 20, zacc);
_mav_put_float(buf, 24, xgyro);
_mav_put_float(buf, 28, ygyro);
_mav_put_float(buf, 32, zgyro);
_mav_put_int32_t(buf, 36, lat);
_mav_put_int32_t(buf, 40, lng);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIMSTATE, buf, MAVLINK_MSG_ID_SIMSTATE_MIN_LEN, MAVLINK_MSG_ID_SIMSTATE_LEN, MAVLINK_MSG_ID_SIMSTATE_CRC);
#else
mavlink_simstate_t *packet = (mavlink_simstate_t *)msgbuf;
packet->roll = roll;
packet->pitch = pitch;
packet->yaw = yaw;
packet->xacc = xacc;
packet->yacc = yacc;
packet->zacc = zacc;
packet->xgyro = xgyro;
packet->ygyro = ygyro;
packet->zgyro = zgyro;
packet->lat = lat;
packet->lng = lng;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIMSTATE, (const char *)packet, MAVLINK_MSG_ID_SIMSTATE_MIN_LEN, MAVLINK_MSG_ID_SIMSTATE_LEN, MAVLINK_MSG_ID_SIMSTATE_CRC);
#endif
}
#endif
#endif
// MESSAGE SIMSTATE UNPACKING
/**
* @brief Get field roll from simstate message
*
* @return [rad] Roll angle.
*/
static inline float mavlink_msg_simstate_get_roll(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 0);
}
/**
* @brief Get field pitch from simstate message
*
* @return [rad] Pitch angle.
*/
static inline float mavlink_msg_simstate_get_pitch(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 4);
}
/**
* @brief Get field yaw from simstate message
*
* @return [rad] Yaw angle.
*/
static inline float mavlink_msg_simstate_get_yaw(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
/**
* @brief Get field xacc from simstate message
*
* @return [m/s/s] X acceleration.
*/
static inline float mavlink_msg_simstate_get_xacc(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
/**
* @brief Get field yacc from simstate message
*
* @return [m/s/s] Y acceleration.
*/
static inline float mavlink_msg_simstate_get_yacc(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 16);
}
/**
* @brief Get field zacc from simstate message
*
* @return [m/s/s] Z acceleration.
*/
static inline float mavlink_msg_simstate_get_zacc(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 20);
}
/**
* @brief Get field xgyro from simstate message
*
* @return [rad/s] Angular speed around X axis.
*/
static inline float mavlink_msg_simstate_get_xgyro(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 24);
}
/**
* @brief Get field ygyro from simstate message
*
* @return [rad/s] Angular speed around Y axis.
*/
static inline float mavlink_msg_simstate_get_ygyro(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 28);
}
/**
* @brief Get field zgyro from simstate message
*
* @return [rad/s] Angular speed around Z axis.
*/
static inline float mavlink_msg_simstate_get_zgyro(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 32);
}
/**
* @brief Get field lat from simstate message
*
* @return [degE7] Latitude.
*/
static inline int32_t mavlink_msg_simstate_get_lat(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 36);
}
/**
* @brief Get field lng from simstate message
*
* @return [degE7] Longitude.
*/
static inline int32_t mavlink_msg_simstate_get_lng(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 40);
}
/**
* @brief Decode a simstate message into a struct
*
* @param msg The message to decode
* @param simstate C-struct to decode the message contents into
*/
static inline void mavlink_msg_simstate_decode(const mavlink_message_t* msg, mavlink_simstate_t* simstate)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
simstate->roll = mavlink_msg_simstate_get_roll(msg);
simstate->pitch = mavlink_msg_simstate_get_pitch(msg);
simstate->yaw = mavlink_msg_simstate_get_yaw(msg);
simstate->xacc = mavlink_msg_simstate_get_xacc(msg);
simstate->yacc = mavlink_msg_simstate_get_yacc(msg);
simstate->zacc = mavlink_msg_simstate_get_zacc(msg);
simstate->xgyro = mavlink_msg_simstate_get_xgyro(msg);
simstate->ygyro = mavlink_msg_simstate_get_ygyro(msg);
simstate->zgyro = mavlink_msg_simstate_get_zgyro(msg);
simstate->lat = mavlink_msg_simstate_get_lat(msg);
simstate->lng = mavlink_msg_simstate_get_lng(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_SIMSTATE_LEN? msg->len : MAVLINK_MSG_ID_SIMSTATE_LEN;
memset(simstate, 0, MAVLINK_MSG_ID_SIMSTATE_LEN);
memcpy(simstate, _MAV_PAYLOAD(msg), len);
#endif
}

View File

@@ -0,0 +1,306 @@
#pragma once
// MESSAGE VISION_POSITION_DELTA PACKING
#define MAVLINK_MSG_ID_VISION_POSITION_DELTA 11011
MAVPACKED(
typedef struct __mavlink_vision_position_delta_t {
uint64_t time_usec; /*< [us] Timestamp (synced to UNIX time or since system boot).*/
uint64_t time_delta_usec; /*< [us] Time since the last reported camera frame.*/
float angle_delta[3]; /*< Defines a rotation vector in body frame that rotates the vehicle from the previous to the current orientation.*/
float position_delta[3]; /*< [m] Change in position from previous to current frame rotated into body frame (0=forward, 1=right, 2=down).*/
float confidence; /*< [%] Normalised confidence value from 0 to 100.*/
}) mavlink_vision_position_delta_t;
#define MAVLINK_MSG_ID_VISION_POSITION_DELTA_LEN 44
#define MAVLINK_MSG_ID_VISION_POSITION_DELTA_MIN_LEN 44
#define MAVLINK_MSG_ID_11011_LEN 44
#define MAVLINK_MSG_ID_11011_MIN_LEN 44
#define MAVLINK_MSG_ID_VISION_POSITION_DELTA_CRC 106
#define MAVLINK_MSG_ID_11011_CRC 106
#define MAVLINK_MSG_VISION_POSITION_DELTA_FIELD_ANGLE_DELTA_LEN 3
#define MAVLINK_MSG_VISION_POSITION_DELTA_FIELD_POSITION_DELTA_LEN 3
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_VISION_POSITION_DELTA { \
11011, \
"VISION_POSITION_DELTA", \
5, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_vision_position_delta_t, time_usec) }, \
{ "time_delta_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_vision_position_delta_t, time_delta_usec) }, \
{ "angle_delta", NULL, MAVLINK_TYPE_FLOAT, 3, 16, offsetof(mavlink_vision_position_delta_t, angle_delta) }, \
{ "position_delta", NULL, MAVLINK_TYPE_FLOAT, 3, 28, offsetof(mavlink_vision_position_delta_t, position_delta) }, \
{ "confidence", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_vision_position_delta_t, confidence) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_VISION_POSITION_DELTA { \
"VISION_POSITION_DELTA", \
5, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_vision_position_delta_t, time_usec) }, \
{ "time_delta_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_vision_position_delta_t, time_delta_usec) }, \
{ "angle_delta", NULL, MAVLINK_TYPE_FLOAT, 3, 16, offsetof(mavlink_vision_position_delta_t, angle_delta) }, \
{ "position_delta", NULL, MAVLINK_TYPE_FLOAT, 3, 28, offsetof(mavlink_vision_position_delta_t, position_delta) }, \
{ "confidence", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_vision_position_delta_t, confidence) }, \
} \
}
#endif
/**
* @brief Pack a vision_position_delta 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 [us] Timestamp (synced to UNIX time or since system boot).
* @param time_delta_usec [us] Time since the last reported camera frame.
* @param angle_delta Defines a rotation vector in body frame that rotates the vehicle from the previous to the current orientation.
* @param position_delta [m] Change in position from previous to current frame rotated into body frame (0=forward, 1=right, 2=down).
* @param confidence [%] Normalised confidence value from 0 to 100.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_vision_position_delta_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint64_t time_usec, uint64_t time_delta_usec, const float *angle_delta, const float *position_delta, float confidence)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_VISION_POSITION_DELTA_LEN];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_uint64_t(buf, 8, time_delta_usec);
_mav_put_float(buf, 40, confidence);
_mav_put_float_array(buf, 16, angle_delta, 3);
_mav_put_float_array(buf, 28, position_delta, 3);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VISION_POSITION_DELTA_LEN);
#else
mavlink_vision_position_delta_t packet;
packet.time_usec = time_usec;
packet.time_delta_usec = time_delta_usec;
packet.confidence = confidence;
mav_array_memcpy(packet.angle_delta, angle_delta, sizeof(float)*3);
mav_array_memcpy(packet.position_delta, position_delta, sizeof(float)*3);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VISION_POSITION_DELTA_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_VISION_POSITION_DELTA;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_VISION_POSITION_DELTA_MIN_LEN, MAVLINK_MSG_ID_VISION_POSITION_DELTA_LEN, MAVLINK_MSG_ID_VISION_POSITION_DELTA_CRC);
}
/**
* @brief Pack a vision_position_delta message on a channel
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_usec [us] Timestamp (synced to UNIX time or since system boot).
* @param time_delta_usec [us] Time since the last reported camera frame.
* @param angle_delta Defines a rotation vector in body frame that rotates the vehicle from the previous to the current orientation.
* @param position_delta [m] Change in position from previous to current frame rotated into body frame (0=forward, 1=right, 2=down).
* @param confidence [%] Normalised confidence value from 0 to 100.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_vision_position_delta_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint64_t time_usec,uint64_t time_delta_usec,const float *angle_delta,const float *position_delta,float confidence)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_VISION_POSITION_DELTA_LEN];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_uint64_t(buf, 8, time_delta_usec);
_mav_put_float(buf, 40, confidence);
_mav_put_float_array(buf, 16, angle_delta, 3);
_mav_put_float_array(buf, 28, position_delta, 3);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VISION_POSITION_DELTA_LEN);
#else
mavlink_vision_position_delta_t packet;
packet.time_usec = time_usec;
packet.time_delta_usec = time_delta_usec;
packet.confidence = confidence;
mav_array_memcpy(packet.angle_delta, angle_delta, sizeof(float)*3);
mav_array_memcpy(packet.position_delta, position_delta, sizeof(float)*3);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VISION_POSITION_DELTA_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_VISION_POSITION_DELTA;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_VISION_POSITION_DELTA_MIN_LEN, MAVLINK_MSG_ID_VISION_POSITION_DELTA_LEN, MAVLINK_MSG_ID_VISION_POSITION_DELTA_CRC);
}
/**
* @brief Encode a vision_position_delta struct
*
* @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_delta C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_vision_position_delta_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_vision_position_delta_t* vision_position_delta)
{
return mavlink_msg_vision_position_delta_pack(system_id, component_id, msg, vision_position_delta->time_usec, vision_position_delta->time_delta_usec, vision_position_delta->angle_delta, vision_position_delta->position_delta, vision_position_delta->confidence);
}
/**
* @brief Encode a vision_position_delta struct on a channel
*
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param vision_position_delta C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_vision_position_delta_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_vision_position_delta_t* vision_position_delta)
{
return mavlink_msg_vision_position_delta_pack_chan(system_id, component_id, chan, msg, vision_position_delta->time_usec, vision_position_delta->time_delta_usec, vision_position_delta->angle_delta, vision_position_delta->position_delta, vision_position_delta->confidence);
}
/**
* @brief Send a vision_position_delta message
* @param chan MAVLink channel to send the message
*
* @param time_usec [us] Timestamp (synced to UNIX time or since system boot).
* @param time_delta_usec [us] Time since the last reported camera frame.
* @param angle_delta Defines a rotation vector in body frame that rotates the vehicle from the previous to the current orientation.
* @param position_delta [m] Change in position from previous to current frame rotated into body frame (0=forward, 1=right, 2=down).
* @param confidence [%] Normalised confidence value from 0 to 100.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_vision_position_delta_send(mavlink_channel_t chan, uint64_t time_usec, uint64_t time_delta_usec, const float *angle_delta, const float *position_delta, float confidence)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_VISION_POSITION_DELTA_LEN];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_uint64_t(buf, 8, time_delta_usec);
_mav_put_float(buf, 40, confidence);
_mav_put_float_array(buf, 16, angle_delta, 3);
_mav_put_float_array(buf, 28, position_delta, 3);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_POSITION_DELTA, buf, MAVLINK_MSG_ID_VISION_POSITION_DELTA_MIN_LEN, MAVLINK_MSG_ID_VISION_POSITION_DELTA_LEN, MAVLINK_MSG_ID_VISION_POSITION_DELTA_CRC);
#else
mavlink_vision_position_delta_t packet;
packet.time_usec = time_usec;
packet.time_delta_usec = time_delta_usec;
packet.confidence = confidence;
mav_array_memcpy(packet.angle_delta, angle_delta, sizeof(float)*3);
mav_array_memcpy(packet.position_delta, position_delta, sizeof(float)*3);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_POSITION_DELTA, (const char *)&packet, MAVLINK_MSG_ID_VISION_POSITION_DELTA_MIN_LEN, MAVLINK_MSG_ID_VISION_POSITION_DELTA_LEN, MAVLINK_MSG_ID_VISION_POSITION_DELTA_CRC);
#endif
}
/**
* @brief Send a vision_position_delta message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_vision_position_delta_send_struct(mavlink_channel_t chan, const mavlink_vision_position_delta_t* vision_position_delta)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_vision_position_delta_send(chan, vision_position_delta->time_usec, vision_position_delta->time_delta_usec, vision_position_delta->angle_delta, vision_position_delta->position_delta, vision_position_delta->confidence);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_POSITION_DELTA, (const char *)vision_position_delta, MAVLINK_MSG_ID_VISION_POSITION_DELTA_MIN_LEN, MAVLINK_MSG_ID_VISION_POSITION_DELTA_LEN, MAVLINK_MSG_ID_VISION_POSITION_DELTA_CRC);
#endif
}
#if MAVLINK_MSG_ID_VISION_POSITION_DELTA_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_vision_position_delta_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint64_t time_delta_usec, const float *angle_delta, const float *position_delta, float confidence)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_uint64_t(buf, 8, time_delta_usec);
_mav_put_float(buf, 40, confidence);
_mav_put_float_array(buf, 16, angle_delta, 3);
_mav_put_float_array(buf, 28, position_delta, 3);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_POSITION_DELTA, buf, MAVLINK_MSG_ID_VISION_POSITION_DELTA_MIN_LEN, MAVLINK_MSG_ID_VISION_POSITION_DELTA_LEN, MAVLINK_MSG_ID_VISION_POSITION_DELTA_CRC);
#else
mavlink_vision_position_delta_t *packet = (mavlink_vision_position_delta_t *)msgbuf;
packet->time_usec = time_usec;
packet->time_delta_usec = time_delta_usec;
packet->confidence = confidence;
mav_array_memcpy(packet->angle_delta, angle_delta, sizeof(float)*3);
mav_array_memcpy(packet->position_delta, position_delta, sizeof(float)*3);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_POSITION_DELTA, (const char *)packet, MAVLINK_MSG_ID_VISION_POSITION_DELTA_MIN_LEN, MAVLINK_MSG_ID_VISION_POSITION_DELTA_LEN, MAVLINK_MSG_ID_VISION_POSITION_DELTA_CRC);
#endif
}
#endif
#endif
// MESSAGE VISION_POSITION_DELTA UNPACKING
/**
* @brief Get field time_usec from vision_position_delta message
*
* @return [us] Timestamp (synced to UNIX time or since system boot).
*/
static inline uint64_t mavlink_msg_vision_position_delta_get_time_usec(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint64_t(msg, 0);
}
/**
* @brief Get field time_delta_usec from vision_position_delta message
*
* @return [us] Time since the last reported camera frame.
*/
static inline uint64_t mavlink_msg_vision_position_delta_get_time_delta_usec(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint64_t(msg, 8);
}
/**
* @brief Get field angle_delta from vision_position_delta message
*
* @return Defines a rotation vector in body frame that rotates the vehicle from the previous to the current orientation.
*/
static inline uint16_t mavlink_msg_vision_position_delta_get_angle_delta(const mavlink_message_t* msg, float *angle_delta)
{
return _MAV_RETURN_float_array(msg, angle_delta, 3, 16);
}
/**
* @brief Get field position_delta from vision_position_delta message
*
* @return [m] Change in position from previous to current frame rotated into body frame (0=forward, 1=right, 2=down).
*/
static inline uint16_t mavlink_msg_vision_position_delta_get_position_delta(const mavlink_message_t* msg, float *position_delta)
{
return _MAV_RETURN_float_array(msg, position_delta, 3, 28);
}
/**
* @brief Get field confidence from vision_position_delta message
*
* @return [%] Normalised confidence value from 0 to 100.
*/
static inline float mavlink_msg_vision_position_delta_get_confidence(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 40);
}
/**
* @brief Decode a vision_position_delta message into a struct
*
* @param msg The message to decode
* @param vision_position_delta C-struct to decode the message contents into
*/
static inline void mavlink_msg_vision_position_delta_decode(const mavlink_message_t* msg, mavlink_vision_position_delta_t* vision_position_delta)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
vision_position_delta->time_usec = mavlink_msg_vision_position_delta_get_time_usec(msg);
vision_position_delta->time_delta_usec = mavlink_msg_vision_position_delta_get_time_delta_usec(msg);
mavlink_msg_vision_position_delta_get_angle_delta(msg, vision_position_delta->angle_delta);
mavlink_msg_vision_position_delta_get_position_delta(msg, vision_position_delta->position_delta);
vision_position_delta->confidence = mavlink_msg_vision_position_delta_get_confidence(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_VISION_POSITION_DELTA_LEN? msg->len : MAVLINK_MSG_ID_VISION_POSITION_DELTA_LEN;
memset(vision_position_delta, 0, MAVLINK_MSG_ID_VISION_POSITION_DELTA_LEN);
memcpy(vision_position_delta, _MAV_PAYLOAD(msg), len);
#endif
}

View File

@@ -0,0 +1,263 @@
#pragma once
// MESSAGE WIND PACKING
#define MAVLINK_MSG_ID_WIND 168
MAVPACKED(
typedef struct __mavlink_wind_t {
float direction; /*< [deg] Wind direction (that wind is coming from).*/
float speed; /*< [m/s] Wind speed in ground plane.*/
float speed_z; /*< [m/s] Vertical wind speed.*/
}) mavlink_wind_t;
#define MAVLINK_MSG_ID_WIND_LEN 12
#define MAVLINK_MSG_ID_WIND_MIN_LEN 12
#define MAVLINK_MSG_ID_168_LEN 12
#define MAVLINK_MSG_ID_168_MIN_LEN 12
#define MAVLINK_MSG_ID_WIND_CRC 1
#define MAVLINK_MSG_ID_168_CRC 1
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_WIND { \
168, \
"WIND", \
3, \
{ { "direction", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_wind_t, direction) }, \
{ "speed", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_wind_t, speed) }, \
{ "speed_z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_wind_t, speed_z) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_WIND { \
"WIND", \
3, \
{ { "direction", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_wind_t, direction) }, \
{ "speed", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_wind_t, speed) }, \
{ "speed_z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_wind_t, speed_z) }, \
} \
}
#endif
/**
* @brief Pack a wind 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 direction [deg] Wind direction (that wind is coming from).
* @param speed [m/s] Wind speed in ground plane.
* @param speed_z [m/s] Vertical wind speed.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_wind_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
float direction, float speed, float speed_z)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_WIND_LEN];
_mav_put_float(buf, 0, direction);
_mav_put_float(buf, 4, speed);
_mav_put_float(buf, 8, speed_z);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_WIND_LEN);
#else
mavlink_wind_t packet;
packet.direction = direction;
packet.speed = speed;
packet.speed_z = speed_z;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_WIND_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_WIND;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_WIND_MIN_LEN, MAVLINK_MSG_ID_WIND_LEN, MAVLINK_MSG_ID_WIND_CRC);
}
/**
* @brief Pack a wind message on a channel
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param direction [deg] Wind direction (that wind is coming from).
* @param speed [m/s] Wind speed in ground plane.
* @param speed_z [m/s] Vertical wind speed.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_wind_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
float direction,float speed,float speed_z)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_WIND_LEN];
_mav_put_float(buf, 0, direction);
_mav_put_float(buf, 4, speed);
_mav_put_float(buf, 8, speed_z);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_WIND_LEN);
#else
mavlink_wind_t packet;
packet.direction = direction;
packet.speed = speed;
packet.speed_z = speed_z;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_WIND_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_WIND;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_WIND_MIN_LEN, MAVLINK_MSG_ID_WIND_LEN, MAVLINK_MSG_ID_WIND_CRC);
}
/**
* @brief Encode a wind struct
*
* @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 wind C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_wind_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_wind_t* wind)
{
return mavlink_msg_wind_pack(system_id, component_id, msg, wind->direction, wind->speed, wind->speed_z);
}
/**
* @brief Encode a wind struct on a channel
*
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param wind C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_wind_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_wind_t* wind)
{
return mavlink_msg_wind_pack_chan(system_id, component_id, chan, msg, wind->direction, wind->speed, wind->speed_z);
}
/**
* @brief Send a wind message
* @param chan MAVLink channel to send the message
*
* @param direction [deg] Wind direction (that wind is coming from).
* @param speed [m/s] Wind speed in ground plane.
* @param speed_z [m/s] Vertical wind speed.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_wind_send(mavlink_channel_t chan, float direction, float speed, float speed_z)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_WIND_LEN];
_mav_put_float(buf, 0, direction);
_mav_put_float(buf, 4, speed);
_mav_put_float(buf, 8, speed_z);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WIND, buf, MAVLINK_MSG_ID_WIND_MIN_LEN, MAVLINK_MSG_ID_WIND_LEN, MAVLINK_MSG_ID_WIND_CRC);
#else
mavlink_wind_t packet;
packet.direction = direction;
packet.speed = speed;
packet.speed_z = speed_z;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WIND, (const char *)&packet, MAVLINK_MSG_ID_WIND_MIN_LEN, MAVLINK_MSG_ID_WIND_LEN, MAVLINK_MSG_ID_WIND_CRC);
#endif
}
/**
* @brief Send a wind message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_wind_send_struct(mavlink_channel_t chan, const mavlink_wind_t* wind)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_wind_send(chan, wind->direction, wind->speed, wind->speed_z);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WIND, (const char *)wind, MAVLINK_MSG_ID_WIND_MIN_LEN, MAVLINK_MSG_ID_WIND_LEN, MAVLINK_MSG_ID_WIND_CRC);
#endif
}
#if MAVLINK_MSG_ID_WIND_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_wind_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float direction, float speed, float speed_z)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_float(buf, 0, direction);
_mav_put_float(buf, 4, speed);
_mav_put_float(buf, 8, speed_z);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WIND, buf, MAVLINK_MSG_ID_WIND_MIN_LEN, MAVLINK_MSG_ID_WIND_LEN, MAVLINK_MSG_ID_WIND_CRC);
#else
mavlink_wind_t *packet = (mavlink_wind_t *)msgbuf;
packet->direction = direction;
packet->speed = speed;
packet->speed_z = speed_z;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WIND, (const char *)packet, MAVLINK_MSG_ID_WIND_MIN_LEN, MAVLINK_MSG_ID_WIND_LEN, MAVLINK_MSG_ID_WIND_CRC);
#endif
}
#endif
#endif
// MESSAGE WIND UNPACKING
/**
* @brief Get field direction from wind message
*
* @return [deg] Wind direction (that wind is coming from).
*/
static inline float mavlink_msg_wind_get_direction(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 0);
}
/**
* @brief Get field speed from wind message
*
* @return [m/s] Wind speed in ground plane.
*/
static inline float mavlink_msg_wind_get_speed(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 4);
}
/**
* @brief Get field speed_z from wind message
*
* @return [m/s] Vertical wind speed.
*/
static inline float mavlink_msg_wind_get_speed_z(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
/**
* @brief Decode a wind message into a struct
*
* @param msg The message to decode
* @param wind C-struct to decode the message contents into
*/
static inline void mavlink_msg_wind_decode(const mavlink_message_t* msg, mavlink_wind_t* wind)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
wind->direction = mavlink_msg_wind_get_direction(msg);
wind->speed = mavlink_msg_wind_get_speed(msg);
wind->speed_z = mavlink_msg_wind_get_speed_z(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_WIND_LEN? msg->len : MAVLINK_MSG_ID_WIND_LEN;
memset(wind, 0, MAVLINK_MSG_ID_WIND_LEN);
memcpy(wind, _MAV_PAYLOAD(msg), len);
#endif
}

File diff suppressed because it is too large Load Diff

View File

@@ -0,0 +1,14 @@
/** @file
* @brief MAVLink comm protocol built from ardupilotmega.xml
* @see http://mavlink.org
*/
#pragma once
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Thu Aug 30 2018"
#define MAVLINK_WIRE_PROTOCOL_VERSION "2.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255
#endif // MAVLINK_VERSION_H