3 #define MAVLINK_MSG_ID_SENS_ATMOS 208
11 #define MAVLINK_MSG_ID_SENS_ATMOS_LEN 8
12 #define MAVLINK_MSG_ID_208_LEN 8
14 #define MAVLINK_MSG_ID_SENS_ATMOS_CRC 175
15 #define MAVLINK_MSG_ID_208_CRC 175
19 #define MAVLINK_MESSAGE_INFO_SENS_ATMOS { \
22 { { "TempAmbient", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_sens_atmos_t, TempAmbient) }, \
23 { "Humidity", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_sens_atmos_t, Humidity) }, \
38 static inline uint16_t mavlink_msg_sens_atmos_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
39 float TempAmbient,
float Humidity)
41 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
73 static inline uint16_t mavlink_msg_sens_atmos_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
74 mavlink_message_t* msg,
75 float TempAmbient,
float Humidity)
77 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
107 static inline uint16_t mavlink_msg_sens_atmos_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
const mavlink_sens_atmos_t* sens_atmos)
109 return mavlink_msg_sens_atmos_pack(system_id, component_id, msg, sens_atmos->
TempAmbient, sens_atmos->
Humidity);
121 static inline uint16_t mavlink_msg_sens_atmos_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg,
const mavlink_sens_atmos_t* sens_atmos)
123 return mavlink_msg_sens_atmos_pack_chan(system_id, component_id, chan, msg, sens_atmos->
TempAmbient, sens_atmos->
Humidity);
133 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
135 static inline void mavlink_msg_sens_atmos_send(
mavlink_channel_t chan,
float TempAmbient,
float Humidity)
137 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
142 #if MAVLINK_CRC_EXTRA
152 #if MAVLINK_CRC_EXTRA
160 #if MAVLINK_MSG_ID_SENS_ATMOS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
168 static inline void mavlink_msg_sens_atmos_send_buf(mavlink_message_t *msgbuf,
mavlink_channel_t chan,
float TempAmbient,
float Humidity)
170 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
171 char *buf = (
char *)msgbuf;
175 #if MAVLINK_CRC_EXTRA
185 #if MAVLINK_CRC_EXTRA
204 static inline float mavlink_msg_sens_atmos_get_TempAmbient(
const mavlink_message_t* msg)
206 return _MAV_RETURN_float(msg, 0);
214 static inline float mavlink_msg_sens_atmos_get_Humidity(
const mavlink_message_t* msg)
216 return _MAV_RETURN_float(msg, 4);
225 static inline void mavlink_msg_sens_atmos_decode(
const mavlink_message_t* msg,
mavlink_sens_atmos_t* sens_atmos)
227 #if MAVLINK_NEED_BYTE_SWAP
228 sens_atmos->
TempAmbient = mavlink_msg_sens_atmos_get_TempAmbient(msg);
229 sens_atmos->
Humidity = mavlink_msg_sens_atmos_get_Humidity(msg);
#define _mav_put_float(buf, wire_offset, b)
Definition: protocol.h:145
#define MAVLINK_MSG_ID_SENS_ATMOS_LEN
Definition: mavlink_msg_sens_atmos.h:11
#define MAVLINK_MSG_ID_SENS_ATMOS
Definition: mavlink_msg_sens_atmos.h:3
Definition: mavlink_msg_sens_atmos.h:5
MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t *msg, uint8_t system_id, uint8_t component_id, uint8_t length)
Finalize a MAVLink message with MAVLINK_COMM_0 as default channel.
Definition: mavlink_helpers.h:105
float Humidity
Relative humidity [%].
Definition: mavlink_msg_sens_atmos.h:8
#define _MAV_PAYLOAD_NON_CONST(msg)
Definition: mavlink_types.h:172
float TempAmbient
Ambient temperature [degrees Celsius].
Definition: mavlink_msg_sens_atmos.h:7
mavlink_channel_t
Definition: mavlink_types.h:178
struct __mavlink_sens_atmos_t mavlink_sens_atmos_t
#define _MAV_PAYLOAD(msg)
Definition: mavlink_types.h:171
MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t *msg, uint8_t system_id, uint8_t component_id, uint8_t chan, uint8_t length)
Finalize a MAVLink message with channel assignment.
Definition: mavlink_helpers.h:71
#define MAVLINK_MSG_ID_SENS_ATMOS_CRC
Definition: mavlink_msg_sens_atmos.h:14