mavlink_msg_sensor_bias.h 7.91 KB
Newer Older
James Goppert's avatar
James Goppert committed
1 2 3 4
// MESSAGE SENSOR_BIAS PACKING

#define MAVLINK_MSG_ID_SENSOR_BIAS 172

lm's avatar
lm committed
5
typedef struct __mavlink_sensor_bias_t
James Goppert's avatar
James Goppert committed
6
{
lm's avatar
lm committed
7 8 9 10 11 12
 float axBias; ///< Accelerometer X bias (m/s)
 float ayBias; ///< Accelerometer Y bias (m/s)
 float azBias; ///< Accelerometer Z bias (m/s)
 float gxBias; ///< Gyro X bias (rad/s)
 float gyBias; ///< Gyro Y bias (rad/s)
 float gzBias; ///< Gyro Z bias (rad/s)
James Goppert's avatar
James Goppert committed
13 14
} mavlink_sensor_bias_t;

lm's avatar
lm committed
15 16 17 18 19 20 21 22
#define MAVLINK_MSG_ID_SENSOR_BIAS_LEN 24
#define MAVLINK_MSG_ID_172_LEN 24



#define MAVLINK_MESSAGE_INFO_SENSOR_BIAS { \
	"SENSOR_BIAS", \
	6, \
lm's avatar
lm committed
23 24 25 26 27 28
	{  { "axBias", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_sensor_bias_t, axBias) }, \
         { "ayBias", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_sensor_bias_t, ayBias) }, \
         { "azBias", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_sensor_bias_t, azBias) }, \
         { "gxBias", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_sensor_bias_t, gxBias) }, \
         { "gyBias", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_sensor_bias_t, gyBias) }, \
         { "gzBias", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_sensor_bias_t, gzBias) }, \
lm's avatar
lm committed
29 30 31 32
         } \
}


James Goppert's avatar
James Goppert committed
33
/**
James Goppert's avatar
James Goppert committed
34 35 36 37
 * @brief Pack a sensor_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
James Goppert's avatar
James Goppert committed
38 39 40 41 42 43 44 45 46
 *
 * @param axBias Accelerometer X bias (m/s)
 * @param ayBias Accelerometer Y bias (m/s)
 * @param azBias Accelerometer Z bias (m/s)
 * @param gxBias Gyro X bias (rad/s)
 * @param gyBias Gyro Y bias (rad/s)
 * @param gzBias Gyro Z bias (rad/s)
 * @return length of the message in bytes (excluding serial stream start sign)
 */
lm's avatar
lm committed
47 48
static inline uint16_t mavlink_msg_sensor_bias_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
						       float axBias, float ayBias, float azBias, float gxBias, float gyBias, float gzBias)
James Goppert's avatar
James Goppert committed
49
{
LM's avatar
LM committed
50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
	char buf[24];
	_mav_put_float(buf, 0, axBias);
	_mav_put_float(buf, 4, ayBias);
	_mav_put_float(buf, 8, azBias);
	_mav_put_float(buf, 12, gxBias);
	_mav_put_float(buf, 16, gyBias);
	_mav_put_float(buf, 20, gzBias);

        memcpy(_MAV_PAYLOAD(msg), buf, 24);
#else
	mavlink_sensor_bias_t packet;
	packet.axBias = axBias;
	packet.ayBias = ayBias;
	packet.azBias = azBias;
	packet.gxBias = gxBias;
	packet.gyBias = gyBias;
	packet.gzBias = gzBias;

        memcpy(_MAV_PAYLOAD(msg), &packet, 24);
#endif
James Goppert's avatar
James Goppert committed
71

LM's avatar
LM committed
72
	msg->msgid = MAVLINK_MSG_ID_SENSOR_BIAS;
lm's avatar
lm committed
73
	return mavlink_finalize_message(msg, system_id, component_id, 24, 168);
James Goppert's avatar
James Goppert committed
74 75
}

