Subversion Repositories Projects

Rev

Details | Last modification | View Log | RSS feed

Rev Author Line No. Line
1702 - 1
// MESSAGE MOUNT_CONFIGURE PACKING
2
 
3
#define MAVLINK_MSG_ID_MOUNT_CONFIGURE 156
4
 
5
typedef struct __mavlink_mount_configure_t
6
{
7
 uint8_t target_system; ///< System ID
8
 uint8_t target_component; ///< Component ID
9
 uint8_t mount_mode; ///< mount operating mode (see MAV_MOUNT_MODE enum)
10
 uint8_t stab_roll; ///< (1 = yes, 0 = no)
11
 uint8_t stab_pitch; ///< (1 = yes, 0 = no)
12
 uint8_t stab_yaw; ///< (1 = yes, 0 = no)
13
} mavlink_mount_configure_t;
14
 
15
#define MAVLINK_MSG_ID_MOUNT_CONFIGURE_LEN 6
16
#define MAVLINK_MSG_ID_156_LEN 6
17
 
18
 
19
 
20
#define MAVLINK_MESSAGE_INFO_MOUNT_CONFIGURE { \
21
        "MOUNT_CONFIGURE", \
22
        6, \
23
        {  { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_mount_configure_t, target_system) }, \
24
         { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_mount_configure_t, target_component) }, \
25
         { "mount_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mount_configure_t, mount_mode) }, \
26
         { "stab_roll", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_mount_configure_t, stab_roll) }, \
27
         { "stab_pitch", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_mount_configure_t, stab_pitch) }, \
28
         { "stab_yaw", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_mount_configure_t, stab_yaw) }, \
29
         } \
30
}
31
 
32
 
33
/**
34
 * @brief Pack a mount_configure 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 target_system System ID
40
 * @param target_component Component ID
41
 * @param mount_mode mount operating mode (see MAV_MOUNT_MODE enum)
42
 * @param stab_roll (1 = yes, 0 = no)
43
 * @param stab_pitch (1 = yes, 0 = no)
44
 * @param stab_yaw (1 = yes, 0 = no)
45
 * @return length of the message in bytes (excluding serial stream start sign)
46
 */
47
static inline uint16_t mavlink_msg_mount_configure_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
48
                                                       uint8_t target_system, uint8_t target_component, uint8_t mount_mode, uint8_t stab_roll, uint8_t stab_pitch, uint8_t stab_yaw)
49
{
50
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
51
        char buf[6];
52
        _mav_put_uint8_t(buf, 0, target_system);
53
        _mav_put_uint8_t(buf, 1, target_component);
54
        _mav_put_uint8_t(buf, 2, mount_mode);
55
        _mav_put_uint8_t(buf, 3, stab_roll);
56
        _mav_put_uint8_t(buf, 4, stab_pitch);
57
        _mav_put_uint8_t(buf, 5, stab_yaw);
58
 
59
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 6);
60
#else
61
        mavlink_mount_configure_t packet;
62
        packet.target_system = target_system;
63
        packet.target_component = target_component;
64
        packet.mount_mode = mount_mode;
65
        packet.stab_roll = stab_roll;
66
        packet.stab_pitch = stab_pitch;
67
        packet.stab_yaw = stab_yaw;
68
 
69
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 6);
70
#endif
71
 
72
        msg->msgid = MAVLINK_MSG_ID_MOUNT_CONFIGURE;
73
        return mavlink_finalize_message(msg, system_id, component_id, 6, 19);
74
}
75
 
76
/**
77
 * @brief Pack a mount_configure 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 target_system System ID
83
 * @param target_component Component ID
84
 * @param mount_mode mount operating mode (see MAV_MOUNT_MODE enum)
85
 * @param stab_roll (1 = yes, 0 = no)
86
 * @param stab_pitch (1 = yes, 0 = no)
87
 * @param stab_yaw (1 = yes, 0 = no)
88
 * @return length of the message in bytes (excluding serial stream start sign)
89
 */
90
static inline uint16_t mavlink_msg_mount_configure_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
91
                                                           mavlink_message_t* msg,
92
                                                           uint8_t target_system,uint8_t target_component,uint8_t mount_mode,uint8_t stab_roll,uint8_t stab_pitch,uint8_t stab_yaw)
93
{
94
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
95
        char buf[6];
96
        _mav_put_uint8_t(buf, 0, target_system);
97
        _mav_put_uint8_t(buf, 1, target_component);
98
        _mav_put_uint8_t(buf, 2, mount_mode);
99
        _mav_put_uint8_t(buf, 3, stab_roll);
100
        _mav_put_uint8_t(buf, 4, stab_pitch);
101
        _mav_put_uint8_t(buf, 5, stab_yaw);
102
 
103
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 6);
104
#else
105
        mavlink_mount_configure_t packet;
106
        packet.target_system = target_system;
107
        packet.target_component = target_component;
108
        packet.mount_mode = mount_mode;
109
        packet.stab_roll = stab_roll;
110
        packet.stab_pitch = stab_pitch;
111
        packet.stab_yaw = stab_yaw;
112
 
113
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 6);
114
#endif
115
 
116
        msg->msgid = MAVLINK_MSG_ID_MOUNT_CONFIGURE;
117
        return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 6, 19);
118
}
119
 
120
/**
121
 * @brief Encode a mount_configure 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 mount_configure C-struct to read the message contents from
127
 */
