Subversion Repositories Projects

Rev

Details | Last modification | View Log | RSS feed

Rev Author Line No. Line
1702 - 1
// MESSAGE DEBUG_VECT PACKING
2
 
3
#define MAVLINK_MSG_ID_DEBUG_VECT 251
4
 
5
typedef struct __mavlink_debug_vect_t
6
{
7
 char name[10]; ///< Name
8
 uint64_t usec; ///< Timestamp
9
 float x; ///< x
10
 float y; ///< y
11
 float z; ///< z
12
} mavlink_debug_vect_t;
13
 
14
#define MAVLINK_MSG_ID_DEBUG_VECT_LEN 30
15
#define MAVLINK_MSG_ID_251_LEN 30
16
 
17
#define MAVLINK_MSG_DEBUG_VECT_FIELD_NAME_LEN 10
18
 
19
#define MAVLINK_MESSAGE_INFO_DEBUG_VECT { \
20
        "DEBUG_VECT", \
21
        5, \
22
        {  { "name", NULL, MAVLINK_TYPE_CHAR, 10, 0, offsetof(mavlink_debug_vect_t, name) }, \
23
         { "usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 10, offsetof(mavlink_debug_vect_t, usec) }, \
24
         { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 18, offsetof(mavlink_debug_vect_t, x) }, \
25
         { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 22, offsetof(mavlink_debug_vect_t, y) }, \
26
         { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 26, offsetof(mavlink_debug_vect_t, z) }, \
27
         } \
28
}
29
 
30
 
31
/**
32
 * @brief Pack a debug_vect message
33
 * @param system_id ID of this system
34
 * @param component_id ID of this component (e.g. 200 for IMU)
35
 * @param msg The MAVLink message to compress the data into
36
 *
37
 * @param name Name
38
 * @param usec Timestamp
39
 * @param x x
40
 * @param y y
41
 * @param z z
42
 * @return length of the message in bytes (excluding serial stream start sign)
43
 */
44
static inline uint16_t mavlink_msg_debug_vect_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
45
                                                       const char *name, uint64_t usec, float x, float y, float z)
46
{
47
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
48
        char buf[30];
49
        _mav_put_uint64_t(buf, 10, usec);
50
        _mav_put_float(buf, 18, x);
51
        _mav_put_float(buf, 22, y);
52
        _mav_put_float(buf, 26, z);
53
        _mav_put_char_array(buf, 0, name, 10);
54
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 30);
55
#else
56
        mavlink_debug_vect_t packet;
57
        packet.usec = usec;
58
        packet.x = x;
59
        packet.y = y;
60
        packet.z = z;
61
        mav_array_memcpy(packet.name, name, sizeof(char)*10);
62
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 30);
63
#endif
64
 
65
        msg->msgid = MAVLINK_MSG_ID_DEBUG_VECT;
66
        return mavlink_finalize_message(msg, system_id, component_id, 30);
67
}
68
 
69
/**
70
 * @brief Pack a debug_vect message on a channel
71
 * @param system_id ID of this system
72
 * @param component_id ID of this component (e.g. 200 for IMU)
73
 * @param chan The MAVLink channel this message was sent over
74
 * @param msg The MAVLink message to compress the data into
75
 * @param name Name
76
 * @param usec Timestamp
77
 * @param x x
78
 * @param y y
79
 * @param z z
80
 * @return length of the message in bytes (excluding serial stream start sign)
81
 */
82
static inline uint16_t mavlink_msg_debug_vect_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
83
                                                           mavlink_message_t* msg,
84
                                                           const char *name,uint64_t usec,float x,float y,float z)
85
{
86
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
87
        char buf[30];
88
        _mav_put_uint64_t(buf, 10, usec);
89
        _mav_put_float(buf, 18, x);
90
        _mav_put_float(buf, 22, y);
91
        _mav_put_float(buf, 26, z);
92
        _mav_put_char_array(buf, 0, name, 10);
93
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 30);
94
#else
95
        mavlink_debug_vect_t packet;
96
        packet.usec = usec;
97
        packet.x = x;
98
        packet.y = y;
99
        packet.z = z;
100
        mav_array_memcpy(packet.name, name, sizeof(char)*10);
101
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 30);
102
#endif
103
 
104
        msg->msgid = MAVLINK_MSG_ID_DEBUG_VECT;
105
        return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 30);
