Subversion Repositories Projects

Rev

Details | Last modification | View Log | RSS feed

Rev Author Line No. Line
1702 - 1
// MESSAGE HIL_CONTROLS PACKING
2
 
3
#define MAVLINK_MSG_ID_HIL_CONTROLS 68
4
 
5
typedef struct __mavlink_hil_controls_t
6
{
7
 uint64_t time_us; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot)
8
 float roll_ailerons; ///< Control output -3 .. 1
9
 float pitch_elevator; ///< Control output -1 .. 1
10
 float yaw_rudder; ///< Control output -1 .. 1
11
 float throttle; ///< Throttle 0 .. 1
12
 uint8_t mode; ///< System mode (MAV_MODE)
13
 uint8_t nav_mode; ///< Navigation mode (MAV_NAV_MODE)
14
} mavlink_hil_controls_t;
15
 
16
#define MAVLINK_MSG_ID_HIL_CONTROLS_LEN 26
17
#define MAVLINK_MSG_ID_68_LEN 26
18
 
19
 
20
 
21
#define MAVLINK_MESSAGE_INFO_HIL_CONTROLS { \
22
        "HIL_CONTROLS", \
23
        7, \
24
        {  { "time_us", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_controls_t, time_us) }, \
25
         { "roll_ailerons", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_hil_controls_t, roll_ailerons) }, \
26
         { "pitch_elevator", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_hil_controls_t, pitch_elevator) }, \
27
         { "yaw_rudder", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_hil_controls_t, yaw_rudder) }, \
28
         { "throttle", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_hil_controls_t, throttle) }, \
29
         { "mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_hil_controls_t, mode) }, \
30
         { "nav_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 25, offsetof(mavlink_hil_controls_t, nav_mode) }, \
31
         } \
32
}
33
 
34
 
35
/**
36
 * @brief Pack a hil_controls message
37
 * @param system_id ID of this system
38
 * @param component_id ID of this component (e.g. 200 for IMU)
39
 * @param msg The MAVLink message to compress the data into
40
 *
41
 * @param time_us Timestamp (microseconds since UNIX epoch or microseconds since system boot)
42
 * @param roll_ailerons Control output -3 .. 1
43
 * @param pitch_elevator Control output -1 .. 1
44
 * @param yaw_rudder Control output -1 .. 1
45
 * @param throttle Throttle 0 .. 1
46
 * @param mode System mode (MAV_MODE)
47
 * @param nav_mode Navigation mode (MAV_NAV_MODE)
48
 * @return length of the message in bytes (excluding serial stream start sign)
49
 */
50
static inline uint16_t mavlink_msg_hil_controls_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
51
                                                       uint64_t time_us, float roll_ailerons, float pitch_elevator, float yaw_rudder, float throttle, uint8_t mode, uint8_t nav_mode)
52
{
53
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
54
        char buf[26];
55
        _mav_put_uint64_t(buf, 0, time_us);
56
        _mav_put_float(buf, 8, roll_ailerons);
57
        _mav_put_float(buf, 12, pitch_elevator);
58
        _mav_put_float(buf, 16, yaw_rudder);
59
        _mav_put_float(buf, 20, throttle);
60
        _mav_put_uint8_t(buf, 24, mode);
61
        _mav_put_uint8_t(buf, 25, nav_mode);
62
 
63
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 26);
64
#else
65
        mavlink_hil_controls_t packet;
66
        packet.time_us = time_us;
67
        packet.roll_ailerons = roll_ailerons;
68
        packet.pitch_elevator = pitch_elevator;
69
        packet.yaw_rudder = yaw_rudder;
70
        packet.throttle = throttle;
71
        packet.mode = mode;
72
        packet.nav_mode = nav_mode;
73
 
74
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 26);
75
#endif
76
 
77
        msg->msgid = MAVLINK_MSG_ID_HIL_CONTROLS;
78
        return mavlink_finalize_message(msg, system_id, component_id, 26);
79
}
80
 
