Subversion Repositories Projects

Rev

Details | Last modification | View Log | RSS feed

Rev Author Line No. Line
1702 - 1
// MESSAGE OPTICAL_FLOW PACKING
2
 
3
#define MAVLINK_MSG_ID_OPTICAL_FLOW 100
4
 
5
typedef struct __mavlink_optical_flow_t
6
{
7
 uint64_t time; ///< Timestamp (UNIX)
8
 uint8_t sensor_id; ///< Sensor ID
9
 int16_t flow_x; ///< Flow in pixels in x-sensor direction
10
 int16_t flow_y; ///< Flow in pixels in y-sensor direction
11
 uint8_t quality; ///< Optical flow quality / confidence. 0: bad, 255: maximum quality
12
 float ground_distance; ///< Ground distance in meters
13
} mavlink_optical_flow_t;
14
 
15
#define MAVLINK_MSG_ID_OPTICAL_FLOW_LEN 18
16
#define MAVLINK_MSG_ID_100_LEN 18
17
 
18
 
19
 
20
#define MAVLINK_MESSAGE_INFO_OPTICAL_FLOW { \
21
        "OPTICAL_FLOW", \
22
        6, \
23
        {  { "time", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_optical_flow_t, time) }, \
24
         { "sensor_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_optical_flow_t, sensor_id) }, \
25
         { "flow_x", NULL, MAVLINK_TYPE_INT16_T, 0, 9, offsetof(mavlink_optical_flow_t, flow_x) }, \
26
         { "flow_y", NULL, MAVLINK_TYPE_INT16_T, 0, 11, offsetof(mavlink_optical_flow_t, flow_y) }, \
27
         { "quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_optical_flow_t, quality) }, \
28
         { "ground_distance", NULL, MAVLINK_TYPE_FLOAT, 0, 14, offsetof(mavlink_optical_flow_t, ground_distance) }, \
29
         } \
30
}
31
 
32
 
33
/**
34
 * @brief Pack a optical_flow message
35
 * @param system_id ID of this system
36
 * @param component_id ID of this component (e.g. 200 for IMU)
37
 * @param msg The MAVLink message to compress the data into
38
 *
39
 * @param time Timestamp (UNIX)
40
 * @param sensor_id Sensor ID
41
 * @param flow_x Flow in pixels in x-sensor direction
42
 * @param flow_y Flow in pixels in y-sensor direction
43
 * @param quality Optical flow quality / confidence. 0: bad, 255: maximum quality
44
 * @param ground_distance Ground distance in meters
45
 * @return length of the message in bytes (excluding serial stream start sign)
46
 */
47
static inline uint16_t mavlink_msg_optical_flow_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
48
                                                       uint64_t time, uint8_t sensor_id, int16_t flow_x, int16_t flow_y, uint8_t quality, float ground_distance)
49
{
50
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
51
        char buf[18];
52
        _mav_put_uint64_t(buf, 0, time);
53
        _mav_put_uint8_t(buf, 8, sensor_id);
54
        _mav_put_int16_t(buf, 9, flow_x);
55
        _mav_put_int16_t(buf, 11, flow_y);
56
        _mav_put_uint8_t(buf, 13, quality);
57
        _mav_put_float(buf, 14, ground_distance);
58
 
59
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 18);
60
#else
61
        mavlink_optical_flow_t packet;
62
        packet.time = time;
63
        packet.sensor_id = sensor_id;
64
        packet.flow_x = flow_x;
65
        packet.flow_y = flow_y;
66
        packet.quality = quality;
67
        packet.ground_distance = ground_distance;
68
 
69
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 18);
70
#endif
71
 
72
        msg->msgid = MAVLINK_MSG_ID_OPTICAL_FLOW;
73
        return mavlink_finalize_message(msg, system_id, component_id, 18);
74
}
75
 
76
/**
77
 * @brief Pack a optical_flow message on a channel
78
 * @param system_id ID of this system
79
 * @param component_id ID of this component (e.g. 200 for IMU)
80
 * @param chan The MAVLink channel this message was sent over
81
 * @param msg The MAVLink message to compress the data into
82
 * @param time Timestamp (UNIX)
83
 * @param sensor_id Sensor ID
84
 * @param flow_x Flow in pixels in x-sensor direction
85
 * @param flow_y Flow in pixels in y-sensor direction
86
 * @param quality Optical flow quality / confidence. 0: bad, 255: maximum quality
87
 * @param ground_distance Ground distance in meters
88
 * @return length of the message in bytes (excluding serial stream start sign)
89
 */
90
static inline uint16_t mavlink_msg_optical_flow_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
91
                                                           mavlink_message_t* msg,
92
                                                           uint64_t time,uint8_t sensor_id,int16_t flow_x,int16_t flow_y,uint8_t quality,float ground_distance)
93
{
94
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
95
        char buf[18];
96
        _mav_put_uint64_t(buf, 0, time);
97
        _mav_put_uint8_t(buf, 8, sensor_id);
98
        _mav_put_int16_t(buf, 9, flow_x);
99
        _mav_put_int16_t(buf, 11, flow_y);
100
        _mav_put_uint8_t(buf, 13, quality);
101
        _mav_put_float(buf, 14, ground_distance);
102
 
103
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 18);
104
#else
105
        mavlink_optical_flow_t packet;
106
        packet.time = time;
107
        packet.sensor_id = sensor_id;
108
        packet.flow_x = flow_x;
109
        packet.flow_y = flow_y;
110
        packet.quality = quality;
111
        packet.ground_distance = ground_distance;
112
 
113
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 18);
114
#endif
115
 
116
        msg->msgid = MAVLINK_MSG_ID_OPTICAL_FLOW;
