Subversion Repositories Projects

Rev

Details | Last modification | View Log | RSS feed

Rev Author Line No. Line
1702 - 1
// MESSAGE MOUNT_STATUS PACKING
2
 
3
#define MAVLINK_MSG_ID_MOUNT_STATUS 158
4
 
5
typedef struct __mavlink_mount_status_t
6
{
7
 int32_t pointing_a; ///< pitch(deg*100) or lat, depending on mount mode
8
 int32_t pointing_b; ///< roll(deg*100) or lon depending on mount mode
9
 int32_t pointing_c; ///< yaw(deg*100) or alt (in cm) depending on mount mode
10
 uint8_t target_system; ///< System ID
11
 uint8_t target_component; ///< Component ID
12
} mavlink_mount_status_t;
13
 
14
#define MAVLINK_MSG_ID_MOUNT_STATUS_LEN 14
15
#define MAVLINK_MSG_ID_158_LEN 14
16
 
17
 
18
 
19
#define MAVLINK_MESSAGE_INFO_MOUNT_STATUS { \
20
        "MOUNT_STATUS", \
21
        5, \
22
        {  { "pointing_a", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_mount_status_t, pointing_a) }, \
23
         { "pointing_b", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_mount_status_t, pointing_b) }, \
24
         { "pointing_c", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_mount_status_t, pointing_c) }, \
25
         { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_mount_status_t, target_system) }, \
26
         { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_mount_status_t, target_component) }, \
27
         } \
28
}
29
 
30
 
31
/**
32
 * @brief Pack a mount_status 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 target_system System ID
38
 * @param target_component Component ID
39
 * @param pointing_a pitch(deg*100) or lat, depending on mount mode
40
 * @param pointing_b roll(deg*100) or lon depending on mount mode
41
 * @param pointing_c yaw(deg*100) or alt (in cm) depending on mount mode
42
 * @return length of the message in bytes (excluding serial stream start sign)
43
 */
44
static inline uint16_t mavlink_msg_mount_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
45
                                                       uint8_t target_system, uint8_t target_component, int32_t pointing_a, int32_t pointing_b, int32_t pointing_c)
46
{
47
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
48
        char buf[14];
49
        _mav_put_int32_t(buf, 0, pointing_a);
50
        _mav_put_int32_t(buf, 4, pointing_b);
51
        _mav_put_int32_t(buf, 8, pointing_c);
52
        _mav_put_uint8_t(buf, 12, target_system);
53
        _mav_put_uint8_t(buf, 13, target_component);
54
 
55
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 14);
56
#else
57
        mavlink_mount_status_t packet;
58
        packet.pointing_a = pointing_a;
59
        packet.pointing_b = pointing_b;
60
        packet.pointing_c = pointing_c;
61
        packet.target_system = target_system;
62
        packet.target_component = target_component;
63
 
64
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 14);
65
#endif
66
 
67
        msg->msgid = MAVLINK_MSG_ID_MOUNT_STATUS;
68
        return mavlink_finalize_message(msg, system_id, component_id, 14, 134);
69
}
70
 
71
/**
72
 * @brief Pack a mount_status message on a channel
73
 * @param system_id ID of this system
74
 * @param component_id ID of this component (e.g. 200 for IMU)
75
 * @param chan The MAVLink channel this message was sent over
76
 * @param msg The MAVLink message to compress the data into
77
 * @param target_system System ID
78
 * @param target_component Component ID
79
 * @param pointing_a pitch(deg*100) or lat, depending on mount mode
80
 * @param pointing_b roll(deg*100) or lon depending on mount mode
81
 * @param pointing_c yaw(deg*100) or alt (in cm) depending on mount mode
82
 * @return length of the message in bytes (excluding serial stream start sign)
83
 */
84
static inline uint16_t mavlink_msg_mount_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
85
                                                           mavlink_message_t* msg,
86
                                                           uint8_t target_system,uint8_t target_component,int32_t pointing_a,int32_t pointing_b,int32_t pointing_c)
87
{
88
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
89
        char buf[14];
90
        _mav_put_int32_t(buf, 0, pointing_a);
91
        _mav_put_int32_t(buf, 4, pointing_b);
92
        _mav_put_int32_t(buf, 8, pointing_c);
93
        _mav_put_uint8_t(buf, 12, target_system);
94
        _mav_put_uint8_t(buf, 13, target_component);
95
 
96
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 14);
97
#else
98
        mavlink_mount_status_t packet;
99
        packet.pointing_a = pointing_a;
100
        packet.pointing_b = pointing_b;
101
        packet.pointing_c = pointing_c;
102
        packet.target_system = target_system;
103
        packet.target_component = target_component;
104
 
105
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 14);
106
#endif
107
 
108
        msg->msgid = MAVLINK_MSG_ID_MOUNT_STATUS;
109
        return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 14, 134);
110
}
111
 