81
/**
82
 * @brief Pack a hil_controls message on a channel
83
 * @param system_id ID of this system
84
 * @param component_id ID of this component (e.g. 200 for IMU)
85
 * @param chan The MAVLink channel this message was sent over
86
 * @param msg The MAVLink message to compress the data into
87
 * @param time_us Timestamp (microseconds since UNIX epoch or microseconds since system boot)
88
 * @param roll_ailerons Control output -3 .. 1
89
 * @param pitch_elevator Control output -1 .. 1
90
 * @param yaw_rudder Control output -1 .. 1
91
 * @param throttle Throttle 0 .. 1
92
 * @param mode System mode (MAV_MODE)
93
 * @param nav_mode Navigation mode (MAV_NAV_MODE)
94
 * @return length of the message in bytes (excluding serial stream start sign)
95
 */
96
static inline uint16_t mavlink_msg_hil_controls_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
97
                                                           mavlink_message_t* msg,
98
                                                           uint64_t time_us,float roll_ailerons,float pitch_elevator,float yaw_rudder,float throttle,uint8_t mode,uint8_t nav_mode)
99
{
100
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
101
        char buf[26];
102
        _mav_put_uint64_t(buf, 0, time_us);
103
        _mav_put_float(buf, 8, roll_ailerons);
104
        _mav_put_float(buf, 12, pitch_elevator);
105
        _mav_put_float(buf, 16, yaw_rudder);
106
        _mav_put_float(buf, 20, throttle);
107
        _mav_put_uint8_t(buf, 24, mode);
108
        _mav_put_uint8_t(buf, 25, nav_mode);
109
 
110
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 26);
111
#else
112
        mavlink_hil_controls_t packet;
113
        packet.time_us = time_us;
114
        packet.roll_ailerons = roll_ailerons;
115
        packet.pitch_elevator = pitch_elevator;
116
        packet.yaw_rudder = yaw_rudder;
117
        packet.throttle = throttle;
118
        packet.mode = mode;
119
        packet.nav_mode = nav_mode;
120
 
121
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 26);
122
#endif
123
 
124
        msg->msgid = MAVLINK_MSG_ID_HIL_CONTROLS;
125
        return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 26);
126
}
127
 
128
/**
129
 * @brief Encode a hil_controls struct into a message
130
 *
131
 * @param system_id ID of this system
132
 * @param component_id ID of this component (e.g. 200 for IMU)
133
 * @param msg The MAVLink message to compress the data into
134
 * @param hil_controls C-struct to read the message contents from
135
 */
136
static inline uint16_t mavlink_msg_hil_controls_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_hil_controls_t* hil_controls)
137
{
138
        return mavlink_msg_hil_controls_pack(system_id, component_id, msg, hil_controls->time_us, hil_controls->roll_ailerons, hil_controls->pitch_elevator, hil_controls->yaw_rudder, hil_controls->throttle, hil_controls->mode, hil_controls->nav_mode);
139
}
140
 
141
/**
142
 * @brief Send a hil_controls message
143
 * @param chan MAVLink channel to send the message
144
 *
145
 * @param time_us Timestamp (microseconds since UNIX epoch or microseconds since system boot)
146
 * @param roll_ailerons Control output -3 .. 1
147
 * @param pitch_elevator Control output -1 .. 1
148
 * @param yaw_rudder Control output -1 .. 1
149
 * @param throttle Throttle 0 .. 1
150
 * @param mode System mode (MAV_MODE)
151
 * @param nav_mode Navigation mode (MAV_NAV_MODE)
152
 */
153
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
154
 
155
static inline void mavlink_msg_hil_controls_send(mavlink_channel_t chan, uint64_t time_us, float roll_ailerons, float pitch_elevator, float yaw_rudder, float throttle, uint8_t mode, uint8_t nav_mode)
156
{
157
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
158
        char buf[26];
159
        _mav_put_uint64_t(buf, 0, time_us);
160
        _mav_put_float(buf, 8, roll_ailerons);
161
        _mav_put_float(buf, 12, pitch_elevator);
162
        _mav_put_float(buf, 16, yaw_rudder);
163
        _mav_put_float(buf, 20, throttle);
164
        _mav_put_uint8_t(buf, 24, mode);
165
        _mav_put_uint8_t(buf, 25, nav_mode);
166
 
167
        _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_CONTROLS, buf, 26);
168
#else
169
        mavlink_hil_controls_t packet;