James Goppert's avatar
James Goppert committed
76
/**
lm's avatar
lm committed
77
 * @brief Pack a sensor_bias message on a channel
James Goppert's avatar
James Goppert committed
78 79 80 81 82 83 84 85 86 87 88 89
 * @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 axBias Accelerometer X bias (m/s)
 * @param ayBias Accelerometer Y bias (m/s)
 * @param azBias Accelerometer Z bias (m/s)
 * @param gxBias Gyro X bias (rad/s)
 * @param gyBias Gyro Y bias (rad/s)
 * @param gzBias Gyro Z bias (rad/s)
 * @return length of the message in bytes (excluding serial stream start sign)
 */
lm's avatar
lm committed
90 91 92 93
static inline uint16_t mavlink_msg_sensor_bias_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
							   mavlink_message_t* msg,
						           float axBias,float ayBias,float azBias,float gxBias,float gyBias,float gzBias)
{
LM's avatar
LM committed
94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
	char buf[24];
	_mav_put_float(buf, 0, axBias);
	_mav_put_float(buf, 4, ayBias);
	_mav_put_float(buf, 8, azBias);
	_mav_put_float(buf, 12, gxBias);
	_mav_put_float(buf, 16, gyBias);
	_mav_put_float(buf, 20, gzBias);

        memcpy(_MAV_PAYLOAD(msg), buf, 24);
#else
	mavlink_sensor_bias_t packet;
	packet.axBias = axBias;
	packet.ayBias = ayBias;
	packet.azBias = azBias;
	packet.gxBias = gxBias;
	packet.gyBias = gyBias;
	packet.gzBias = gzBias;

        memcpy(_MAV_PAYLOAD(msg), &packet, 24);
#endif
lm's avatar
lm committed
115

LM's avatar
LM committed
116
	msg->msgid = MAVLINK_MSG_ID_SENSOR_BIAS;
lm's avatar
lm committed
117 118 119
	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 24, 168);
}

James Goppert's avatar
James Goppert committed
120 121 122 123 124 125 126 127
/**
 * @brief Encode a sensor_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 sensor_bias C-struct to read the message contents from
 */
James Goppert's avatar
James Goppert committed
128 129 130 131 132
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)
{
	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);
}

James Goppert's avatar
James Goppert committed
133 134 135 136 137 138 139 140 141 142 143
/**
 * @brief Send a sensor_bias message
 * @param chan MAVLink channel to send the message
 *
 * @param axBias Accelerometer X bias (m/s)
 * @param ayBias Accelerometer Y bias (m/s)
 * @param azBias Accelerometer Z bias (m/s)
 * @param gxBias Gyro X bias (rad/s)
 * @param gyBias Gyro Y bias (rad/s)
 * @param gzBias Gyro Z bias (rad/s)
 */
lm's avatar
lm committed
144 145
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS

lm's avatar
lm committed
146 147
static inline void mavlink_msg_sensor_bias_send(mavlink_channel_t chan, float axBias, float ayBias, float azBias, float gxBias, float gyBias, float gzBias)
{
LM's avatar
LM committed
148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 163 164 165 166 167 168
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
	char buf[24];
	_mav_put_float(buf, 0, axBias);
	_mav_put_float(buf, 4, ayBias);
	_mav_put_float(buf, 8, azBias);
	_mav_put_float(buf, 12, gxBias);
	_mav_put_float(buf, 16, gyBias);
	_mav_put_float(buf, 20, gzBias);

	_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENSOR_BIAS, buf, 24, 168);
#else
	mavlink_sensor_bias_t packet;
	packet.axBias = axBias;
	packet.ayBias = ayBias;
	packet.azBias = azBias;
	packet.gxBias = gxBias;
	packet.gyBias = gyBias;
	packet.gzBias = gzBias;

	_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENSOR_BIAS, (const char *)&packet, 24, 168);
#endif
James Goppert's avatar
James Goppert committed
169 170 171
}

#endif
lm's avatar
lm committed
172

James Goppert's avatar
James Goppert committed
173 174
// MESSAGE SENSOR_BIAS UNPACKING