112
/**
113
 * @brief Encode a mount_status struct into a message
114
 *
115
 * @param system_id ID of this system
116
 * @param component_id ID of this component (e.g. 200 for IMU)
117
 * @param msg The MAVLink message to compress the data into
118
 * @param mount_status C-struct to read the message contents from
119
 */
120
static inline uint16_t mavlink_msg_mount_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mount_status_t* mount_status)
121
{
122
        return mavlink_msg_mount_status_pack(system_id, component_id, msg, mount_status->target_system, mount_status->target_component, mount_status->pointing_a, mount_status->pointing_b, mount_status->pointing_c);
123
}
124
 
125
/**
126
 * @brief Send a mount_status message
127
 * @param chan MAVLink channel to send the message
128
 *
129
 * @param target_system System ID
130
 * @param target_component Component ID
131
 * @param pointing_a pitch(deg*100) or lat, depending on mount mode
132
 * @param pointing_b roll(deg*100) or lon depending on mount mode
133
 * @param pointing_c yaw(deg*100) or alt (in cm) depending on mount mode
134
 */
135
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
136
 
137
static inline void mavlink_msg_mount_status_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, int32_t pointing_a, int32_t pointing_b, int32_t pointing_c)
138
{
139
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
140
        char buf[14];
141
        _mav_put_int32_t(buf, 0, pointing_a);
142
        _mav_put_int32_t(buf, 4, pointing_b);
143
        _mav_put_int32_t(buf, 8, pointing_c);
144
        _mav_put_uint8_t(buf, 12, target_system);
145
        _mav_put_uint8_t(buf, 13, target_component);
146
 
147
        _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_STATUS, buf, 14, 134);
148
#else
149
        mavlink_mount_status_t packet;
150
        packet.pointing_a = pointing_a;
151
        packet.pointing_b = pointing_b;
152
        packet.pointing_c = pointing_c;
153
        packet.target_system = target_system;
154
        packet.target_component = target_component;
155
 
156
        _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_STATUS, (const char *)&packet, 14, 134);
157
#endif
158
}
159
 
160
#endif
161
 
162
// MESSAGE MOUNT_STATUS UNPACKING
163
 
164
 
165
/**
166
 * @brief Get field target_system from mount_status message
167
 *
168
 * @return System ID
169
 */
170
static inline uint8_t mavlink_msg_mount_status_get_target_system(const mavlink_message_t* msg)
171
{
172
        return _MAV_RETURN_uint8_t(msg,  12);
173
}
174
 
175
/**
176
 * @brief Get field target_component from mount_status message
177
 *
178
 * @return Component ID
179
 */
180
static inline uint8_t mavlink_msg_mount_status_get_target_component(const mavlink_message_t* msg)
181
{
182
        return _MAV_RETURN_uint8_t(msg,  13);
183
}
184
 
185
/**
186
 * @brief Get field pointing_a from mount_status message
187
 *
188
 * @return pitch(deg*100) or lat, depending on mount mode
189
 */
190
static inline int32_t mavlink_msg_mount_status_get_pointing_a(const mavlink_message_t* msg)
191
{
192
        return _MAV_RETURN_int32_t(msg,  0);
193
}
194
 
195
/**
196
 * @brief Get field pointing_b from mount_status message
197
 *
198
 * @return roll(deg*100) or lon depending on mount mode
199
 */
200
static inline int32_t mavlink_msg_mount_status_get_pointing_b(const mavlink_message_t* msg)
201
{
202
        return _MAV_RETURN_int32_t(msg,  4);
203
}
204
 
205
/**
206
 * @brief Get field pointing_c from mount_status message
207
 *
208
 * @return yaw(deg*100) or alt (in cm) depending on mount mode
209
 */
210
static inline int32_t mavlink_msg_mount_status_get_pointing_c(const mavlink_message_t* msg)
211
{
212
        return _MAV_RETURN_int32_t(msg,  8);
213
}
214
 
215
/**
216
 * @brief Decode a mount_status message into a struct
217
 *
218
 * @param msg The message to decode
219
 * @param mount_status C-struct to decode the message contents into
220
 */
221
static inline void mavlink_msg_mount_status_decode(const mavlink_message_t* msg, mavlink_mount_status_t* mount_status)
222
{
223
#if MAVLINK_NEED_BYTE_SWAP
224
        mount_status->pointing_a = mavlink_msg_mount_status_get_pointing_a(msg);
225
        mount_status->pointing_b = mavlink_msg_mount_status_get_pointing_b(msg);
226
        mount_status->pointing_c = mavlink_msg_mount_status_get_pointing_c(msg);
227
        mount_status->target_system = mavlink_msg_mount_status_get_target_system(msg);
228
        mount_status->target_component = mavlink_msg_mount_status_get_target_component(msg);
229
#else
230
        memcpy(mount_status, _MAV_PAYLOAD(msg), 14);
231
#endif
232
}