117
        return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 18);
118
}
119
 
120
/**
121
 * @brief Encode a optical_flow struct into a message
122
 *
123
 * @param system_id ID of this system
124
 * @param component_id ID of this component (e.g. 200 for IMU)
125
 * @param msg The MAVLink message to compress the data into
126
 * @param optical_flow C-struct to read the message contents from
127
 */
128
static inline uint16_t mavlink_msg_optical_flow_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_optical_flow_t* optical_flow)
129
{
130
        return mavlink_msg_optical_flow_pack(system_id, component_id, msg, optical_flow->time, optical_flow->sensor_id, optical_flow->flow_x, optical_flow->flow_y, optical_flow->quality, optical_flow->ground_distance);
131
}
132
 
133
/**
134
 * @brief Send a optical_flow message
135
 * @param chan MAVLink channel to send the message
136
 *
137
 * @param time Timestamp (UNIX)
138
 * @param sensor_id Sensor ID
139
 * @param flow_x Flow in pixels in x-sensor direction
140
 * @param flow_y Flow in pixels in y-sensor direction
141
 * @param quality Optical flow quality / confidence. 0: bad, 255: maximum quality
142
 * @param ground_distance Ground distance in meters
143
 */
144
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
145
 
146
static inline void mavlink_msg_optical_flow_send(mavlink_channel_t chan, uint64_t time, uint8_t sensor_id, int16_t flow_x, int16_t flow_y, uint8_t quality, float ground_distance)
147
{
148
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
149
        char buf[18];
150
        _mav_put_uint64_t(buf, 0, time);
151
        _mav_put_uint8_t(buf, 8, sensor_id);
152
        _mav_put_int16_t(buf, 9, flow_x);
153
        _mav_put_int16_t(buf, 11, flow_y);
154
        _mav_put_uint8_t(buf, 13, quality);
155
        _mav_put_float(buf, 14, ground_distance);
156
 
157
        _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW, buf, 18);
158
#else
159
        mavlink_optical_flow_t packet;
160
        packet.time = time;
161
        packet.sensor_id = sensor_id;
162
        packet.flow_x = flow_x;
163
        packet.flow_y = flow_y;
164
        packet.quality = quality;
165
        packet.ground_distance = ground_distance;
166
 
167
        _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW, (const char *)&packet, 18);
168
#endif
169
}
170
 
171
#endif
172
 
173
// MESSAGE OPTICAL_FLOW UNPACKING
174
 
175
 
176
/**
177
 * @brief Get field time from optical_flow message
178
 *
179
 * @return Timestamp (UNIX)
180
 */
181
static inline uint64_t mavlink_msg_optical_flow_get_time(const mavlink_message_t* msg)
182
{
183
        return _MAV_RETURN_uint64_t(msg,  0);
184
}
185
 
186
/**
187
 * @brief Get field sensor_id from optical_flow message
188
 *
189
 * @return Sensor ID
190
 */
191
static inline uint8_t mavlink_msg_optical_flow_get_sensor_id(const mavlink_message_t* msg)
192
{
193
        return _MAV_RETURN_uint8_t(msg,  8);
194
}
195
 
196
/**
197
 * @brief Get field flow_x from optical_flow message
198
 *
199
 * @return Flow in pixels in x-sensor direction
200
 */
201
static inline int16_t mavlink_msg_optical_flow_get_flow_x(const mavlink_message_t* msg)
202
{
203
        return _MAV_RETURN_int16_t(msg,  9);
204
}
205
 
206
/**
207
 * @brief Get field flow_y from optical_flow message
208
 *
209
 * @return Flow in pixels in y-sensor direction
210
 */
211
static inline int16_t mavlink_msg_optical_flow_get_flow_y(const mavlink_message_t* msg)
212
{
213
        return _MAV_RETURN_int16_t(msg,  11);
214
}
215
 
216
/**
217
 * @brief Get field quality from optical_flow message
218
 *
219
 * @return Optical flow quality / confidence. 0: bad, 255: maximum quality
220
 */
221
static inline uint8_t mavlink_msg_optical_flow_get_quality(const mavlink_message_t* msg)
222
{
223
        return _MAV_RETURN_uint8_t(msg,  13);
224
}
225
 
226
/**
227
 * @brief Get field ground_distance from optical_flow message
228
 *
229
 * @return Ground distance in meters
230
 */
231
static inline float mavlink_msg_optical_flow_get_ground_distance(const mavlink_message_t* msg)
232
{
233
        return _MAV_RETURN_float(msg,  14);
234
}
235
 
236
/**
237
 * @brief Decode a optical_flow message into a struct
238
 *
239
 * @param msg The message to decode
240
 * @param optical_flow C-struct to decode the message contents into
241
 */
242
static inline void mavlink_msg_optical_flow_decode(const mavlink_message_t* msg, mavlink_optical_flow_t* optical_flow)
243
{
244
#if MAVLINK_NEED_BYTE_SWAP
245
        optical_flow->time = mavlink_msg_optical_flow_get_time(msg);
246
        optical_flow->sensor_id = mavlink_msg_optical_flow_get_sensor_id(msg);
247
        optical_flow->flow_x = mavlink_msg_optical_flow_get_flow_x(msg);
248
        optical_flow->flow_y = mavlink_msg_optical_flow_get_flow_y(msg);
249
        optical_flow->quality = mavlink_msg_optical_flow_get_quality(msg);
250
        optical_flow->ground_distance = mavlink_msg_optical_flow_get_ground_distance(msg);
251
#else
252
        memcpy(optical_flow, _MAV_PAYLOAD(msg), 18);
253
#endif
254
}