Subversion Repositories Projects

Rev

Details | Last modification | View Log | RSS feed

Rev Author Line No. Line
1702 - 1
// MESSAGE OBS_BIAS PACKING
2
 
3
#define MAVLINK_MSG_ID_OBS_BIAS 180
4
 
5
typedef struct __mavlink_obs_bias_t
6
{
7
 float accBias[3]; ///< accelerometer bias
8
 float gyroBias[3]; ///< gyroscope bias
9
} mavlink_obs_bias_t;
10
 
11
#define MAVLINK_MSG_ID_OBS_BIAS_LEN 24
12
#define MAVLINK_MSG_ID_180_LEN 24
13
 
14
#define MAVLINK_MSG_OBS_BIAS_FIELD_ACCBIAS_LEN 3
15
#define MAVLINK_MSG_OBS_BIAS_FIELD_GYROBIAS_LEN 3
16
 
17
#define MAVLINK_MESSAGE_INFO_OBS_BIAS { \
18
        "OBS_BIAS", \
19
        2, \
20
        {  { "accBias", NULL, MAVLINK_TYPE_FLOAT, 3, 0, offsetof(mavlink_obs_bias_t, accBias) }, \
21
         { "gyroBias", NULL, MAVLINK_TYPE_FLOAT, 3, 12, offsetof(mavlink_obs_bias_t, gyroBias) }, \
22
         } \
23
}
24
 
25
 
26
/**
27
 * @brief Pack a obs_bias message
28
 * @param system_id ID of this system
29
 * @param component_id ID of this component (e.g. 200 for IMU)
30
 * @param msg The MAVLink message to compress the data into
31
 *
32
 * @param accBias accelerometer bias
33
 * @param gyroBias gyroscope bias
34
 * @return length of the message in bytes (excluding serial stream start sign)
35
 */
36
static inline uint16_t mavlink_msg_obs_bias_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
37
                                                       const float *accBias, const float *gyroBias)
38
{
39
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
40
        char buf[24];
41
 
42
        _mav_put_float_array(buf, 0, accBias, 3);
43
        _mav_put_float_array(buf, 12, gyroBias, 3);
44
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 24);
45
#else
46
        mavlink_obs_bias_t packet;
47
 
48
        mav_array_memcpy(packet.accBias, accBias, sizeof(float)*3);
49
        mav_array_memcpy(packet.gyroBias, gyroBias, sizeof(float)*3);
50
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 24);
51
#endif
52
 
53
        msg->msgid = MAVLINK_MSG_ID_OBS_BIAS;
54
        return mavlink_finalize_message(msg, system_id, component_id, 24, 159);
55
}
56
 
57
/**
58
 * @brief Pack a obs_bias message on a channel
59
 * @param system_id ID of this system
60
 * @param component_id ID of this component (e.g. 200 for IMU)
61
 * @param chan The MAVLink channel this message was sent over
62
 * @param msg The MAVLink message to compress the data into
63
 * @param accBias accelerometer bias
64
 * @param gyroBias gyroscope bias
65
 * @return length of the message in bytes (excluding serial stream start sign)
66
 */
67
static inline uint16_t mavlink_msg_obs_bias_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
68
                                                           mavlink_message_t* msg,
69
                                                           const float *accBias,const float *gyroBias)
70
{
71
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
72
        char buf[24];
73
 
74
        _mav_put_float_array(buf, 0, accBias, 3);
75
        _mav_put_float_array(buf, 12, gyroBias, 3);
76
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 24);
77
#else
78
        mavlink_obs_bias_t packet;
79
 
80
        mav_array_memcpy(packet.accBias, accBias, sizeof(float)*3);
81
        mav_array_memcpy(packet.gyroBias, gyroBias, sizeof(float)*3);
82
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 24);
83
#endif
84
 
85
        msg->msgid = MAVLINK_MSG_ID_OBS_BIAS;
86
        return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 24, 159);
87
}
88
 
89
/**
90
 * @brief Encode a obs_bias struct into a message
91
 *
92
 * @param system_id ID of this system
93
 * @param component_id ID of this component (e.g. 200 for IMU)
94
 * @param msg The MAVLink message to compress the data into
95
 * @param obs_bias C-struct to read the message contents from
96
 */
97
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)
98
{
99
        return mavlink_msg_obs_bias_pack(system_id, component_id, msg, obs_bias->accBias, obs_bias->gyroBias);
100
}
101
 
102
/**
103
 * @brief Send a obs_bias message
104
 * @param chan MAVLink channel to send the message
105
 *
106
 * @param accBias accelerometer bias
107
 * @param gyroBias gyroscope bias
108
 */
109
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
110
 
111
static inline void mavlink_msg_obs_bias_send(mavlink_channel_t chan, const float *accBias, const float *gyroBias)
112
{
113
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
114
        char buf[24];
115
 
116
        _mav_put_float_array(buf, 0, accBias, 3);
117
        _mav_put_float_array(buf, 12, gyroBias, 3);
118
        _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_BIAS, buf, 24, 159);
119
#else
120
        mavlink_obs_bias_t packet;
121
 
122
        mav_array_memcpy(packet.accBias, accBias, sizeof(float)*3);
123
        mav_array_memcpy(packet.gyroBias, gyroBias, sizeof(float)*3);
124
        _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_BIAS, (const char *)&packet, 24, 159);
125
#endif
126
}
127
 
128
#endif
129
 
130
// MESSAGE OBS_BIAS UNPACKING
131
 
132
 
133
/**
134
 * @brief Get field accBias from obs_bias message
135
 *
136
 * @return accelerometer bias
137
 */
138
static inline uint16_t mavlink_msg_obs_bias_get_accBias(const mavlink_message_t* msg, float *accBias)
139
{
140
        return _MAV_RETURN_float_array(msg, accBias, 3,  0);
141
}
142
 
143
/**
144
 * @brief Get field gyroBias from obs_bias message
145
 *
146
 * @return gyroscope bias
147
 */
148
static inline uint16_t mavlink_msg_obs_bias_get_gyroBias(const mavlink_message_t* msg, float *gyroBias)
149
{
150
        return _MAV_RETURN_float_array(msg, gyroBias, 3,  12);
151
}
152
 
153
/**
154
 * @brief Decode a obs_bias message into a struct
155
 *
156
 * @param msg The message to decode
157
 * @param obs_bias C-struct to decode the message contents into
158
 */
159
static inline void mavlink_msg_obs_bias_decode(const mavlink_message_t* msg, mavlink_obs_bias_t* obs_bias)
160
{
161
#if MAVLINK_NEED_BYTE_SWAP
162
        mavlink_msg_obs_bias_get_accBias(msg, obs_bias->accBias);
163
        mavlink_msg_obs_bias_get_gyroBias(msg, obs_bias->gyroBias);
164
#else
165
        memcpy(obs_bias, _MAV_PAYLOAD(msg), 24);
166
#endif
167
}