Subversion Repositories Projects

Rev

Details | Last modification | View Log | RSS feed

Rev Author Line No. Line
1702 - 1
// MESSAGE AHRS PACKING
2
 
3
#define MAVLINK_MSG_ID_AHRS 163
4
 
5
typedef struct __mavlink_ahrs_t
6
{
7
 float omegaIx; ///< X gyro drift estimate rad/s
8
 float omegaIy; ///< Y gyro drift estimate rad/s
9
 float omegaIz; ///< Z gyro drift estimate rad/s
10
 float accel_weight; ///< average accel_weight
11
 float renorm_val; ///< average renormalisation value
12
 float error_rp; ///< average error_roll_pitch value
13
 float error_yaw; ///< average error_yaw value
14
} mavlink_ahrs_t;
15
 
16
#define MAVLINK_MSG_ID_AHRS_LEN 28
17
#define MAVLINK_MSG_ID_163_LEN 28
18
 
19
 
20
 
21
#define MAVLINK_MESSAGE_INFO_AHRS { \
22
        "AHRS", \
23
        7, \
24
        {  { "omegaIx", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_ahrs_t, omegaIx) }, \
25
         { "omegaIy", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_ahrs_t, omegaIy) }, \
26
         { "omegaIz", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_ahrs_t, omegaIz) }, \
27
         { "accel_weight", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_ahrs_t, accel_weight) }, \
28
         { "renorm_val", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_ahrs_t, renorm_val) }, \
29
         { "error_rp", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_ahrs_t, error_rp) }, \
30
         { "error_yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_ahrs_t, error_yaw) }, \
31
         } \
32
}
33
 
34
 
35
/**
36
 * @brief Pack a ahrs message
37
 * @param system_id ID of this system
38
 * @param component_id ID of this component (e.g. 200 for IMU)
39
 * @param msg The MAVLink message to compress the data into
40
 *
41
 * @param omegaIx X gyro drift estimate rad/s
42
 * @param omegaIy Y gyro drift estimate rad/s
43
 * @param omegaIz Z gyro drift estimate rad/s
44
 * @param accel_weight average accel_weight
45
 * @param renorm_val average renormalisation value
46
 * @param error_rp average error_roll_pitch value
47
 * @param error_yaw average error_yaw value
48
 * @return length of the message in bytes (excluding serial stream start sign)
49
 */
50
static inline uint16_t mavlink_msg_ahrs_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
51
                                                       float omegaIx, float omegaIy, float omegaIz, float accel_weight, float renorm_val, float error_rp, float error_yaw)
52
{
53
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
54
        char buf[28];
55
        _mav_put_float(buf, 0, omegaIx);
56
        _mav_put_float(buf, 4, omegaIy);
57
        _mav_put_float(buf, 8, omegaIz);
58
        _mav_put_float(buf, 12, accel_weight);
59
        _mav_put_float(buf, 16, renorm_val);
60
        _mav_put_float(buf, 20, error_rp);
61
        _mav_put_float(buf, 24, error_yaw);
62
 
63
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 28);
64
#else
65
        mavlink_ahrs_t packet;
66
        packet.omegaIx = omegaIx;
67
        packet.omegaIy = omegaIy;
68
        packet.omegaIz = omegaIz;
69
        packet.accel_weight = accel_weight;
70
        packet.renorm_val = renorm_val;
71
        packet.error_rp = error_rp;
72
        packet.error_yaw = error_yaw;
73
 
74
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 28);
75
#endif
76
 
77
        msg->msgid = MAVLINK_MSG_ID_AHRS;
78
        return mavlink_finalize_message(msg, system_id, component_id, 28);
79
}
80
 