lm's avatar
lm committed
175

James Goppert's avatar
James Goppert committed
176 177 178 179 180 181 182
/**
 * @brief Get field axBias from sensor_bias message
 *
 * @return Accelerometer X bias (m/s)
 */
static inline float mavlink_msg_sensor_bias_get_axBias(const mavlink_message_t* msg)
{
LM's avatar
LM committed
183
	return _MAV_RETURN_float(msg,  0);
James Goppert's avatar
James Goppert committed
184 185 186 187 188 189 190 191 192
}

/**
 * @brief Get field ayBias from sensor_bias message
 *
 * @return Accelerometer Y bias (m/s)
 */
static inline float mavlink_msg_sensor_bias_get_ayBias(const mavlink_message_t* msg)
{
LM's avatar
LM committed
193
	return _MAV_RETURN_float(msg,  4);
James Goppert's avatar
James Goppert committed
194 195 196 197 198 199 200 201 202
}

/**
 * @brief Get field azBias from sensor_bias message
 *
 * @return Accelerometer Z bias (m/s)
 */
static inline float mavlink_msg_sensor_bias_get_azBias(const mavlink_message_t* msg)
{
LM's avatar
LM committed
203
	return _MAV_RETURN_float(msg,  8);
James Goppert's avatar
James Goppert committed
204 205 206 207 208 209 210 211 212
}

/**
 * @brief Get field gxBias from sensor_bias message
 *
 * @return Gyro X bias (rad/s)
 */
static inline float mavlink_msg_sensor_bias_get_gxBias(const mavlink_message_t* msg)
{
LM's avatar
LM committed
213
	return _MAV_RETURN_float(msg,  12);
James Goppert's avatar
James Goppert committed
214 215 216 217 218 219 220 221 222
}

/**
 * @brief Get field gyBias from sensor_bias message
 *
 * @return Gyro Y bias (rad/s)
 */
static inline float mavlink_msg_sensor_bias_get_gyBias(const mavlink_message_t* msg)
{
LM's avatar
LM committed
223
	return _MAV_RETURN_float(msg,  16);
James Goppert's avatar
James Goppert committed
224 225 226 227 228 229 230 231 232
}

/**
 * @brief Get field gzBias from sensor_bias message
 *
 * @return Gyro Z bias (rad/s)
 */
static inline float mavlink_msg_sensor_bias_get_gzBias(const mavlink_message_t* msg)
{
LM's avatar
LM committed
233
	return _MAV_RETURN_float(msg,  20);
James Goppert's avatar
James Goppert committed
234 235
}

James Goppert's avatar
James Goppert committed
236 237 238 239 240 241
/**
 * @brief Decode a sensor_bias message into a struct
 *
 * @param msg The message to decode
 * @param sensor_bias C-struct to decode the message contents into
 */
James Goppert's avatar
James Goppert committed
242 243
static inline void mavlink_msg_sensor_bias_decode(const mavlink_message_t* msg, mavlink_sensor_bias_t* sensor_bias)
{
lm's avatar
lm committed
244 245 246 247 248 249 250 251
#if MAVLINK_NEED_BYTE_SWAP
	sensor_bias->axBias = mavlink_msg_sensor_bias_get_axBias(msg);
	sensor_bias->ayBias = mavlink_msg_sensor_bias_get_ayBias(msg);
	sensor_bias->azBias = mavlink_msg_sensor_bias_get_azBias(msg);
	sensor_bias->gxBias = mavlink_msg_sensor_bias_get_gxBias(msg);
	sensor_bias->gyBias = mavlink_msg_sensor_bias_get_gyBias(msg);
	sensor_bias->gzBias = mavlink_msg_sensor_bias_get_gzBias(msg);
#else
LM's avatar
LM committed
252
	memcpy(sensor_bias, _MAV_PAYLOAD(msg), 24);
lm's avatar
lm committed
253
#endif
James Goppert's avatar
James Goppert committed
254
}