106
}
107
 
108
/**
109
 * @brief Encode a debug_vect struct into a message
110
 *
111
 * @param system_id ID of this system
112
 * @param component_id ID of this component (e.g. 200 for IMU)
113
 * @param msg The MAVLink message to compress the data into
114
 * @param debug_vect C-struct to read the message contents from
115
 */
116
static inline uint16_t mavlink_msg_debug_vect_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_debug_vect_t* debug_vect)
117
{
118
        return mavlink_msg_debug_vect_pack(system_id, component_id, msg, debug_vect->name, debug_vect->usec, debug_vect->x, debug_vect->y, debug_vect->z);
119
}
120
 
121
/**
122
 * @brief Send a debug_vect message
123
 * @param chan MAVLink channel to send the message
124
 *
125
 * @param name Name
126
 * @param usec Timestamp
127
 * @param x x
128
 * @param y y
129
 * @param z z
130
 */
131
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
132
 
133
static inline void mavlink_msg_debug_vect_send(mavlink_channel_t chan, const char *name, uint64_t usec, float x, float y, float z)
134
{
135
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
136
        char buf[30];
137
        _mav_put_uint64_t(buf, 10, usec);
138
        _mav_put_float(buf, 18, x);
139
        _mav_put_float(buf, 22, y);
140
        _mav_put_float(buf, 26, z);
141
        _mav_put_char_array(buf, 0, name, 10);
142
        _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_VECT, buf, 30);
143
#else
144
        mavlink_debug_vect_t packet;
145
        packet.usec = usec;
146
        packet.x = x;
147
        packet.y = y;
148
        packet.z = z;
149
        mav_array_memcpy(packet.name, name, sizeof(char)*10);
150
        _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_VECT, (const char *)&packet, 30);
151
#endif
152
}
153
 
154
#endif
155
 
156
// MESSAGE DEBUG_VECT UNPACKING
157
 
158
 
159
/**
160
 * @brief Get field name from debug_vect message
161
 *
162
 * @return Name
163
 */
164
static inline uint16_t mavlink_msg_debug_vect_get_name(const mavlink_message_t* msg, char *name)
165
{
166
        return _MAV_RETURN_char_array(msg, name, 10,  0);
167
}
168
 
169
/**
170
 * @brief Get field usec from debug_vect message
171
 *
172
 * @return Timestamp
173
 */
174
static inline uint64_t mavlink_msg_debug_vect_get_usec(const mavlink_message_t* msg)
175
{
176
        return _MAV_RETURN_uint64_t(msg,  10);
177
}
178
 
179
/**
180
 * @brief Get field x from debug_vect message
181
 *
182
 * @return x
183
 */
184
static inline float mavlink_msg_debug_vect_get_x(const mavlink_message_t* msg)
185
{
186
        return _MAV_RETURN_float(msg,  18);
187
}
188
 
189
/**
190
 * @brief Get field y from debug_vect message
191
 *
192
 * @return y
193
 */
194
static inline float mavlink_msg_debug_vect_get_y(const mavlink_message_t* msg)
195
{
196
        return _MAV_RETURN_float(msg,  22);
197
}
198
 
199
/**
200
 * @brief Get field z from debug_vect message
201
 *
202
 * @return z
203
 */
204
static inline float mavlink_msg_debug_vect_get_z(const mavlink_message_t* msg)
205
{
206
        return _MAV_RETURN_float(msg,  26);
207
}
208
 
209
/**
210
 * @brief Decode a debug_vect message into a struct
211
 *
212
 * @param msg The message to decode
213
 * @param debug_vect C-struct to decode the message contents into
214
 */
215
static inline void mavlink_msg_debug_vect_decode(const mavlink_message_t* msg, mavlink_debug_vect_t* debug_vect)
216
{
217
#if MAVLINK_NEED_BYTE_SWAP
218
        mavlink_msg_debug_vect_get_name(msg, debug_vect->name);
219
        debug_vect->usec = mavlink_msg_debug_vect_get_usec(msg);
220
        debug_vect->x = mavlink_msg_debug_vect_get_x(msg);
221
        debug_vect->y = mavlink_msg_debug_vect_get_y(msg);
222
        debug_vect->z = mavlink_msg_debug_vect_get_z(msg);
223
#else
224
        memcpy(debug_vect, _MAV_PAYLOAD(msg), 30);
225
#endif
226
}