128
static inline uint16_t mavlink_msg_mount_configure_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mount_configure_t* mount_configure)
129
{
130
        return mavlink_msg_mount_configure_pack(system_id, component_id, msg, mount_configure->target_system, mount_configure->target_component, mount_configure->mount_mode, mount_configure->stab_roll, mount_configure->stab_pitch, mount_configure->stab_yaw);
131
}
132
 
133
/**
134
 * @brief Send a mount_configure message
135
 * @param chan MAVLink channel to send the message
136
 *
137
 * @param target_system System ID
138
 * @param target_component Component ID
139
 * @param mount_mode mount operating mode (see MAV_MOUNT_MODE enum)
140
 * @param stab_roll (1 = yes, 0 = no)
141
 * @param stab_pitch (1 = yes, 0 = no)
142
 * @param stab_yaw (1 = yes, 0 = no)
143
 */
144
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
145
 
146
static inline void mavlink_msg_mount_configure_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t mount_mode, uint8_t stab_roll, uint8_t stab_pitch, uint8_t stab_yaw)
147
{
148
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
149
        char buf[6];
150
        _mav_put_uint8_t(buf, 0, target_system);
151
        _mav_put_uint8_t(buf, 1, target_component);
152
        _mav_put_uint8_t(buf, 2, mount_mode);
153
        _mav_put_uint8_t(buf, 3, stab_roll);
154
        _mav_put_uint8_t(buf, 4, stab_pitch);
155
        _mav_put_uint8_t(buf, 5, stab_yaw);
156
 
157
        _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_CONFIGURE, buf, 6, 19);
158
#else
159
        mavlink_mount_configure_t packet;
160
        packet.target_system = target_system;
161
        packet.target_component = target_component;
162
        packet.mount_mode = mount_mode;
163
        packet.stab_roll = stab_roll;
164
        packet.stab_pitch = stab_pitch;
165
        packet.stab_yaw = stab_yaw;
166
 
167
        _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_CONFIGURE, (const char *)&packet, 6, 19);
168
#endif
169
}
170
 
171
#endif
172
 
173
// MESSAGE MOUNT_CONFIGURE UNPACKING
174
 
175
 
176
/**
177
 * @brief Get field target_system from mount_configure message
178
 *
179
 * @return System ID
180
 */
181
static inline uint8_t mavlink_msg_mount_configure_get_target_system(const mavlink_message_t* msg)
182
{
183
        return _MAV_RETURN_uint8_t(msg,  0);
184
}
185
 
186
/**
187
 * @brief Get field target_component from mount_configure message
188
 *
189
 * @return Component ID
190
 */
191
static inline uint8_t mavlink_msg_mount_configure_get_target_component(const mavlink_message_t* msg)
192
{
193
        return _MAV_RETURN_uint8_t(msg,  1);
194
}
195
 
196
/**
197
 * @brief Get field mount_mode from mount_configure message
198
 *
199
 * @return mount operating mode (see MAV_MOUNT_MODE enum)
200
 */
201
static inline uint8_t mavlink_msg_mount_configure_get_mount_mode(const mavlink_message_t* msg)
202
{
203
        return _MAV_RETURN_uint8_t(msg,  2);
204
}
205
 
206
/**
207
 * @brief Get field stab_roll from mount_configure message
208
 *
209
 * @return (1 = yes, 0 = no)
210
 */
211
static inline uint8_t mavlink_msg_mount_configure_get_stab_roll(const mavlink_message_t* msg)
212
{
213
        return _MAV_RETURN_uint8_t(msg,  3);
214
}
215
 
216
/**
217
 * @brief Get field stab_pitch from mount_configure message
218
 *
219
 * @return (1 = yes, 0 = no)
220
 */
221
static inline uint8_t mavlink_msg_mount_configure_get_stab_pitch(const mavlink_message_t* msg)
222
{
223
        return _MAV_RETURN_uint8_t(msg,  4);
224
}
225
 
226
/**
227
 * @brief Get field stab_yaw from mount_configure message
228
 *
229
 * @return (1 = yes, 0 = no)
230
 */
231
static inline uint8_t mavlink_msg_mount_configure_get_stab_yaw(const mavlink_message_t* msg)
232
{
233
        return _MAV_RETURN_uint8_t(msg,  5);
234
}
235
 
236
/**
237
 * @brief Decode a mount_configure message into a struct
238
 *
239
 * @param msg The message to decode
240
 * @param mount_configure C-struct to decode the message contents into
241
 */
242
static inline void mavlink_msg_mount_configure_decode(const mavlink_message_t* msg, mavlink_mount_configure_t* mount_configure)
243
{
244
#if MAVLINK_NEED_BYTE_SWAP
245
        mount_configure->target_system = mavlink_msg_mount_configure_get_target_system(msg);
246
        mount_configure->target_component = mavlink_msg_mount_configure_get_target_component(msg);
247
        mount_configure->mount_mode = mavlink_msg_mount_configure_get_mount_mode(msg);
248
        mount_configure->stab_roll = mavlink_msg_mount_configure_get_stab_roll(msg);
249
        mount_configure->stab_pitch = mavlink_msg_mount_configure_get_stab_pitch(msg);
250
        mount_configure->stab_yaw = mavlink_msg_mount_configure_get_stab_yaw(msg);
251
#else
252
        memcpy(mount_configure, _MAV_PAYLOAD(msg), 6);
253
#endif
254
}