Subversion Repositories Projects

Rev

Details | Last modification | View Log | RSS feed

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