81
/**
82
 * @brief Pack a ahrs message on a channel
83
 * @param system_id ID of this system
84
 * @param component_id ID of this component (e.g. 200 for IMU)
85
 * @param chan The MAVLink channel this message was sent over
86
 * @param msg The MAVLink message to compress the data into
87
 * @param omegaIx X gyro drift estimate rad/s
88
 * @param omegaIy Y gyro drift estimate rad/s
89
 * @param omegaIz Z gyro drift estimate rad/s
90
 * @param accel_weight average accel_weight
91
 * @param renorm_val average renormalisation value
92
 * @param error_rp average error_roll_pitch value
93
 * @param error_yaw average error_yaw value
94
 * @return length of the message in bytes (excluding serial stream start sign)
95
 */
96
static inline uint16_t mavlink_msg_ahrs_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
97
                                                           mavlink_message_t* msg,
98
                                                           float omegaIx,float omegaIy,float omegaIz,float accel_weight,float renorm_val,float error_rp,float error_yaw)
99
{
100
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
101
        char buf[28];
102
        _mav_put_float(buf, 0, omegaIx);
103
        _mav_put_float(buf, 4, omegaIy);
104
        _mav_put_float(buf, 8, omegaIz);
105
        _mav_put_float(buf, 12, accel_weight);
106
        _mav_put_float(buf, 16, renorm_val);
107
        _mav_put_float(buf, 20, error_rp);
108
        _mav_put_float(buf, 24, error_yaw);
109
 
110
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 28);
111
#else
112
        mavlink_ahrs_t packet;
113
        packet.omegaIx = omegaIx;
114
        packet.omegaIy = omegaIy;
115
        packet.omegaIz = omegaIz;
116
        packet.accel_weight = accel_weight;
117
        packet.renorm_val = renorm_val;
118
        packet.error_rp = error_rp;
119
        packet.error_yaw = error_yaw;
120
 
121
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 28);
122
#endif
123
 
124
        msg->msgid = MAVLINK_MSG_ID_AHRS;
125
        return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 28);
126
}
127
 
128
/**
129
 * @brief Encode a ahrs struct into a message
130
 *
131
 * @param system_id ID of this system
132
 * @param component_id ID of this component (e.g. 200 for IMU)
133
 * @param msg The MAVLink message to compress the data into
134
 * @param ahrs C-struct to read the message contents from
135
 */
136
static inline uint16_t mavlink_msg_ahrs_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_ahrs_t* ahrs)
137
{
138
        return mavlink_msg_ahrs_pack(system_id, component_id, msg, ahrs->omegaIx, ahrs->omegaIy, ahrs->omegaIz, ahrs->accel_weight, ahrs->renorm_val, ahrs->error_rp, ahrs->error_yaw);
139
}
140
 
141
/**
142
 * @brief Send a ahrs message
143
 * @param chan MAVLink channel to send the message
144
 *
145
 * @param omegaIx X gyro drift estimate rad/s
146
 * @param omegaIy Y gyro drift estimate rad/s
147
 * @param omegaIz Z gyro drift estimate rad/s
148
 * @param accel_weight average accel_weight
149
 * @param renorm_val average renormalisation value
150
 * @param error_rp average error_roll_pitch value
151
 * @param error_yaw average error_yaw value
152
 */
153
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
154
 
155
static inline void mavlink_msg_ahrs_send(mavlink_channel_t chan, float omegaIx, float omegaIy, float omegaIz, float accel_weight, float renorm_val, float error_rp, float error_yaw)
156
{
157
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
158
        char buf[28];
159
        _mav_put_float(buf, 0, omegaIx);
160
        _mav_put_float(buf, 4, omegaIy);
161
        _mav_put_float(buf, 8, omegaIz);
162
        _mav_put_float(buf, 12, accel_weight);
163
        _mav_put_float(buf, 16, renorm_val);
164
        _mav_put_float(buf, 20, error_rp);
165
        _mav_put_float(buf, 24, error_yaw);
166
 
167
        _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AHRS, buf, 28);
168
#else
169
        mavlink_ahrs_t packet;
170
        packet.omegaIx = omegaIx;
171
        packet.omegaIy = omegaIy;