170
        packet.time_us = time_us;
171
        packet.roll_ailerons = roll_ailerons;
172
        packet.pitch_elevator = pitch_elevator;
173
        packet.yaw_rudder = yaw_rudder;
174
        packet.throttle = throttle;
175
        packet.mode = mode;
176
        packet.nav_mode = nav_mode;
177
 
178
        _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_CONTROLS, (const char *)&packet, 26);
179
#endif
180
}
181
 
182
#endif
183
 
184
// MESSAGE HIL_CONTROLS UNPACKING
185
 
186
 
187
/**
188
 * @brief Get field time_us from hil_controls message
189
 *
190
 * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot)
191
 */
192
static inline uint64_t mavlink_msg_hil_controls_get_time_us(const mavlink_message_t* msg)
193
{
194
        return _MAV_RETURN_uint64_t(msg,  0);
195
}
196
 
197
/**
198
 * @brief Get field roll_ailerons from hil_controls message
199
 *
200
 * @return Control output -3 .. 1
201
 */
202
static inline float mavlink_msg_hil_controls_get_roll_ailerons(const mavlink_message_t* msg)
203
{
204
        return _MAV_RETURN_float(msg,  8);
205
}
206
 
207
/**
208
 * @brief Get field pitch_elevator from hil_controls message
209
 *
210
 * @return Control output -1 .. 1
211
 */
212
static inline float mavlink_msg_hil_controls_get_pitch_elevator(const mavlink_message_t* msg)
213
{
214
        return _MAV_RETURN_float(msg,  12);
215
}
216
 
217
/**
218
 * @brief Get field yaw_rudder from hil_controls message
219
 *
220
 * @return Control output -1 .. 1
221
 */
222
static inline float mavlink_msg_hil_controls_get_yaw_rudder(const mavlink_message_t* msg)
223
{
224
        return _MAV_RETURN_float(msg,  16);
225
}
226
 
227
/**
228
 * @brief Get field throttle from hil_controls message
229
 *
230
 * @return Throttle 0 .. 1
231
 */
232
static inline float mavlink_msg_hil_controls_get_throttle(const mavlink_message_t* msg)
233
{
234
        return _MAV_RETURN_float(msg,  20);
235
}
236
 
237
/**
238
 * @brief Get field mode from hil_controls message
239
 *
240
 * @return System mode (MAV_MODE)
241
 */
242
static inline uint8_t mavlink_msg_hil_controls_get_mode(const mavlink_message_t* msg)
243
{
244
        return _MAV_RETURN_uint8_t(msg,  24);
245
}
246
 
247
/**
248
 * @brief Get field nav_mode from hil_controls message
249
 *
250
 * @return Navigation mode (MAV_NAV_MODE)
251
 */
252
static inline uint8_t mavlink_msg_hil_controls_get_nav_mode(const mavlink_message_t* msg)
253
{
254
        return _MAV_RETURN_uint8_t(msg,  25);
255
}
256
 
257
/**
258
 * @brief Decode a hil_controls message into a struct
259
 *
260
 * @param msg The message to decode
261
 * @param hil_controls C-struct to decode the message contents into
262
 */
263
static inline void mavlink_msg_hil_controls_decode(const mavlink_message_t* msg, mavlink_hil_controls_t* hil_controls)
264
{
265
#if MAVLINK_NEED_BYTE_SWAP
266
        hil_controls->time_us = mavlink_msg_hil_controls_get_time_us(msg);
267
        hil_controls->roll_ailerons = mavlink_msg_hil_controls_get_roll_ailerons(msg);
268
        hil_controls->pitch_elevator = mavlink_msg_hil_controls_get_pitch_elevator(msg);
269
        hil_controls->yaw_rudder = mavlink_msg_hil_controls_get_yaw_rudder(msg);
270
        hil_controls->throttle = mavlink_msg_hil_controls_get_throttle(msg);
271
        hil_controls->mode = mavlink_msg_hil_controls_get_mode(msg);
272
        hil_controls->nav_mode = mavlink_msg_hil_controls_get_nav_mode(msg);
273
#else
274
        memcpy(hil_controls, _MAV_PAYLOAD(msg), 26);
275
#endif
276
}