Commit 241d6c36 authored by oberion's avatar oberion

added SenseSoar Mavlink Messages

parent 0641c635
......@@ -51,3 +51,4 @@ user_config.pri
thirdParty/qserialport-build-desktop/
thirdParty/qserialport/bin/
thirdParty/qserialport/lib/
thirdParty/libxbee/lib
......@@ -118,6 +118,16 @@ contains(MAVLINK_CONF, ardupilotmega) {
INCLUDEPATH += $$BASEDIR/thirdParty/mavlink/include/ardupilotmega
DEFINES += QGC_USE_ARDUPILOTMEGA_MESSAGES
}
contains(MAVLINK_CONF, senseSoar) {
# Remove the default set - it is included anyway
INCLUDEPATH -= $$BASEDIR/../mavlink/include/common
INCLUDEPATH -= $$BASEDIR/thirdParty/mavlink/include/common
# SENSESOAR SPECIAL MESSAGES
INCLUDEPATH += $$BASEDIR/../mavlink/include/SenseSoar
INCLUDEPATH += $$BASEDIR/thirdParty/mavlink/include/SenseSoar
DEFINES += QGC_USE_SENSESOAR_MESSAGES
}
# Include general settings for QGroundControl
......
/** @file
* @brief MAVLink comm protocol.
* @see http://qgroundcontrol.org/mavlink/
* Generated on Tuesday, August 2 2011, 15:51 UTC
*/
#ifndef SENSESOAR_H
#define SENSESOAR_H
#ifdef __cplusplus
extern "C" {
#endif
#include "../protocol.h"
#define MAVLINK_ENABLED_SENSESOAR
#include "../common/common.h"
// MAVLINK VERSION
#ifndef MAVLINK_VERSION
#define MAVLINK_VERSION 0
#endif
#if (MAVLINK_VERSION == 0)
#undef MAVLINK_VERSION
#define MAVLINK_VERSION 0
#endif
// ENUM DEFINITIONS
/** @brief Different flight modes */
enum SENSESOAR_MODE
{
SENSESOAR_MODE_GLIDING=0, /* */
SENSESOAR_MODE_AUTONOMOUS=1, /* */
SENSESOAR_MODE_MANUAL=2, /* */
SENSESOAR_MODE_ENUM_END
};
// MESSAGE DEFINITIONS
#include "./mavlink_msg_sensesoar_mode_chng.h"
#include "./mavlink_msg_sensesoar_mode_ack.h"
#include "./mavlink_msg_sensesoar_mode_rqst.h"
#include "./mavlink_msg_sensesoar_mode_rqst_send.h"
#include "./mavlink_msg_obs_position.h"
#include "./mavlink_msg_obs_velocity.h"
#include "./mavlink_msg_obs_attitude.h"
#include "./mavlink_msg_obs_wind.h"
#include "./mavlink_msg_obs_air_velocity.h"
#include "./mavlink_msg_obs_bias.h"
#include "./mavlink_msg_obs_qff.h"
#include "./mavlink_msg_obs_air_temp.h"
#include "./mavlink_msg_filt_rot_vel.h"
#include "./mavlink_msg_llc_out.h"
#include "./mavlink_msg_pm_elec.h"
#include "./mavlink_msg_sys_stat.h"
#include "./mavlink_msg_cmd_airspeed_chng.h"
#include "./mavlink_msg_cmd_airspeed_ack.h"
// MESSAGE LENGTHS
#undef MAVLINK_MESSAGE_LENGTHS
#define MAVLINK_MESSAGE_LENGTHS { 3, 4, 8, 14, 8, 28, 3, 32, 0, 2, 3, 2, 2, 0, 0, 0, 0, 0, 0, 0, 19, 2, 23, 21, 0, 37, 26, 101, 26, 16, 32, 32, 37, 32, 11, 17, 17, 16, 18, 36, 4, 4, 2, 2, 4, 2, 2, 3, 14, 12, 18, 16, 8, 27, 25, 0, 0, 0, 0, 0, 5, 5, 26, 16, 36, 5, 6, 0, 0, 21, 0, 0, 0, 18, 20, 20, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 2, 2, 1, 1, 24, 0, 12, 0, 16, 0, 12, 0, 12, 0, 24, 0, 4, 4, 12, 0, 12, 0, 20, 0, 4, 0, 5, 0, 5, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 30, 14, 14, 51 }
#ifdef __cplusplus
}
#endif
#endif
/** @file
* @brief MAVLink comm protocol.
* @see http://pixhawk.ethz.ch/software/mavlink
* Generated on Tuesday, August 2 2011, 15:51 UTC
*/
#ifndef MAVLINK_H
#define MAVLINK_H
#include "SenseSoar.h"
#endif
// MESSAGE CMD_AIRSPEED_ACK PACKING
#define MAVLINK_MSG_ID_CMD_AIRSPEED_ACK 194
typedef struct __mavlink_cmd_airspeed_ack_t
{
float spCmd; ///< commanded airspeed
uint8_t ack; ///< 0:ack, 1:nack
} mavlink_cmd_airspeed_ack_t;
/**
* @brief Pack a cmd_airspeed_ack message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param spCmd commanded airspeed
* @param ack 0:ack, 1:nack
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_cmd_airspeed_ack_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, float spCmd, uint8_t ack)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_CMD_AIRSPEED_ACK;
i += put_float_by_index(spCmd, i, msg->payload); // commanded airspeed
i += put_uint8_t_by_index(ack, i, msg->payload); // 0:ack, 1:nack
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a cmd_airspeed_ack message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param spCmd commanded airspeed
* @param ack 0:ack, 1:nack
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_cmd_airspeed_ack_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, float spCmd, uint8_t ack)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_CMD_AIRSPEED_ACK;
i += put_float_by_index(spCmd, i, msg->payload); // commanded airspeed
i += put_uint8_t_by_index(ack, i, msg->payload); // 0:ack, 1:nack
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a cmd_airspeed_ack struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param cmd_airspeed_ack C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_cmd_airspeed_ack_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_cmd_airspeed_ack_t* cmd_airspeed_ack)
{
return mavlink_msg_cmd_airspeed_ack_pack(system_id, component_id, msg, cmd_airspeed_ack->spCmd, cmd_airspeed_ack->ack);
}
/**
* @brief Send a cmd_airspeed_ack message
* @param chan MAVLink channel to send the message
*
* @param spCmd commanded airspeed
* @param ack 0:ack, 1:nack
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_cmd_airspeed_ack_send(mavlink_channel_t chan, float spCmd, uint8_t ack)
{
mavlink_message_t msg;
mavlink_msg_cmd_airspeed_ack_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, spCmd, ack);
mavlink_send_uart(chan, &msg);
}
#endif
// MESSAGE CMD_AIRSPEED_ACK UNPACKING
/**
* @brief Get field spCmd from cmd_airspeed_ack message
*
* @return commanded airspeed
*/
static inline float mavlink_msg_cmd_airspeed_ack_get_spCmd(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload)[0];
r.b[2] = (msg->payload)[1];
r.b[1] = (msg->payload)[2];
r.b[0] = (msg->payload)[3];
return (float)r.f;
}
/**
* @brief Get field ack from cmd_airspeed_ack message
*
* @return 0:ack, 1:nack
*/
static inline uint8_t mavlink_msg_cmd_airspeed_ack_get_ack(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload+sizeof(float))[0];
}
/**
* @brief Decode a cmd_airspeed_ack message into a struct
*
* @param msg The message to decode
* @param cmd_airspeed_ack C-struct to decode the message contents into
*/
static inline void mavlink_msg_cmd_airspeed_ack_decode(const mavlink_message_t* msg, mavlink_cmd_airspeed_ack_t* cmd_airspeed_ack)
{
cmd_airspeed_ack->spCmd = mavlink_msg_cmd_airspeed_ack_get_spCmd(msg);
cmd_airspeed_ack->ack = mavlink_msg_cmd_airspeed_ack_get_ack(msg);
}
// MESSAGE CMD_AIRSPEED_CHNG PACKING
#define MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG 192
typedef struct __mavlink_cmd_airspeed_chng_t
{
uint8_t target; ///< Target ID
float spCmd; ///< commanded airspeed
} mavlink_cmd_airspeed_chng_t;
/**
* @brief Pack a cmd_airspeed_chng 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 Target ID
* @param spCmd commanded airspeed
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_cmd_airspeed_chng_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target, float spCmd)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG;
i += put_uint8_t_by_index(target, i, msg->payload); // Target ID
i += put_float_by_index(spCmd, i, msg->payload); // commanded airspeed
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a cmd_airspeed_chng message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param target Target ID
* @param spCmd commanded airspeed
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_cmd_airspeed_chng_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target, float spCmd)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG;
i += put_uint8_t_by_index(target, i, msg->payload); // Target ID
i += put_float_by_index(spCmd, i, msg->payload); // commanded airspeed
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a cmd_airspeed_chng struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param cmd_airspeed_chng C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_cmd_airspeed_chng_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_cmd_airspeed_chng_t* cmd_airspeed_chng)
{
return mavlink_msg_cmd_airspeed_chng_pack(system_id, component_id, msg, cmd_airspeed_chng->target, cmd_airspeed_chng->spCmd);
}
/**
* @brief Send a cmd_airspeed_chng message
* @param chan MAVLink channel to send the message
*
* @param target Target ID
* @param spCmd commanded airspeed
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_cmd_airspeed_chng_send(mavlink_channel_t chan, uint8_t target, float spCmd)
{
mavlink_message_t msg;
mavlink_msg_cmd_airspeed_chng_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target, spCmd);
mavlink_send_uart(chan, &msg);
}
#endif
// MESSAGE CMD_AIRSPEED_CHNG UNPACKING
/**
* @brief Get field target from cmd_airspeed_chng message
*
* @return Target ID
*/
static inline uint8_t mavlink_msg_cmd_airspeed_chng_get_target(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload)[0];
}
/**
* @brief Get field spCmd from cmd_airspeed_chng message
*
* @return commanded airspeed
*/
static inline float mavlink_msg_cmd_airspeed_chng_get_spCmd(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(uint8_t))[0];
r.b[2] = (msg->payload+sizeof(uint8_t))[1];
r.b[1] = (msg->payload+sizeof(uint8_t))[2];
r.b[0] = (msg->payload+sizeof(uint8_t))[3];
return (float)r.f;
}
/**
* @brief Decode a cmd_airspeed_chng message into a struct
*
* @param msg The message to decode
* @param cmd_airspeed_chng C-struct to decode the message contents into
*/
static inline void mavlink_msg_cmd_airspeed_chng_decode(const mavlink_message_t* msg, mavlink_cmd_airspeed_chng_t* cmd_airspeed_chng)
{
cmd_airspeed_chng->target = mavlink_msg_cmd_airspeed_chng_get_target(msg);
cmd_airspeed_chng->spCmd = mavlink_msg_cmd_airspeed_chng_get_spCmd(msg);
}
// MESSAGE FILT_ROT_VEL PACKING
#define MAVLINK_MSG_ID_FILT_ROT_VEL 184
typedef struct __mavlink_filt_rot_vel_t
{
float rotVel[3]; ///< rotational velocity
} mavlink_filt_rot_vel_t;
#define MAVLINK_MSG_FILT_ROT_VEL_FIELD_ROTVEL_LEN 3
/**
* @brief Pack a filt_rot_vel 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 rotVel rotational velocity
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_filt_rot_vel_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const float* rotVel)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_FILT_ROT_VEL;
i += put_array_by_index((const int8_t*)rotVel, sizeof(float)*3, i, msg->payload); // rotational velocity
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a filt_rot_vel message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param rotVel rotational velocity
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_filt_rot_vel_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const float* rotVel)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_FILT_ROT_VEL;
i += put_array_by_index((const int8_t*)rotVel, sizeof(float)*3, i, msg->payload); // rotational velocity
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a filt_rot_vel struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param filt_rot_vel C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_filt_rot_vel_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_filt_rot_vel_t* filt_rot_vel)
{
return mavlink_msg_filt_rot_vel_pack(system_id, component_id, msg, filt_rot_vel->rotVel);
}
/**
* @brief Send a filt_rot_vel message
* @param chan MAVLink channel to send the message
*
* @param rotVel rotational velocity
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_filt_rot_vel_send(mavlink_channel_t chan, const float* rotVel)
{
mavlink_message_t msg;
mavlink_msg_filt_rot_vel_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, rotVel);
mavlink_send_uart(chan, &msg);
}
#endif
// MESSAGE FILT_ROT_VEL UNPACKING
/**
* @brief Get field rotVel from filt_rot_vel message
*
* @return rotational velocity
*/
static inline uint16_t mavlink_msg_filt_rot_vel_get_rotVel(const mavlink_message_t* msg, float* r_data)
{
memcpy(r_data, msg->payload, sizeof(float)*3);
return sizeof(float)*3;
}
/**
* @brief Decode a filt_rot_vel message into a struct
*
* @param msg The message to decode
* @param filt_rot_vel C-struct to decode the message contents into
*/
static inline void mavlink_msg_filt_rot_vel_decode(const mavlink_message_t* msg, mavlink_filt_rot_vel_t* filt_rot_vel)
{
mavlink_msg_filt_rot_vel_get_rotVel(msg, filt_rot_vel->rotVel);
}
// MESSAGE LLC_OUT PACKING
#define MAVLINK_MSG_ID_LLC_OUT 186
typedef struct __mavlink_llc_out_t
{
int16_t servoOut[4]; ///< Servo signal
int16_t MotorOut[2]; ///< motor signal
} mavlink_llc_out_t;
#define MAVLINK_MSG_LLC_OUT_FIELD_SERVOOUT_LEN 4
#define MAVLINK_MSG_LLC_OUT_FIELD_MOTOROUT_LEN 2
/**
* @brief Pack a llc_out 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 servoOut Servo signal
* @param MotorOut motor signal
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_llc_out_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const int16_t* servoOut, const int16_t* MotorOut)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_LLC_OUT;
i += put_array_by_index((const int8_t*)servoOut, sizeof(int16_t)*4, i, msg->payload); // Servo signal
i += put_array_by_index((const int8_t*)MotorOut, sizeof(int16_t)*2, i, msg->payload); // motor signal
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a llc_out message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param servoOut Servo signal
* @param MotorOut motor signal
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_llc_out_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const int16_t* servoOut, const int16_t* MotorOut)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_LLC_OUT;
i += put_array_by_index((const int8_t*)servoOut, sizeof(int16_t)*4, i, msg->payload); // Servo signal
i += put_array_by_index((const int8_t*)MotorOut, sizeof(int16_t)*2, i, msg->payload); // motor signal
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a llc_out struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param llc_out C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_llc_out_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_llc_out_t* llc_out)
{
return mavlink_msg_llc_out_pack(system_id, component_id, msg, llc_out->servoOut, llc_out->MotorOut);
}
/**
* @brief Send a llc_out message
* @param chan MAVLink channel to send the message
*
* @param servoOut Servo signal
* @param MotorOut motor signal
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_llc_out_send(mavlink_channel_t chan, const int16_t* servoOut, const int16_t* MotorOut)
{
mavlink_message_t msg;
mavlink_msg_llc_out_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, servoOut, MotorOut);
mavlink_send_uart(chan, &msg);
}
#endif
// MESSAGE LLC_OUT UNPACKING
/**
* @brief Get field servoOut from llc_out message
*
* @return Servo signal
*/
static inline uint16_t mavlink_msg_llc_out_get_servoOut(const mavlink_message_t* msg, int16_t* r_data)
{
memcpy(r_data, msg->payload, sizeof(int16_t)*4);
return sizeof(int16_t)*4;
}
/**
* @brief Get field MotorOut from llc_out message
*
* @return motor signal
*/
static inline uint16_t mavlink_msg_llc_out_get_MotorOut(const mavlink_message_t* msg, int16_t* r_data)
{
memcpy(r_data, msg->payload+sizeof(int16_t)*4, sizeof(int16_t)*2);
return sizeof(int16_t)*2;
}
/**
* @brief Decode a llc_out message into a struct
*
* @param msg The message to decode
* @param llc_out C-struct to decode the message contents into
*/
static inline void mavlink_msg_llc_out_decode(const mavlink_message_t* msg, mavlink_llc_out_t* llc_out)
{
mavlink_msg_llc_out_get_servoOut(msg, llc_out->servoOut);
mavlink_msg_llc_out_get_MotorOut(msg, llc_out->MotorOut);
}
// MESSAGE OBS_AIR_TEMP PACKING
#define MAVLINK_MSG_ID_OBS_AIR_TEMP 183
typedef struct __mavlink_obs_air_temp_t
{
float airT; ///< Air Temperatur
} mavlink_obs_air_temp_t;
/**
* @brief Pack a obs_air_temp 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 airT Air Temperatur
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_obs_air_temp_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, float airT)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_OBS_AIR_TEMP;
i += put_float_by_index(airT, i, msg->payload); // Air Temperatur
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a obs_air_temp message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param airT Air Temperatur
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_obs_air_temp_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, float airT)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_OBS_AIR_TEMP;
i += put_float_by_index(airT, i, msg->payload); // Air Temperatur
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a obs_air_temp struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param obs_air_temp C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_obs_air_temp_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_obs_air_temp_t* obs_air_temp)
{
return mavlink_msg_obs_air_temp_pack(system_id, component_id, msg, obs_air_temp->airT);
}
/**
* @brief Send a obs_air_temp message
* @param chan MAVLink channel to send the message
*
* @param airT Air Temperatur
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_obs_air_temp_send(mavlink_channel_t chan, float airT)
{
mavlink_message_t msg;
mavlink_msg_obs_air_temp_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, airT);
mavlink_send_uart(chan, &msg);
}
#endif
// MESSAGE OBS_AIR_TEMP UNPACKING
/**
* @brief Get field airT from obs_air_temp message
*
* @return Air Temperatur
*/
static inline float mavlink_msg_obs_air_temp_get_airT(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload)[0];
r.b[2] = (msg->payload)[1];
r.b[1] = (msg->payload)[2];
r.b[0] = (msg->payload)[3];
return (float)r.f;
}
/**
* @brief Decode a obs_air_temp message into a struct
*
* @param msg The message to decode
* @param obs_air_temp C-struct to decode the message contents into
*/
static inline void mavlink_msg_obs_air_temp_decode(const mavlink_message_t* msg, mavlink_obs_air_temp_t* obs_air_temp)
{
obs_air_temp->airT = mavlink_msg_obs_air_temp_get_airT(msg);
}
// MESSAGE OBS_AIR_VELOCITY PACKING
#define MAVLINK_MSG_ID_OBS_AIR_VELOCITY 178
typedef struct __mavlink_obs_air_velocity_t
{
float magnitude; ///< Air speed
float aoa; ///< angle of attack
float slip; ///< slip angle
} mavlink_obs_air_velocity_t;
/**
* @brief Pack a obs_air_velocity 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 magnitude Air speed
* @param aoa angle of attack
* @param slip slip angle
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_obs_air_velocity_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, float magnitude, float aoa, float slip)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_OBS_AIR_VELOCITY;
i += put_float_by_index(magnitude, i, msg->payload); // Air speed
i += put_float_by_index(aoa, i, msg->payload); // angle of attack
i += put_float_by_index(slip, i, msg->payload); // slip angle
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a obs_air_velocity message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param magnitude Air speed
* @param aoa angle of attack
* @param slip slip angle
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_obs_air_velocity_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, float magnitude, float aoa, float slip)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_OBS_AIR_VELOCITY;
i += put_float_by_index(magnitude, i, msg->payload); // Air speed
i += put_float_by_index(aoa, i, msg->payload); // angle of attack
i += put_float_by_index(slip, i, msg->payload); // slip angle
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a obs_air_velocity struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param obs_air_velocity C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_obs_air_velocity_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_obs_air_velocity_t* obs_air_velocity)
{
return mavlink_msg_obs_air_velocity_pack(system_id, component_id, msg, obs_air_velocity->magnitude, obs_air_velocity->aoa, obs_air_velocity->slip);
}
/**
* @brief Send a obs_air_velocity message
* @param chan MAVLink channel to send the message
*
* @param magnitude Air speed
* @param aoa angle of attack
* @param slip slip angle
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_obs_air_velocity_send(mavlink_channel_t chan, float magnitude, float aoa, float slip)
{
mavlink_message_t msg;
mavlink_msg_obs_air_velocity_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, magnitude, aoa, slip);
mavlink_send_uart(chan, &msg);
}
#endif
// MESSAGE OBS_AIR_VELOCITY UNPACKING
/**
* @brief Get field magnitude from obs_air_velocity message
*
* @return Air speed
*/
static inline float mavlink_msg_obs_air_velocity_get_magnitude(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload)[0];
r.b[2] = (msg->payload)[1];
r.b[1] = (msg->payload)[2];
r.b[0] = (msg->payload)[3];
return (float)r.f;
}
/**
* @brief Get field aoa from obs_air_velocity message
*
* @return angle of attack
*/
static inline float mavlink_msg_obs_air_velocity_get_aoa(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(float))[3];
return (float)r.f;
}
/**
* @brief Get field slip from obs_air_velocity message
*
* @return slip angle
*/
static inline float mavlink_msg_obs_air_velocity_get_slip(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(float)+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(float)+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(float)+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(float)+sizeof(float))[3];
return (float)r.f;
}
/**
* @brief Decode a obs_air_velocity message into a struct
*
* @param msg The message to decode
* @param obs_air_velocity C-struct to decode the message contents into
*/
static inline void mavlink_msg_obs_air_velocity_decode(const mavlink_message_t* msg, mavlink_obs_air_velocity_t* obs_air_velocity)
{
obs_air_velocity->magnitude = mavlink_msg_obs_air_velocity_get_magnitude(msg);
obs_air_velocity->aoa = mavlink_msg_obs_air_velocity_get_aoa(msg);
obs_air_velocity->slip = mavlink_msg_obs_air_velocity_get_slip(msg);
}
// MESSAGE OBS_ATTITUDE PACKING
#define MAVLINK_MSG_ID_OBS_ATTITUDE 174
typedef struct __mavlink_obs_attitude_t
{
float quat[4]; ///< Quaternion re;im
} mavlink_obs_attitude_t;
#define MAVLINK_MSG_OBS_ATTITUDE_FIELD_QUAT_LEN 4
/**
* @brief Pack a obs_attitude message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param quat Quaternion re;im
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_obs_attitude_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const float* quat)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_OBS_ATTITUDE;
i += put_array_by_index((const int8_t*)quat, sizeof(float)*4, i, msg->payload); // Quaternion re;im
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a obs_attitude message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param quat Quaternion re;im
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_obs_attitude_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const float* quat)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_OBS_ATTITUDE;
i += put_array_by_index((const int8_t*)quat, sizeof(float)*4, i, msg->payload); // Quaternion re;im
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a obs_attitude struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param obs_attitude C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_obs_attitude_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_obs_attitude_t* obs_attitude)
{
return mavlink_msg_obs_attitude_pack(system_id, component_id, msg, obs_attitude->quat);
}
/**
* @brief Send a obs_attitude message
* @param chan MAVLink channel to send the message
*
* @param quat Quaternion re;im
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_obs_attitude_send(mavlink_channel_t chan, const float* quat)
{
mavlink_message_t msg;
mavlink_msg_obs_attitude_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, quat);
mavlink_send_uart(chan, &msg);
}
#endif
// MESSAGE OBS_ATTITUDE UNPACKING
/**
* @brief Get field quat from obs_attitude message
*
* @return Quaternion re;im
*/
static inline uint16_t mavlink_msg_obs_attitude_get_quat(const mavlink_message_t* msg, float* r_data)
{
memcpy(r_data, msg->payload, sizeof(float)*4);
return sizeof(float)*4;
}
/**
* @brief Decode a obs_attitude message into a struct
*
* @param msg The message to decode
* @param obs_attitude C-struct to decode the message contents into
*/
static inline void mavlink_msg_obs_attitude_decode(const mavlink_message_t* msg, mavlink_obs_attitude_t* obs_attitude)
{
mavlink_msg_obs_attitude_get_quat(msg, obs_attitude->quat);
}
// MESSAGE OBS_BIAS PACKING
#define MAVLINK_MSG_ID_OBS_BIAS 180
typedef struct __mavlink_obs_bias_t
{
float accBias[3]; ///< accelerometer bias
float gyroBias[3]; ///< gyroscope bias
} mavlink_obs_bias_t;
#define MAVLINK_MSG_OBS_BIAS_FIELD_ACCBIAS_LEN 3
#define MAVLINK_MSG_OBS_BIAS_FIELD_GYROBIAS_LEN 3
/**
* @brief Pack a obs_bias 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 accBias accelerometer bias
* @param gyroBias gyroscope bias
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_obs_bias_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const float* accBias, const float* gyroBias)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_OBS_BIAS;
i += put_array_by_index((const int8_t*)accBias, sizeof(float)*3, i, msg->payload); // accelerometer bias
i += put_array_by_index((const int8_t*)gyroBias, sizeof(float)*3, i, msg->payload); // gyroscope bias
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a obs_bias message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param accBias accelerometer bias
* @param gyroBias gyroscope bias
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_obs_bias_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const float* accBias, const float* gyroBias)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_OBS_BIAS;
i += put_array_by_index((const int8_t*)accBias, sizeof(float)*3, i, msg->payload); // accelerometer bias
i += put_array_by_index((const int8_t*)gyroBias, sizeof(float)*3, i, msg->payload); // gyroscope bias
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a obs_bias struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param obs_bias C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_obs_bias_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_obs_bias_t* obs_bias)
{
return mavlink_msg_obs_bias_pack(system_id, component_id, msg, obs_bias->accBias, obs_bias->gyroBias);
}
/**
* @brief Send a obs_bias message
* @param chan MAVLink channel to send the message
*
* @param accBias accelerometer bias
* @param gyroBias gyroscope bias
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_obs_bias_send(mavlink_channel_t chan, const float* accBias, const float* gyroBias)
{
mavlink_message_t msg;
mavlink_msg_obs_bias_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, accBias, gyroBias);
mavlink_send_uart(chan, &msg);
}
#endif
// MESSAGE OBS_BIAS UNPACKING
/**
* @brief Get field accBias from obs_bias message
*
* @return accelerometer bias
*/
static inline uint16_t mavlink_msg_obs_bias_get_accBias(const mavlink_message_t* msg, float* r_data)
{
memcpy(r_data, msg->payload, sizeof(float)*3);
return sizeof(float)*3;
}
/**
* @brief Get field gyroBias from obs_bias message
*
* @return gyroscope bias
*/
static inline uint16_t mavlink_msg_obs_bias_get_gyroBias(const mavlink_message_t* msg, float* r_data)
{
memcpy(r_data, msg->payload+sizeof(float)*3, sizeof(float)*3);
return sizeof(float)*3;
}
/**
* @brief Decode a obs_bias message into a struct
*
* @param msg The message to decode
* @param obs_bias C-struct to decode the message contents into
*/
static inline void mavlink_msg_obs_bias_decode(const mavlink_message_t* msg, mavlink_obs_bias_t* obs_bias)
{
mavlink_msg_obs_bias_get_accBias(msg, obs_bias->accBias);
mavlink_msg_obs_bias_get_gyroBias(msg, obs_bias->gyroBias);
}
// MESSAGE OBS_POSITION PACKING
#define MAVLINK_MSG_ID_OBS_POSITION 170
typedef struct __mavlink_obs_position_t
{
double pos[3]; ///< Position
} mavlink_obs_position_t;
#define MAVLINK_MSG_OBS_POSITION_FIELD_POS_LEN 3
/**
* @brief Pack a obs_position message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param pos Position
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_obs_position_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const double* pos)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_OBS_POSITION;
i += put_array_by_index((const int8_t*)pos, sizeof(double)*3, i, msg->payload); // Position
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a obs_position message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param pos Position
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_obs_position_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const double* pos)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_OBS_POSITION;
i += put_array_by_index((const int8_t*)pos, sizeof(double)*3, i, msg->payload); // Position
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a obs_position struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param obs_position C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_obs_position_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_obs_position_t* obs_position)
{
return mavlink_msg_obs_position_pack(system_id, component_id, msg, obs_position->pos);
}
/**
* @brief Send a obs_position message
* @param chan MAVLink channel to send the message
*
* @param pos Position
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_obs_position_send(mavlink_channel_t chan, const double* pos)
{
mavlink_message_t msg;
mavlink_msg_obs_position_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, pos);
mavlink_send_uart(chan, &msg);
}
#endif
// MESSAGE OBS_POSITION UNPACKING
/**
* @brief Get field pos from obs_position message
*
* @return Position
*/
static inline uint16_t mavlink_msg_obs_position_get_pos(const mavlink_message_t* msg, double* r_data)
{
memcpy(r_data, msg->payload, sizeof(double)*3);
return sizeof(double)*3;
}
/**
* @brief Decode a obs_position message into a struct
*
* @param msg The message to decode
* @param obs_position C-struct to decode the message contents into
*/
static inline void mavlink_msg_obs_position_decode(const mavlink_message_t* msg, mavlink_obs_position_t* obs_position)
{
mavlink_msg_obs_position_get_pos(msg, obs_position->pos);
}
// MESSAGE OBS_QFF PACKING
#define MAVLINK_MSG_ID_OBS_QFF 182
typedef struct __mavlink_obs_qff_t
{
float qff; ///< Wind
} mavlink_obs_qff_t;
/**
* @brief Pack a obs_qff 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 qff Wind
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_obs_qff_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, float qff)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_OBS_QFF;
i += put_float_by_index(qff, i, msg->payload); // Wind
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a obs_qff message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param qff Wind
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_obs_qff_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, float qff)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_OBS_QFF;
i += put_float_by_index(qff, i, msg->payload); // Wind
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a obs_qff struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param obs_qff C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_obs_qff_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_obs_qff_t* obs_qff)
{
return mavlink_msg_obs_qff_pack(system_id, component_id, msg, obs_qff->qff);
}
/**
* @brief Send a obs_qff message
* @param chan MAVLink channel to send the message
*
* @param qff Wind
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_obs_qff_send(mavlink_channel_t chan, float qff)
{
mavlink_message_t msg;
mavlink_msg_obs_qff_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, qff);
mavlink_send_uart(chan, &msg);
}
#endif
// MESSAGE OBS_QFF UNPACKING
/**
* @brief Get field qff from obs_qff message
*
* @return Wind
*/
static inline float mavlink_msg_obs_qff_get_qff(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload)[0];
r.b[2] = (msg->payload)[1];
r.b[1] = (msg->payload)[2];
r.b[0] = (msg->payload)[3];
return (float)r.f;
}
/**
* @brief Decode a obs_qff message into a struct
*
* @param msg The message to decode
* @param obs_qff C-struct to decode the message contents into
*/
static inline void mavlink_msg_obs_qff_decode(const mavlink_message_t* msg, mavlink_obs_qff_t* obs_qff)
{
obs_qff->qff = mavlink_msg_obs_qff_get_qff(msg);
}
// MESSAGE OBS_VELOCITY PACKING
#define MAVLINK_MSG_ID_OBS_VELOCITY 172
typedef struct __mavlink_obs_velocity_t
{
float vel[3]; ///< Velocity
} mavlink_obs_velocity_t;
#define MAVLINK_MSG_OBS_VELOCITY_FIELD_VEL_LEN 3
/**
* @brief Pack a obs_velocity 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 vel Velocity
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_obs_velocity_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const float* vel)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_OBS_VELOCITY;
i += put_array_by_index((const int8_t*)vel, sizeof(float)*3, i, msg->payload); // Velocity
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a obs_velocity message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param vel Velocity
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_obs_velocity_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const float* vel)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_OBS_VELOCITY;
i += put_array_by_index((const int8_t*)vel, sizeof(float)*3, i, msg->payload); // Velocity
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a obs_velocity struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param obs_velocity C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_obs_velocity_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_obs_velocity_t* obs_velocity)
{
return mavlink_msg_obs_velocity_pack(system_id, component_id, msg, obs_velocity->vel);
}
/**
* @brief Send a obs_velocity message
* @param chan MAVLink channel to send the message
*
* @param vel Velocity
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_obs_velocity_send(mavlink_channel_t chan, const float* vel)
{
mavlink_message_t msg;
mavlink_msg_obs_velocity_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, vel);
mavlink_send_uart(chan, &msg);
}
#endif
// MESSAGE OBS_VELOCITY UNPACKING
/**
* @brief Get field vel from obs_velocity message
*
* @return Velocity
*/
static inline uint16_t mavlink_msg_obs_velocity_get_vel(const mavlink_message_t* msg, float* r_data)
{
memcpy(r_data, msg->payload, sizeof(float)*3);
return sizeof(float)*3;
}
/**
* @brief Decode a obs_velocity message into a struct
*
* @param msg The message to decode
* @param obs_velocity C-struct to decode the message contents into
*/
static inline void mavlink_msg_obs_velocity_decode(const mavlink_message_t* msg, mavlink_obs_velocity_t* obs_velocity)
{
mavlink_msg_obs_velocity_get_vel(msg, obs_velocity->vel);
}
// MESSAGE OBS_WIND PACKING
#define MAVLINK_MSG_ID_OBS_WIND 176
typedef struct __mavlink_obs_wind_t
{
float wind[3]; ///< Wind
} mavlink_obs_wind_t;
#define MAVLINK_MSG_OBS_WIND_FIELD_WIND_LEN 3
/**
* @brief Pack a obs_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 wind Wind
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_obs_wind_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const float* wind)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_OBS_WIND;
i += put_array_by_index((const int8_t*)wind, sizeof(float)*3, i, msg->payload); // Wind
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a obs_wind message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param wind Wind
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_obs_wind_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const float* wind)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_OBS_WIND;
i += put_array_by_index((const int8_t*)wind, sizeof(float)*3, i, msg->payload); // Wind
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a obs_wind struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param obs_wind C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_obs_wind_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_obs_wind_t* obs_wind)
{
return mavlink_msg_obs_wind_pack(system_id, component_id, msg, obs_wind->wind);
}
/**
* @brief Send a obs_wind message
* @param chan MAVLink channel to send the message
*
* @param wind Wind
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_obs_wind_send(mavlink_channel_t chan, const float* wind)
{
mavlink_message_t msg;
mavlink_msg_obs_wind_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, wind);
mavlink_send_uart(chan, &msg);
}
#endif
// MESSAGE OBS_WIND UNPACKING
/**
* @brief Get field wind from obs_wind message
*
* @return Wind
*/
static inline uint16_t mavlink_msg_obs_wind_get_wind(const mavlink_message_t* msg, float* r_data)
{
memcpy(r_data, msg->payload, sizeof(float)*3);
return sizeof(float)*3;
}
/**
* @brief Decode a obs_wind message into a struct
*
* @param msg The message to decode
* @param obs_wind C-struct to decode the message contents into
*/
static inline void mavlink_msg_obs_wind_decode(const mavlink_message_t* msg, mavlink_obs_wind_t* obs_wind)
{
mavlink_msg_obs_wind_get_wind(msg, obs_wind->wind);
}
// MESSAGE PM_ELEC PACKING
#define MAVLINK_MSG_ID_PM_ELEC 188
typedef struct __mavlink_pm_elec_t
{
float PwCons; ///< current power consumption
float BatStat; ///< battery status
float PwGen[3]; ///< Power generation from each module
} mavlink_pm_elec_t;
#define MAVLINK_MSG_PM_ELEC_FIELD_PWGEN_LEN 3
/**
* @brief Pack a pm_elec 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 PwCons current power consumption
* @param BatStat battery status
* @param PwGen Power generation from each module
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_pm_elec_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, float PwCons, float BatStat, const float* PwGen)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_PM_ELEC;
i += put_float_by_index(PwCons, i, msg->payload); // current power consumption
i += put_float_by_index(BatStat, i, msg->payload); // battery status
i += put_array_by_index((const int8_t*)PwGen, sizeof(float)*3, i, msg->payload); // Power generation from each module
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a pm_elec message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param PwCons current power consumption
* @param BatStat battery status
* @param PwGen Power generation from each module
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_pm_elec_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, float PwCons, float BatStat, const float* PwGen)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_PM_ELEC;
i += put_float_by_index(PwCons, i, msg->payload); // current power consumption
i += put_float_by_index(BatStat, i, msg->payload); // battery status
i += put_array_by_index((const int8_t*)PwGen, sizeof(float)*3, i, msg->payload); // Power generation from each module
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a pm_elec struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param pm_elec C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_pm_elec_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_pm_elec_t* pm_elec)
{
return mavlink_msg_pm_elec_pack(system_id, component_id, msg, pm_elec->PwCons, pm_elec->BatStat, pm_elec->PwGen);
}
/**
* @brief Send a pm_elec message
* @param chan MAVLink channel to send the message
*
* @param PwCons current power consumption
* @param BatStat battery status
* @param PwGen Power generation from each module
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_pm_elec_send(mavlink_channel_t chan, float PwCons, float BatStat, const float* PwGen)
{
mavlink_message_t msg;
mavlink_msg_pm_elec_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, PwCons, BatStat, PwGen);
mavlink_send_uart(chan, &msg);
}
#endif
// MESSAGE PM_ELEC UNPACKING
/**
* @brief Get field PwCons from pm_elec message
*
* @return current power consumption
*/
static inline float mavlink_msg_pm_elec_get_PwCons(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload)[0];
r.b[2] = (msg->payload)[1];
r.b[1] = (msg->payload)[2];
r.b[0] = (msg->payload)[3];
return (float)r.f;
}
/**
* @brief Get field BatStat from pm_elec message
*
* @return battery status
*/
static inline float mavlink_msg_pm_elec_get_BatStat(const mavlink_message_t* msg)
{
generic_32bit r;
r.b[3] = (msg->payload+sizeof(float))[0];
r.b[2] = (msg->payload+sizeof(float))[1];
r.b[1] = (msg->payload+sizeof(float))[2];
r.b[0] = (msg->payload+sizeof(float))[3];
return (float)r.f;
}
/**
* @brief Get field PwGen from pm_elec message
*
* @return Power generation from each module
*/
static inline uint16_t mavlink_msg_pm_elec_get_PwGen(const mavlink_message_t* msg, float* r_data)
{
memcpy(r_data, msg->payload+sizeof(float)+sizeof(float), sizeof(float)*3);
return sizeof(float)*3;
}
/**
* @brief Decode a pm_elec message into a struct
*
* @param msg The message to decode
* @param pm_elec C-struct to decode the message contents into
*/
static inline void mavlink_msg_pm_elec_decode(const mavlink_message_t* msg, mavlink_pm_elec_t* pm_elec)
{
pm_elec->PwCons = mavlink_msg_pm_elec_get_PwCons(msg);
pm_elec->BatStat = mavlink_msg_pm_elec_get_BatStat(msg);
mavlink_msg_pm_elec_get_PwGen(msg, pm_elec->PwGen);
}
// MESSAGE SENSESOAR_MODE_ACK PACKING
#define MAVLINK_MSG_ID_SENSESOAR_MODE_ACK 167
typedef struct __mavlink_sensesoar_mode_ack_t
{
uint8_t mode; ///< Mode as desribed in the sensesoar_mode
uint8_t ack; ///< 0:ack, 1:nack
} mavlink_sensesoar_mode_ack_t;
/**
* @brief Pack a sensesoar_mode_ack message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param mode Mode as desribed in the sensesoar_mode
* @param ack 0:ack, 1:nack
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_sensesoar_mode_ack_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t mode, uint8_t ack)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_SENSESOAR_MODE_ACK;
i += put_uint8_t_by_index(mode, i, msg->payload); // Mode as desribed in the sensesoar_mode
i += put_uint8_t_by_index(ack, i, msg->payload); // 0:ack, 1:nack
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a sensesoar_mode_ack message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param mode Mode as desribed in the sensesoar_mode
* @param ack 0:ack, 1:nack
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_sensesoar_mode_ack_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t mode, uint8_t ack)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_SENSESOAR_MODE_ACK;
i += put_uint8_t_by_index(mode, i, msg->payload); // Mode as desribed in the sensesoar_mode
i += put_uint8_t_by_index(ack, i, msg->payload); // 0:ack, 1:nack
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a sensesoar_mode_ack struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param sensesoar_mode_ack C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_sensesoar_mode_ack_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_sensesoar_mode_ack_t* sensesoar_mode_ack)
{
return mavlink_msg_sensesoar_mode_ack_pack(system_id, component_id, msg, sensesoar_mode_ack->mode, sensesoar_mode_ack->ack);
}
/**
* @brief Send a sensesoar_mode_ack message
* @param chan MAVLink channel to send the message
*
* @param mode Mode as desribed in the sensesoar_mode
* @param ack 0:ack, 1:nack
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_sensesoar_mode_ack_send(mavlink_channel_t chan, uint8_t mode, uint8_t ack)
{
mavlink_message_t msg;
mavlink_msg_sensesoar_mode_ack_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, mode, ack);
mavlink_send_uart(chan, &msg);
}
#endif
// MESSAGE SENSESOAR_MODE_ACK UNPACKING
/**
* @brief Get field mode from sensesoar_mode_ack message
*
* @return Mode as desribed in the sensesoar_mode
*/
static inline uint8_t mavlink_msg_sensesoar_mode_ack_get_mode(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload)[0];
}
/**
* @brief Get field ack from sensesoar_mode_ack message
*
* @return 0:ack, 1:nack
*/
static inline uint8_t mavlink_msg_sensesoar_mode_ack_get_ack(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload+sizeof(uint8_t))[0];
}
/**
* @brief Decode a sensesoar_mode_ack message into a struct
*
* @param msg The message to decode
* @param sensesoar_mode_ack C-struct to decode the message contents into
*/
static inline void mavlink_msg_sensesoar_mode_ack_decode(const mavlink_message_t* msg, mavlink_sensesoar_mode_ack_t* sensesoar_mode_ack)
{
sensesoar_mode_ack->mode = mavlink_msg_sensesoar_mode_ack_get_mode(msg);
sensesoar_mode_ack->ack = mavlink_msg_sensesoar_mode_ack_get_ack(msg);
}
// MESSAGE SENSESOAR_MODE_CHNG PACKING
#define MAVLINK_MSG_ID_SENSESOAR_MODE_CHNG 166
typedef struct __mavlink_sensesoar_mode_chng_t
{
uint8_t target; ///< Target ID
uint8_t mode; ///< Mode as desribed in the sensesoar_mode
} mavlink_sensesoar_mode_chng_t;
/**
* @brief Pack a sensesoar_mode_chng 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 Target ID
* @param mode Mode as desribed in the sensesoar_mode
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_sensesoar_mode_chng_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target, uint8_t mode)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_SENSESOAR_MODE_CHNG;
i += put_uint8_t_by_index(target, i, msg->payload); // Target ID
i += put_uint8_t_by_index(mode, i, msg->payload); // Mode as desribed in the sensesoar_mode
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a sensesoar_mode_chng message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param target Target ID
* @param mode Mode as desribed in the sensesoar_mode
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_sensesoar_mode_chng_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target, uint8_t mode)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_SENSESOAR_MODE_CHNG;
i += put_uint8_t_by_index(target, i, msg->payload); // Target ID
i += put_uint8_t_by_index(mode, i, msg->payload); // Mode as desribed in the sensesoar_mode
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a sensesoar_mode_chng struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param sensesoar_mode_chng C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_sensesoar_mode_chng_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_sensesoar_mode_chng_t* sensesoar_mode_chng)
{
return mavlink_msg_sensesoar_mode_chng_pack(system_id, component_id, msg, sensesoar_mode_chng->target, sensesoar_mode_chng->mode);
}
/**
* @brief Send a sensesoar_mode_chng message
* @param chan MAVLink channel to send the message
*
* @param target Target ID
* @param mode Mode as desribed in the sensesoar_mode
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_sensesoar_mode_chng_send(mavlink_channel_t chan, uint8_t target, uint8_t mode)
{
mavlink_message_t msg;
mavlink_msg_sensesoar_mode_chng_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target, mode);
mavlink_send_uart(chan, &msg);
}
#endif
// MESSAGE SENSESOAR_MODE_CHNG UNPACKING
/**
* @brief Get field target from sensesoar_mode_chng message
*
* @return Target ID
*/
static inline uint8_t mavlink_msg_sensesoar_mode_chng_get_target(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload)[0];
}
/**
* @brief Get field mode from sensesoar_mode_chng message
*
* @return Mode as desribed in the sensesoar_mode
*/
static inline uint8_t mavlink_msg_sensesoar_mode_chng_get_mode(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload+sizeof(uint8_t))[0];
}
/**
* @brief Decode a sensesoar_mode_chng message into a struct
*
* @param msg The message to decode
* @param sensesoar_mode_chng C-struct to decode the message contents into
*/
static inline void mavlink_msg_sensesoar_mode_chng_decode(const mavlink_message_t* msg, mavlink_sensesoar_mode_chng_t* sensesoar_mode_chng)
{
sensesoar_mode_chng->target = mavlink_msg_sensesoar_mode_chng_get_target(msg);
sensesoar_mode_chng->mode = mavlink_msg_sensesoar_mode_chng_get_mode(msg);
}
// MESSAGE SENSESOAR_MODE_RQST PACKING
#define MAVLINK_MSG_ID_SENSESOAR_MODE_RQST 168
typedef struct __mavlink_sensesoar_mode_rqst_t
{
uint8_t target; ///< Target ID
} mavlink_sensesoar_mode_rqst_t;
/**
* @brief Pack a sensesoar_mode_rqst 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 Target ID
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_sensesoar_mode_rqst_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_SENSESOAR_MODE_RQST;
i += put_uint8_t_by_index(target, i, msg->payload); // Target ID
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a sensesoar_mode_rqst message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param target Target ID
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_sensesoar_mode_rqst_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_SENSESOAR_MODE_RQST;
i += put_uint8_t_by_index(target, i, msg->payload); // Target ID
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a sensesoar_mode_rqst struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param sensesoar_mode_rqst C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_sensesoar_mode_rqst_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_sensesoar_mode_rqst_t* sensesoar_mode_rqst)
{
return mavlink_msg_sensesoar_mode_rqst_pack(system_id, component_id, msg, sensesoar_mode_rqst->target);
}
/**
* @brief Send a sensesoar_mode_rqst message
* @param chan MAVLink channel to send the message
*
* @param target Target ID
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_sensesoar_mode_rqst_send(mavlink_channel_t chan, uint8_t target)
{
mavlink_message_t msg;
mavlink_msg_sensesoar_mode_rqst_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, target);
mavlink_send_uart(chan, &msg);
}
#endif
// MESSAGE SENSESOAR_MODE_RQST UNPACKING
/**
* @brief Get field target from sensesoar_mode_rqst message
*
* @return Target ID
*/
static inline uint8_t mavlink_msg_sensesoar_mode_rqst_get_target(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload)[0];
}
/**
* @brief Decode a sensesoar_mode_rqst message into a struct
*
* @param msg The message to decode
* @param sensesoar_mode_rqst C-struct to decode the message contents into
*/
static inline void mavlink_msg_sensesoar_mode_rqst_decode(const mavlink_message_t* msg, mavlink_sensesoar_mode_rqst_t* sensesoar_mode_rqst)
{
sensesoar_mode_rqst->target = mavlink_msg_sensesoar_mode_rqst_get_target(msg);
}
// MESSAGE SENSESOAR_MODE_RQST_SEND PACKING
#define MAVLINK_MSG_ID_SENSESOAR_MODE_RQST_SEND 169
typedef struct __mavlink_sensesoar_mode_rqst_send_t
{
uint8_t mode; ///< Mode as desribed in the sensesoar_mode
} mavlink_sensesoar_mode_rqst_send_t;
/**
* @brief Pack a sensesoar_mode_rqst_send message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param mode Mode as desribed in the sensesoar_mode
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_sensesoar_mode_rqst_send_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t mode)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_SENSESOAR_MODE_RQST_SEND;
i += put_uint8_t_by_index(mode, i, msg->payload); // Mode as desribed in the sensesoar_mode
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a sensesoar_mode_rqst_send message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param mode Mode as desribed in the sensesoar_mode
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_sensesoar_mode_rqst_send_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t mode)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_SENSESOAR_MODE_RQST_SEND;
i += put_uint8_t_by_index(mode, i, msg->payload); // Mode as desribed in the sensesoar_mode
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a sensesoar_mode_rqst_send struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param sensesoar_mode_rqst_send C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_sensesoar_mode_rqst_send_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_sensesoar_mode_rqst_send_t* sensesoar_mode_rqst_send)
{
return mavlink_msg_sensesoar_mode_rqst_send_pack(system_id, component_id, msg, sensesoar_mode_rqst_send->mode);
}
/**
* @brief Send a sensesoar_mode_rqst_send message
* @param chan MAVLink channel to send the message
*
* @param mode Mode as desribed in the sensesoar_mode
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_sensesoar_mode_rqst_send_send(mavlink_channel_t chan, uint8_t mode)
{
mavlink_message_t msg;
mavlink_msg_sensesoar_mode_rqst_send_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, mode);
mavlink_send_uart(chan, &msg);
}
#endif
// MESSAGE SENSESOAR_MODE_RQST_SEND UNPACKING
/**
* @brief Get field mode from sensesoar_mode_rqst_send message
*
* @return Mode as desribed in the sensesoar_mode
*/
static inline uint8_t mavlink_msg_sensesoar_mode_rqst_send_get_mode(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload)[0];
}
/**
* @brief Decode a sensesoar_mode_rqst_send message into a struct
*
* @param msg The message to decode
* @param sensesoar_mode_rqst_send C-struct to decode the message contents into
*/
static inline void mavlink_msg_sensesoar_mode_rqst_send_decode(const mavlink_message_t* msg, mavlink_sensesoar_mode_rqst_send_t* sensesoar_mode_rqst_send)
{
sensesoar_mode_rqst_send->mode = mavlink_msg_sensesoar_mode_rqst_send_get_mode(msg);
}
// MESSAGE SYS_STAT PACKING
#define MAVLINK_MSG_ID_SYS_STAT 190
typedef struct __mavlink_sys_stat_t
{
uint8_t gps; ///< gps status
uint8_t act; ///< actuator status
uint8_t mod; ///< module status
uint8_t commRssi; ///< module status
} mavlink_sys_stat_t;
/**
* @brief Pack a sys_stat message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param gps gps status
* @param act actuator status
* @param mod module status
* @param commRssi module status
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_sys_stat_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t gps, uint8_t act, uint8_t mod, uint8_t commRssi)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_SYS_STAT;
i += put_uint8_t_by_index(gps, i, msg->payload); // gps status
i += put_uint8_t_by_index(act, i, msg->payload); // actuator status
i += put_uint8_t_by_index(mod, i, msg->payload); // module status
i += put_uint8_t_by_index(commRssi, i, msg->payload); // module status
return mavlink_finalize_message(msg, system_id, component_id, i);
}
/**
* @brief Pack a sys_stat message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param gps gps status
* @param act actuator status
* @param mod module status
* @param commRssi module status
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_sys_stat_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t gps, uint8_t act, uint8_t mod, uint8_t commRssi)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_SYS_STAT;
i += put_uint8_t_by_index(gps, i, msg->payload); // gps status
i += put_uint8_t_by_index(act, i, msg->payload); // actuator status
i += put_uint8_t_by_index(mod, i, msg->payload); // module status
i += put_uint8_t_by_index(commRssi, i, msg->payload); // module status
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
}
/**
* @brief Encode a sys_stat struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param sys_stat C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_sys_stat_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_sys_stat_t* sys_stat)
{
return mavlink_msg_sys_stat_pack(system_id, component_id, msg, sys_stat->gps, sys_stat->act, sys_stat->mod, sys_stat->commRssi);
}
/**
* @brief Send a sys_stat message
* @param chan MAVLink channel to send the message
*
* @param gps gps status
* @param act actuator status
* @param mod module status
* @param commRssi module status
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_sys_stat_send(mavlink_channel_t chan, uint8_t gps, uint8_t act, uint8_t mod, uint8_t commRssi)
{
mavlink_message_t msg;
mavlink_msg_sys_stat_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, gps, act, mod, commRssi);
mavlink_send_uart(chan, &msg);
}
#endif
// MESSAGE SYS_STAT UNPACKING
/**
* @brief Get field gps from sys_stat message
*
* @return gps status
*/
static inline uint8_t mavlink_msg_sys_stat_get_gps(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload)[0];
}
/**
* @brief Get field act from sys_stat message
*
* @return actuator status
*/
static inline uint8_t mavlink_msg_sys_stat_get_act(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload+sizeof(uint8_t))[0];
}
/**
* @brief Get field mod from sys_stat message
*
* @return module status
*/
static inline uint8_t mavlink_msg_sys_stat_get_mod(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t))[0];
}
/**
* @brief Get field commRssi from sys_stat message
*
* @return module status
*/
static inline uint8_t mavlink_msg_sys_stat_get_commRssi(const mavlink_message_t* msg)
{
return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint8_t)+sizeof(uint8_t))[0];
}
/**
* @brief Decode a sys_stat message into a struct
*
* @param msg The message to decode
* @param sys_stat C-struct to decode the message contents into
*/
static inline void mavlink_msg_sys_stat_decode(const mavlink_message_t* msg, mavlink_sys_stat_t* sys_stat)
{
sys_stat->gps = mavlink_msg_sys_stat_get_gps(msg);
sys_stat->act = mavlink_msg_sys_stat_get_act(msg);
sys_stat->mod = mavlink_msg_sys_stat_get_mod(msg);
sys_stat->commRssi = mavlink_msg_sys_stat_get_commRssi(msg);
}
/** @file
* @brief MAVLink comm protocol.
* @see http://qgroundcontrol.org/mavlink/
* Generated on Wednesday, July 27 2011, 14:17 UTC
* Generated on Tuesday, August 2 2011, 15:51 UTC
*/
#ifndef COMMON_H
#define COMMON_H
......
/** @file
* @brief MAVLink comm protocol.
* @see http://pixhawk.ethz.ch/software/mavlink
* Generated on Wednesday, July 27 2011, 14:17 UTC
* Generated on Tuesday, August 2 2011, 15:51 UTC
*/
#ifndef MAVLINK_H
#define MAVLINK_H
......
......@@ -14,6 +14,7 @@ enum MAV_CLASS
MAV_CLASS_GENERIC_MISSION_NAVIGATION_ONLY = 6, ///< Generic autopilot supporting waypoints and other simple navigation commands
MAV_CLASS_GENERIC_MISSION_FULL = 7, ///< Generic autopilot supporting the full mission command set
MAV_CLASS_NONE = 8, ///< No valid autopilot
MAV_CLASS_SENSESOAR = 9, ///< senseSoar autopilot
MAV_CLASS_NB ///< Number of autopilot classes
};
......@@ -128,7 +129,8 @@ enum MAV_AUTOPILOT_TYPE
MAV_AUTOPILOT_PIXHAWK = 1,
MAV_AUTOPILOT_SLUGS = 2,
MAV_AUTOPILOT_ARDUPILOTMEGA = 3,
MAV_AUTOPILOT_NONE = 4
MAV_AUTOPILOT_NONE = 4,
MAV_AUTOPILOT_SENSESOAR = 5
};
enum MAV_COMPONENT
......
<?xml version='1.0'?>
<mavlink>
<include>common.xml</include>
<enums>
<enum name="SENSESOAR_MODE">
<description> Different flight modes </description>
<entry name="SENSESOAR_MODE_GLIDING"> Gliding mode with motors off</entry>
<entry name="SENSESOAR_MODE_AUTONOMOUS"> Autonomous flight</entry>
<entry name="SENSESOAR_MODE_MANUAL"> RC controlled</entry>
</enum>
</enums>
<messages>
<message id="166" name="SENSESOAR_MODE_CHNG">
change flight mode of the sensesoar
<field type="uint8_t" name="target">Target ID</field>
<field type="uint8_t" name="mode">Mode as desribed in the sensesoar_mode</field>
</message>
<message id="167" name="SENSESOAR_MODE_ACK">
accept change of mode
<field type="uint8_t" name="mode">Mode as desribed in the sensesoar_mode</field>
<field type="uint8_t" name="ack">0:ack, 1:nack</field>
</message>
<message id="168" name="SENSESOAR_MODE_RQST">
request for sending current flight mode
<field type="uint8_t" name="target">Target ID</field>
</message>
<message id="169" name="SENSESOAR_MODE_RQST_SEND">
sending current flight mode
<field type="uint8_t" name="mode">Mode as desribed in the sensesoar_mode</field>
</message>
<message id="170" name="OBS_POSITION">
Position estimate of the observer in NED inertial frame
<field type="double[3]" name="pos">Position</field>
</message>
<message id="172" name="OBS_VELOCITY">
velocity estimate of the observer in NED inertial frame
<field type="float[3]" name="vel">Velocity</field>
</message>
<message id="174" name="OBS_ATTITUDE">
attitude estimate of the observer
<field type="float[4]" name="quat">Quaternion re;im</field>
</message>
<message id="176" name="OBS_WIND">
Wind estimate in NED inertial frame
<field type="float[3]" name="wind">Wind</field>
</message>
<message id="178" name="OBS_AIR_VELOCITY">
Estimate of the air velocity
<field type="float" name="magnitude">Air speed</field>
<field type="float" name="aoa">angle of attack</field>
<field type="float" name="slip">slip angle</field>
</message>
<message id="180" name="OBS_BIAS">
IMU biases
<field type="float[3]" name="accBias">accelerometer bias</field>
<field type="float[3]" name="gyroBias">gyroscope bias</field>
</message>
<message id="182" name="OBS_QFF">
estimate of the pressure at sea level
<field type="float" name="qff">Wind</field>
</message>
<message id="183" name="OBS_AIR_TEMP">
ambient air temperature
<field type="float" name="airT">Air Temperatur</field>
</message>
<message id="184" name="FILT_ROT_VEL">
filtered rotational velocity
<field type="float[3]" name="rotVel">rotational velocity</field>
</message>
<message id="186" name="LLC_OUT">
low level control output
<field type="int16_t[4]" name="servoOut">Servo signal</field>
<field type="int16_t[2]" name="MotorOut">motor signal</field>
</message>
<message id="188" name="PM_ELEC">
Power managment
<field type="float" name="PwCons">current power consumption</field>
<field type="float" name="BatStat">battery status</field>
<field type="float[3]" name="PwGen">Power generation from each module</field>
</message>
<message id="190" name="SYS_Stat">
system status
<field type="uint8_t" name="gps">gps status</field>
<field type="uint8_t" name="act">actuator status</field>
<field type="uint8_t" name="mod">module status</field>
<field type="uint8_t" name="commRssi">module status</field>
</message>
<message id="192" name="CMD_AIRSPEED_CHNG">
change commanded air speed
<field type="uint8_t" name="target">Target ID</field>
<field type="float" name="spCmd">commanded airspeed</field>
</message>
<message id="194" name="CMD_AIRSPEED_ACK">
accept change of airspeed
<field type="float" name="spCmd">commanded airspeed</field>
<field type="uint8_t" name="ack">0:ack, 1:nack</field>
</message>
</messages>
</mavlink>
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment