Details | Last modification | View Log | RSS feed
Rev | Author | Line No. | Line |
---|---|---|---|
1702 | - | 1 | // MESSAGE ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT PACKING |
2 | |||
3 | #define MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT 59 |
||
4 | |||
5 | typedef struct __mavlink_roll_pitch_yaw_speed_thrust_setpoint_t |
||
6 | { |
||
7 | uint32_t time_boot_ms; ///< Timestamp in milliseconds since system boot |
||
8 | float roll_speed; ///< Desired roll angular speed in rad/s |
||
9 | float pitch_speed; ///< Desired pitch angular speed in rad/s |
||
10 | float yaw_speed; ///< Desired yaw angular speed in rad/s |
||
11 | float thrust; ///< Collective thrust, normalized to 0 .. 1 |
||
12 | } mavlink_roll_pitch_yaw_speed_thrust_setpoint_t; |
||
13 | |||
14 | #define MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT_LEN 20 |
||
15 | #define MAVLINK_MSG_ID_59_LEN 20 |
||
16 | |||
17 | |||
18 | |||
19 | #define MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT { \ |
||
20 | "ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT", \ |
||
21 | 5, \ |
||
22 | { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_roll_pitch_yaw_speed_thrust_setpoint_t, time_boot_ms) }, \ |
||
23 | { "roll_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_roll_pitch_yaw_speed_thrust_setpoint_t, roll_speed) }, \ |
||
24 | { "pitch_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_roll_pitch_yaw_speed_thrust_setpoint_t, pitch_speed) }, \ |
||
25 | { "yaw_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_roll_pitch_yaw_speed_thrust_setpoint_t, yaw_speed) }, \ |
||
26 | { "thrust", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_roll_pitch_yaw_speed_thrust_setpoint_t, thrust) }, \ |
||
27 | } \ |
||
28 | } |
||
29 | |||
30 | |||
31 | /** |
||
32 | * @brief Pack a roll_pitch_yaw_speed_thrust_setpoint 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 time_boot_ms Timestamp in milliseconds since system boot |
||
38 | * @param roll_speed Desired roll angular speed in rad/s |
||
39 | * @param pitch_speed Desired pitch angular speed in rad/s |
||
40 | * @param yaw_speed Desired yaw angular speed in rad/s |
||
41 | * @param thrust Collective thrust, normalized to 0 .. 1 |
||
42 | * @return length of the message in bytes (excluding serial stream start sign) |
||
43 | */ |
||
44 | static inline uint16_t mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, |
||
45 | uint32_t time_boot_ms, float roll_speed, float pitch_speed, float yaw_speed, float thrust) |
||
46 | { |
||
47 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS |
||
48 | char buf[20]; |
||
49 | _mav_put_uint32_t(buf, 0, time_boot_ms); |
||
50 | _mav_put_float(buf, 4, roll_speed); |
||
51 | _mav_put_float(buf, 8, pitch_speed); |
||
52 | _mav_put_float(buf, 12, yaw_speed); |
||
53 | _mav_put_float(buf, 16, thrust); |
||
54 | |||
55 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 20); |
||
56 | #else |
||
57 | mavlink_roll_pitch_yaw_speed_thrust_setpoint_t packet; |
||
58 | packet.time_boot_ms = time_boot_ms; |
||
59 | packet.roll_speed = roll_speed; |
||
60 | packet.pitch_speed = pitch_speed; |
||
61 | packet.yaw_speed = yaw_speed; |
||
62 | packet.thrust = thrust; |
||
63 | |||
64 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 20); |
||
65 | #endif |
||
66 | |||
67 | msg->msgid = MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT; |
||
68 | return mavlink_finalize_message(msg, system_id, component_id, 20, 238); |
||
69 | } |
||
70 | |||
71 | /** |
||
72 | * @brief Pack a roll_pitch_yaw_speed_thrust_setpoint 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 time_boot_ms Timestamp in milliseconds since system boot |
||
78 | * @param roll_speed Desired roll angular speed in rad/s |
||
79 | * @param pitch_speed Desired pitch angular speed in rad/s |
||
80 | * @param yaw_speed Desired yaw angular speed in rad/s |
||
81 | * @param thrust Collective thrust, normalized to 0 .. 1 |
||
82 | * @return length of the message in bytes (excluding serial stream start sign) |
||
83 | */ |
||
84 | static inline uint16_t mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, |
||
85 | mavlink_message_t* msg, |
||
86 | uint32_t time_boot_ms,float roll_speed,float pitch_speed,float yaw_speed,float thrust) |
||
87 | { |
||
88 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS |
||
89 | char buf[20]; |
||
90 | _mav_put_uint32_t(buf, 0, time_boot_ms); |
||
91 | _mav_put_float(buf, 4, roll_speed); |
||
92 | _mav_put_float(buf, 8, pitch_speed); |
||
93 | _mav_put_float(buf, 12, yaw_speed); |
||
94 | _mav_put_float(buf, 16, thrust); |
||
95 | |||
96 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 20); |
||
97 | #else |
||
98 | mavlink_roll_pitch_yaw_speed_thrust_setpoint_t packet; |
||
99 | packet.time_boot_ms = time_boot_ms; |
||
100 | packet.roll_speed = roll_speed; |
||
101 | packet.pitch_speed = pitch_speed; |
||
102 | packet.yaw_speed = yaw_speed; |
||
103 | packet.thrust = thrust; |
||
104 | |||
105 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 20); |
||
106 | #endif |
||
107 | |||
108 | msg->msgid = MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT; |
||
109 | return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 20, 238); |
||
110 | } |
||
111 | |||
112 | /** |
||
113 | * @brief Encode a roll_pitch_yaw_speed_thrust_setpoint 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 roll_pitch_yaw_speed_thrust_setpoint C-struct to read the message contents from |
||
119 | */ |
||
120 | static inline uint16_t mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_roll_pitch_yaw_speed_thrust_setpoint_t* roll_pitch_yaw_speed_thrust_setpoint) |
||
121 | { |
||
122 | return mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_pack(system_id, component_id, msg, roll_pitch_yaw_speed_thrust_setpoint->time_boot_ms, roll_pitch_yaw_speed_thrust_setpoint->roll_speed, roll_pitch_yaw_speed_thrust_setpoint->pitch_speed, roll_pitch_yaw_speed_thrust_setpoint->yaw_speed, roll_pitch_yaw_speed_thrust_setpoint->thrust); |
||
123 | } |
||
124 | |||
125 | /** |
||
126 | * @brief Send a roll_pitch_yaw_speed_thrust_setpoint message |
||
127 | * @param chan MAVLink channel to send the message |
||
128 | * |
||
129 | * @param time_boot_ms Timestamp in milliseconds since system boot |
||
130 | * @param roll_speed Desired roll angular speed in rad/s |
||
131 | * @param pitch_speed Desired pitch angular speed in rad/s |
||
132 | * @param yaw_speed Desired yaw angular speed in rad/s |
||
133 | * @param thrust Collective thrust, normalized to 0 .. 1 |
||
134 | */ |
||
135 | #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS |
||
136 | |||
137 | static inline void mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_send(mavlink_channel_t chan, uint32_t time_boot_ms, float roll_speed, float pitch_speed, float yaw_speed, float thrust) |
||
138 | { |
||
139 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS |
||
140 | char buf[20]; |
||
141 | _mav_put_uint32_t(buf, 0, time_boot_ms); |
||
142 | _mav_put_float(buf, 4, roll_speed); |
||
143 | _mav_put_float(buf, 8, pitch_speed); |
||
144 | _mav_put_float(buf, 12, yaw_speed); |
||
145 | _mav_put_float(buf, 16, thrust); |
||
146 | |||
147 | _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, buf, 20, 238); |
||
148 | #else |
||
149 | mavlink_roll_pitch_yaw_speed_thrust_setpoint_t packet; |
||
150 | packet.time_boot_ms = time_boot_ms; |
||
151 | packet.roll_speed = roll_speed; |
||
152 | packet.pitch_speed = pitch_speed; |
||
153 | packet.yaw_speed = yaw_speed; |
||
154 | packet.thrust = thrust; |
||
155 | |||
156 | _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, (const char *)&packet, 20, 238); |
||
157 | #endif |
||
158 | } |
||
159 | |||
160 | #endif |
||
161 | |||
162 | // MESSAGE ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT UNPACKING |
||
163 | |||
164 | |||
165 | /** |
||
166 | * @brief Get field time_boot_ms from roll_pitch_yaw_speed_thrust_setpoint message |
||
167 | * |
||
168 | * @return Timestamp in milliseconds since system boot |
||
169 | */ |
||
170 | static inline uint32_t mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_get_time_boot_ms(const mavlink_message_t* msg) |
||
171 | { |
||
172 | return _MAV_RETURN_uint32_t(msg, 0); |
||
173 | } |
||
174 | |||
175 | /** |
||
176 | * @brief Get field roll_speed from roll_pitch_yaw_speed_thrust_setpoint message |
||
177 | * |
||
178 | * @return Desired roll angular speed in rad/s |
||
179 | */ |
||
180 | static inline float mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_get_roll_speed(const mavlink_message_t* msg) |
||
181 | { |
||
182 | return _MAV_RETURN_float(msg, 4); |
||
183 | } |
||
184 | |||
185 | /** |
||
186 | * @brief Get field pitch_speed from roll_pitch_yaw_speed_thrust_setpoint message |
||
187 | * |
||
188 | * @return Desired pitch angular speed in rad/s |
||
189 | */ |
||
190 | static inline float mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_get_pitch_speed(const mavlink_message_t* msg) |
||
191 | { |
||
192 | return _MAV_RETURN_float(msg, 8); |
||
193 | } |
||
194 | |||
195 | /** |
||
196 | * @brief Get field yaw_speed from roll_pitch_yaw_speed_thrust_setpoint message |
||
197 | * |
||
198 | * @return Desired yaw angular speed in rad/s |
||
199 | */ |
||
200 | static inline float mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_get_yaw_speed(const mavlink_message_t* msg) |
||
201 | { |
||
202 | return _MAV_RETURN_float(msg, 12); |
||
203 | } |
||
204 | |||
205 | /** |
||
206 | * @brief Get field thrust from roll_pitch_yaw_speed_thrust_setpoint message |
||
207 | * |
||
208 | * @return Collective thrust, normalized to 0 .. 1 |
||
209 | */ |
||
210 | static inline float mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_get_thrust(const mavlink_message_t* msg) |
||
211 | { |
||
212 | return _MAV_RETURN_float(msg, 16); |
||
213 | } |
||
214 | |||
215 | /** |
||
216 | * @brief Decode a roll_pitch_yaw_speed_thrust_setpoint message into a struct |
||
217 | * |
||
218 | * @param msg The message to decode |
||
219 | * @param roll_pitch_yaw_speed_thrust_setpoint C-struct to decode the message contents into |
||
220 | */ |
||
221 | static inline void mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_decode(const mavlink_message_t* msg, mavlink_roll_pitch_yaw_speed_thrust_setpoint_t* roll_pitch_yaw_speed_thrust_setpoint) |
||
222 | { |
||
223 | #if MAVLINK_NEED_BYTE_SWAP |
||
224 | roll_pitch_yaw_speed_thrust_setpoint->time_boot_ms = mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_get_time_boot_ms(msg); |
||
225 | roll_pitch_yaw_speed_thrust_setpoint->roll_speed = mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_get_roll_speed(msg); |
||
226 | roll_pitch_yaw_speed_thrust_setpoint->pitch_speed = mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_get_pitch_speed(msg); |
||
227 | roll_pitch_yaw_speed_thrust_setpoint->yaw_speed = mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_get_yaw_speed(msg); |
||
228 | roll_pitch_yaw_speed_thrust_setpoint->thrust = mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_get_thrust(msg); |
||
229 | #else |
||
230 | memcpy(roll_pitch_yaw_speed_thrust_setpoint, _MAV_PAYLOAD(msg), 20); |
||
231 | #endif |
||
232 | } |