172
        packet.omegaIz = omegaIz;
173
        packet.accel_weight = accel_weight;
174
        packet.renorm_val = renorm_val;
175
        packet.error_rp = error_rp;
176
        packet.error_yaw = error_yaw;
177
 
178
        _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AHRS, (const char *)&packet, 28);
179
#endif
180
}
181
 
182
#endif
183
 
184
// MESSAGE AHRS UNPACKING
185
 
186
 
187
/**
188
 * @brief Get field omegaIx from ahrs message
189
 *
190
 * @return X gyro drift estimate rad/s
191
 */
192
static inline float mavlink_msg_ahrs_get_omegaIx(const mavlink_message_t* msg)
193
{
194
        return _MAV_RETURN_float(msg,  0);
195
}
196
 
197
/**
198
 * @brief Get field omegaIy from ahrs message
199
 *
200
 * @return Y gyro drift estimate rad/s
201
 */
202
static inline float mavlink_msg_ahrs_get_omegaIy(const mavlink_message_t* msg)
203
{
204
        return _MAV_RETURN_float(msg,  4);
205
}
206
 
207
/**
208
 * @brief Get field omegaIz from ahrs message
209
 *
210
 * @return Z gyro drift estimate rad/s
211
 */
212
static inline float mavlink_msg_ahrs_get_omegaIz(const mavlink_message_t* msg)
213
{
214
        return _MAV_RETURN_float(msg,  8);
215
}
216
 
217
/**
218
 * @brief Get field accel_weight from ahrs message
219
 *
220
 * @return average accel_weight
221
 */
222
static inline float mavlink_msg_ahrs_get_accel_weight(const mavlink_message_t* msg)
223
{
224
        return _MAV_RETURN_float(msg,  12);
225
}
226
 
227
/**
228
 * @brief Get field renorm_val from ahrs message
229
 *
230
 * @return average renormalisation value
231
 */
232
static inline float mavlink_msg_ahrs_get_renorm_val(const mavlink_message_t* msg)
233
{
234
        return _MAV_RETURN_float(msg,  16);
235
}
236
 
237
/**
238
 * @brief Get field error_rp from ahrs message
239
 *
240
 * @return average error_roll_pitch value
241
 */
242
static inline float mavlink_msg_ahrs_get_error_rp(const mavlink_message_t* msg)
243
{
244
        return _MAV_RETURN_float(msg,  20);
245
}
246
 
247
/**
248
 * @brief Get field error_yaw from ahrs message
249
 *
250
 * @return average error_yaw value
251
 */
252
static inline float mavlink_msg_ahrs_get_error_yaw(const mavlink_message_t* msg)
253
{
254
        return _MAV_RETURN_float(msg,  24);
255
}
256
 
257
/**
258
 * @brief Decode a ahrs message into a struct
259
 *
260
 * @param msg The message to decode
261
 * @param ahrs C-struct to decode the message contents into
262
 */
263
static inline void mavlink_msg_ahrs_decode(const mavlink_message_t* msg, mavlink_ahrs_t* ahrs)
264
{
265
#if MAVLINK_NEED_BYTE_SWAP
266
        ahrs->omegaIx = mavlink_msg_ahrs_get_omegaIx(msg);
267
        ahrs->omegaIy = mavlink_msg_ahrs_get_omegaIy(msg);
268
        ahrs->omegaIz = mavlink_msg_ahrs_get_omegaIz(msg);
269
        ahrs->accel_weight = mavlink_msg_ahrs_get_accel_weight(msg);
270
        ahrs->renorm_val = mavlink_msg_ahrs_get_renorm_val(msg);
271
        ahrs->error_rp = mavlink_msg_ahrs_get_error_rp(msg);
272
        ahrs->error_yaw = mavlink_msg_ahrs_get_error_yaw(msg);
273
#else
274
        memcpy(ahrs, _MAV_PAYLOAD(msg), 28);
275
#endif
276
}