3 #define MAVLINK_MSG_ID_SENSOR_BIAS 172
15 #define MAVLINK_MSG_ID_SENSOR_BIAS_LEN 24
16 #define MAVLINK_MSG_ID_172_LEN 24
18 #define MAVLINK_MSG_ID_SENSOR_BIAS_CRC 168
19 #define MAVLINK_MSG_ID_172_CRC 168
23 #define MAVLINK_MESSAGE_INFO_SENSOR_BIAS { \
26 { { "axBias", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_sensor_bias_t, axBias) }, \
27 { "ayBias", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_sensor_bias_t, ayBias) }, \
28 { "azBias", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_sensor_bias_t, azBias) }, \
29 { "gxBias", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_sensor_bias_t, gxBias) }, \
30 { "gyBias", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_sensor_bias_t, gyBias) }, \
31 { "gzBias", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_sensor_bias_t, gzBias) }, \
50 static inline uint16_t mavlink_msg_sensor_bias_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
51 float axBias,
float ayBias,
float azBias,
float gxBias,
float gyBias,
float gzBias)
53 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
97 static inline uint16_t mavlink_msg_sensor_bias_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
98 mavlink_message_t* msg,
99 float axBias,
float ayBias,
float azBias,
float gxBias,
float gyBias,
float gzBias)
101 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
124 #if MAVLINK_CRC_EXTRA
139 static inline uint16_t mavlink_msg_sensor_bias_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
const mavlink_sensor_bias_t* sensor_bias)
141 return mavlink_msg_sensor_bias_pack(system_id, component_id, msg, sensor_bias->
axBias, sensor_bias->
ayBias, sensor_bias->
azBias, sensor_bias->
gxBias, sensor_bias->
gyBias, sensor_bias->
gzBias);
153 static inline uint16_t mavlink_msg_sensor_bias_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg,
const mavlink_sensor_bias_t* sensor_bias)
155 return mavlink_msg_sensor_bias_pack_chan(system_id, component_id, chan, msg, sensor_bias->
axBias, sensor_bias->
ayBias, sensor_bias->
azBias, sensor_bias->
gxBias, sensor_bias->
gyBias, sensor_bias->
gzBias);
169 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
171 static inline void mavlink_msg_sensor_bias_send(
mavlink_channel_t chan,
float axBias,
float ayBias,
float azBias,
float gxBias,
float gyBias,
float gzBias)
173 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
182 #if MAVLINK_CRC_EXTRA
196 #if MAVLINK_CRC_EXTRA
204 #if MAVLINK_MSG_ID_SENSOR_BIAS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
212 static inline void mavlink_msg_sensor_bias_send_buf(mavlink_message_t *msgbuf,
mavlink_channel_t chan,
float axBias,
float ayBias,
float azBias,
float gxBias,
float gyBias,
float gzBias)
214 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
215 char *buf = (
char *)msgbuf;
223 #if MAVLINK_CRC_EXTRA
237 #if MAVLINK_CRC_EXTRA
256 static inline float mavlink_msg_sensor_bias_get_axBias(
const mavlink_message_t* msg)
258 return _MAV_RETURN_float(msg, 0);
266 static inline float mavlink_msg_sensor_bias_get_ayBias(
const mavlink_message_t* msg)
268 return _MAV_RETURN_float(msg, 4);
276 static inline float mavlink_msg_sensor_bias_get_azBias(
const mavlink_message_t* msg)
278 return _MAV_RETURN_float(msg, 8);
286 static inline float mavlink_msg_sensor_bias_get_gxBias(
const mavlink_message_t* msg)
288 return _MAV_RETURN_float(msg, 12);
296 static inline float mavlink_msg_sensor_bias_get_gyBias(
const mavlink_message_t* msg)
298 return _MAV_RETURN_float(msg, 16);
306 static inline float mavlink_msg_sensor_bias_get_gzBias(
const mavlink_message_t* msg)
308 return _MAV_RETURN_float(msg, 20);
317 static inline void mavlink_msg_sensor_bias_decode(
const mavlink_message_t* msg,
mavlink_sensor_bias_t* sensor_bias)
319 #if MAVLINK_NEED_BYTE_SWAP
320 sensor_bias->
axBias = mavlink_msg_sensor_bias_get_axBias(msg);
321 sensor_bias->
ayBias = mavlink_msg_sensor_bias_get_ayBias(msg);
322 sensor_bias->
azBias = mavlink_msg_sensor_bias_get_azBias(msg);
323 sensor_bias->
gxBias = mavlink_msg_sensor_bias_get_gxBias(msg);
324 sensor_bias->
gyBias = mavlink_msg_sensor_bias_get_gyBias(msg);
325 sensor_bias->
gzBias = mavlink_msg_sensor_bias_get_gzBias(msg);
float ayBias
Accelerometer Y bias (m/s)
Definition: mavlink_msg_sensor_bias.h:8
#define _mav_put_float(buf, wire_offset, b)
Definition: protocol.h:145
float axBias
Accelerometer X bias (m/s)
Definition: mavlink_msg_sensor_bias.h:7
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
#define _MAV_PAYLOAD_NON_CONST(msg)
Definition: mavlink_types.h:172
Definition: mavlink_msg_sensor_bias.h:5
mavlink_channel_t
Definition: mavlink_types.h:178
#define MAVLINK_MSG_ID_SENSOR_BIAS_CRC
Definition: mavlink_msg_sensor_bias.h:18
#define _MAV_PAYLOAD(msg)
Definition: mavlink_types.h:171
float azBias
Accelerometer Z bias (m/s)
Definition: mavlink_msg_sensor_bias.h:9
float gxBias
Gyro X bias (rad/s)
Definition: mavlink_msg_sensor_bias.h:10
float gyBias
Gyro Y bias (rad/s)
Definition: mavlink_msg_sensor_bias.h:11
float gzBias
Gyro Z bias (rad/s)
Definition: mavlink_msg_sensor_bias.h:12
#define MAVLINK_MSG_ID_SENSOR_BIAS
Definition: mavlink_msg_sensor_bias.h:3
#define MAVLINK_MSG_ID_SENSOR_BIAS_LEN
Definition: mavlink_msg_sensor_bias.h:15
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
struct __mavlink_sensor_bias_t mavlink_sensor_bias_t