RflySimSDK v3.08
RflySimSDK说明文档
载入中...
搜索中...
未找到
mavlink_msg_pid_tuning.h
1#pragma once
2// MESSAGE PID_TUNING PACKING
3
4#define MAVLINK_MSG_ID_PID_TUNING 194
5
6MAVPACKED(
7typedef struct __mavlink_pid_tuning_t {
8 float desired; /*< desired rate (degrees/s)*/
9 float achieved; /*< achieved rate (degrees/s)*/
10 float FF; /*< FF component*/
11 float P; /*< P component*/
12 float I; /*< I component*/
13 float D; /*< D component*/
14 uint8_t axis; /*< axis*/
15}) mavlink_pid_tuning_t;
16
17#define MAVLINK_MSG_ID_PID_TUNING_LEN 25
18#define MAVLINK_MSG_ID_PID_TUNING_MIN_LEN 25
19#define MAVLINK_MSG_ID_194_LEN 25
20#define MAVLINK_MSG_ID_194_MIN_LEN 25
21
22#define MAVLINK_MSG_ID_PID_TUNING_CRC 98
23#define MAVLINK_MSG_ID_194_CRC 98
24
25
26
27#if MAVLINK_COMMAND_24BIT
28#define MAVLINK_MESSAGE_INFO_PID_TUNING { \
29 194, \
30 "PID_TUNING", \
31 7, \
32 { { "axis", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_pid_tuning_t, axis) }, \
33 { "desired", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_pid_tuning_t, desired) }, \
34 { "achieved", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_pid_tuning_t, achieved) }, \
35 { "FF", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_pid_tuning_t, FF) }, \
36 { "P", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_pid_tuning_t, P) }, \
37 { "I", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_pid_tuning_t, I) }, \
38 { "D", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_pid_tuning_t, D) }, \
39 } \
40}
41#else
42#define MAVLINK_MESSAGE_INFO_PID_TUNING { \
43 "PID_TUNING", \
44 7, \
45 { { "axis", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_pid_tuning_t, axis) }, \
46 { "desired", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_pid_tuning_t, desired) }, \
47 { "achieved", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_pid_tuning_t, achieved) }, \
48 { "FF", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_pid_tuning_t, FF) }, \
49 { "P", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_pid_tuning_t, P) }, \
50 { "I", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_pid_tuning_t, I) }, \
51 { "D", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_pid_tuning_t, D) }, \
52 } \
53}
54#endif
55
56/**
57 * @brief Pack a pid_tuning message
58 * @param system_id ID of this system
59 * @param component_id ID of this component (e.g. 200 for IMU)
60 * @param msg The MAVLink message to compress the data into
61 *
62 * @param axis axis
63 * @param desired desired rate (degrees/s)
64 * @param achieved achieved rate (degrees/s)
65 * @param FF FF component
66 * @param P P component
67 * @param I I component
68 * @param D D component
69 * @return length of the message in bytes (excluding serial stream start sign)
70 */
71static inline uint16_t mavlink_msg_pid_tuning_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
72 uint8_t axis, float desired, float achieved, float FF, float P, float I, float D)
73{
74#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
75 char buf[MAVLINK_MSG_ID_PID_TUNING_LEN];
76 _mav_put_float(buf, 0, desired);
77 _mav_put_float(buf, 4, achieved);
78 _mav_put_float(buf, 8, FF);
79 _mav_put_float(buf, 12, P);
80 _mav_put_float(buf, 16, I);
81 _mav_put_float(buf, 20, D);
82 _mav_put_uint8_t(buf, 24, axis);
83
84 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PID_TUNING_LEN);
85#else
86 mavlink_pid_tuning_t packet;
87 packet.desired = desired;
88 packet.achieved = achieved;
89 packet.FF = FF;
90 packet.P = P;
91 packet.I = I;
92 packet.D = D;
93 packet.axis = axis;
94
95 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PID_TUNING_LEN);
96#endif
97
98 msg->msgid = MAVLINK_MSG_ID_PID_TUNING;
99 return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PID_TUNING_MIN_LEN, MAVLINK_MSG_ID_PID_TUNING_LEN, MAVLINK_MSG_ID_PID_TUNING_CRC);
100}
101
102/**
103 * @brief Pack a pid_tuning message on a channel
104 * @param system_id ID of this system
105 * @param component_id ID of this component (e.g. 200 for IMU)
106 * @param chan The MAVLink channel this message will be sent over
107 * @param msg The MAVLink message to compress the data into
108 * @param axis axis
109 * @param desired desired rate (degrees/s)
110 * @param achieved achieved rate (degrees/s)
111 * @param FF FF component
112 * @param P P component
113 * @param I I component
114 * @param D D component
115 * @return length of the message in bytes (excluding serial stream start sign)
116 */
117static inline uint16_t mavlink_msg_pid_tuning_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
118 mavlink_message_t* msg,
119 uint8_t axis,float desired,float achieved,float FF,float P,float I,float D)
120{
121#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
122 char buf[MAVLINK_MSG_ID_PID_TUNING_LEN];
123 _mav_put_float(buf, 0, desired);
124 _mav_put_float(buf, 4, achieved);
125 _mav_put_float(buf, 8, FF);
126 _mav_put_float(buf, 12, P);
127 _mav_put_float(buf, 16, I);
128 _mav_put_float(buf, 20, D);
129 _mav_put_uint8_t(buf, 24, axis);
130
131 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PID_TUNING_LEN);
132#else
133 mavlink_pid_tuning_t packet;
134 packet.desired = desired;
135 packet.achieved = achieved;
136 packet.FF = FF;
137 packet.P = P;
138 packet.I = I;
139 packet.D = D;
140 packet.axis = axis;
141
142 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PID_TUNING_LEN);
143#endif
144
145 msg->msgid = MAVLINK_MSG_ID_PID_TUNING;
146 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PID_TUNING_MIN_LEN, MAVLINK_MSG_ID_PID_TUNING_LEN, MAVLINK_MSG_ID_PID_TUNING_CRC);
147}
148
149/**
150 * @brief Encode a pid_tuning struct
151 *
152 * @param system_id ID of this system
153 * @param component_id ID of this component (e.g. 200 for IMU)
154 * @param msg The MAVLink message to compress the data into
155 * @param pid_tuning C-struct to read the message contents from
156 */
157static inline uint16_t mavlink_msg_pid_tuning_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_pid_tuning_t* pid_tuning)
158{
159 return mavlink_msg_pid_tuning_pack(system_id, component_id, msg, pid_tuning->axis, pid_tuning->desired, pid_tuning->achieved, pid_tuning->FF, pid_tuning->P, pid_tuning->I, pid_tuning->D);
160}
161
162/**
163 * @brief Encode a pid_tuning struct on a channel
164 *
165 * @param system_id ID of this system
166 * @param component_id ID of this component (e.g. 200 for IMU)
167 * @param chan The MAVLink channel this message will be sent over
168 * @param msg The MAVLink message to compress the data into
169 * @param pid_tuning C-struct to read the message contents from
170 */
171static inline uint16_t mavlink_msg_pid_tuning_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_pid_tuning_t* pid_tuning)
172{
173 return mavlink_msg_pid_tuning_pack_chan(system_id, component_id, chan, msg, pid_tuning->axis, pid_tuning->desired, pid_tuning->achieved, pid_tuning->FF, pid_tuning->P, pid_tuning->I, pid_tuning->D);
174}
175
176/**
177 * @brief Send a pid_tuning message
178 * @param chan MAVLink channel to send the message
179 *
180 * @param axis axis
181 * @param desired desired rate (degrees/s)
182 * @param achieved achieved rate (degrees/s)
183 * @param FF FF component
184 * @param P P component
185 * @param I I component
186 * @param D D component
187 */
188#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
189
190static inline void mavlink_msg_pid_tuning_send(mavlink_channel_t chan, uint8_t axis, float desired, float achieved, float FF, float P, float I, float D)
191{
192#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
193 char buf[MAVLINK_MSG_ID_PID_TUNING_LEN];
194 _mav_put_float(buf, 0, desired);
195 _mav_put_float(buf, 4, achieved);
196 _mav_put_float(buf, 8, FF);
197 _mav_put_float(buf, 12, P);
198 _mav_put_float(buf, 16, I);
199 _mav_put_float(buf, 20, D);
200 _mav_put_uint8_t(buf, 24, axis);
201
202 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PID_TUNING, buf, MAVLINK_MSG_ID_PID_TUNING_MIN_LEN, MAVLINK_MSG_ID_PID_TUNING_LEN, MAVLINK_MSG_ID_PID_TUNING_CRC);
203#else
204 mavlink_pid_tuning_t packet;
205 packet.desired = desired;
206 packet.achieved = achieved;
207 packet.FF = FF;
208 packet.P = P;
209 packet.I = I;
210 packet.D = D;
211 packet.axis = axis;
212
213 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PID_TUNING, (const char *)&packet, MAVLINK_MSG_ID_PID_TUNING_MIN_LEN, MAVLINK_MSG_ID_PID_TUNING_LEN, MAVLINK_MSG_ID_PID_TUNING_CRC);
214#endif
215}
216
217/**
218 * @brief Send a pid_tuning message
219 * @param chan MAVLink channel to send the message
220 * @param struct The MAVLink struct to serialize
221 */
222static inline void mavlink_msg_pid_tuning_send_struct(mavlink_channel_t chan, const mavlink_pid_tuning_t* pid_tuning)
223{
224#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
225 mavlink_msg_pid_tuning_send(chan, pid_tuning->axis, pid_tuning->desired, pid_tuning->achieved, pid_tuning->FF, pid_tuning->P, pid_tuning->I, pid_tuning->D);
226#else
227 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PID_TUNING, (const char *)pid_tuning, MAVLINK_MSG_ID_PID_TUNING_MIN_LEN, MAVLINK_MSG_ID_PID_TUNING_LEN, MAVLINK_MSG_ID_PID_TUNING_CRC);
228#endif
229}
230
231#if MAVLINK_MSG_ID_PID_TUNING_LEN <= MAVLINK_MAX_PAYLOAD_LEN
232/*
233 This varient of _send() can be used to save stack space by re-using
234 memory from the receive buffer. The caller provides a
235 mavlink_message_t which is the size of a full mavlink message. This
236 is usually the receive buffer for the channel, and allows a reply to an
237 incoming message with minimum stack space usage.
238 */
239static inline void mavlink_msg_pid_tuning_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t axis, float desired, float achieved, float FF, float P, float I, float D)
240{
241#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
242 char *buf = (char *)msgbuf;
243 _mav_put_float(buf, 0, desired);
244 _mav_put_float(buf, 4, achieved);
245 _mav_put_float(buf, 8, FF);
246 _mav_put_float(buf, 12, P);
247 _mav_put_float(buf, 16, I);
248 _mav_put_float(buf, 20, D);
249 _mav_put_uint8_t(buf, 24, axis);
250
251 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PID_TUNING, buf, MAVLINK_MSG_ID_PID_TUNING_MIN_LEN, MAVLINK_MSG_ID_PID_TUNING_LEN, MAVLINK_MSG_ID_PID_TUNING_CRC);
252#else
253 mavlink_pid_tuning_t *packet = (mavlink_pid_tuning_t *)msgbuf;
254 packet->desired = desired;
255 packet->achieved = achieved;
256 packet->FF = FF;
257 packet->P = P;
258 packet->I = I;
259 packet->D = D;
260 packet->axis = axis;
261
262 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PID_TUNING, (const char *)packet, MAVLINK_MSG_ID_PID_TUNING_MIN_LEN, MAVLINK_MSG_ID_PID_TUNING_LEN, MAVLINK_MSG_ID_PID_TUNING_CRC);
263#endif
264}
265#endif
266
267#endif
268
269// MESSAGE PID_TUNING UNPACKING
270
271
272/**
273 * @brief Get field axis from pid_tuning message
274 *
275 * @return axis
276 */
277static inline uint8_t mavlink_msg_pid_tuning_get_axis(const mavlink_message_t* msg)
278{
279 return _MAV_RETURN_uint8_t(msg, 24);
280}
281
282/**
283 * @brief Get field desired from pid_tuning message
284 *
285 * @return desired rate (degrees/s)
286 */
287static inline float mavlink_msg_pid_tuning_get_desired(const mavlink_message_t* msg)
288{
289 return _MAV_RETURN_float(msg, 0);
290}
291
292/**
293 * @brief Get field achieved from pid_tuning message
294 *
295 * @return achieved rate (degrees/s)
296 */
297static inline float mavlink_msg_pid_tuning_get_achieved(const mavlink_message_t* msg)
298{
299 return _MAV_RETURN_float(msg, 4);
300}
301
302/**
303 * @brief Get field FF from pid_tuning message
304 *
305 * @return FF component
306 */
307static inline float mavlink_msg_pid_tuning_get_FF(const mavlink_message_t* msg)
308{
309 return _MAV_RETURN_float(msg, 8);
310}
311
312/**
313 * @brief Get field P from pid_tuning message
314 *
315 * @return P component
316 */
317static inline float mavlink_msg_pid_tuning_get_P(const mavlink_message_t* msg)
318{
319 return _MAV_RETURN_float(msg, 12);
320}
321
322/**
323 * @brief Get field I from pid_tuning message
324 *
325 * @return I component
326 */
327static inline float mavlink_msg_pid_tuning_get_I(const mavlink_message_t* msg)
328{
329 return _MAV_RETURN_float(msg, 16);
330}
331
332/**
333 * @brief Get field D from pid_tuning message
334 *
335 * @return D component
336 */
337static inline float mavlink_msg_pid_tuning_get_D(const mavlink_message_t* msg)
338{
339 return _MAV_RETURN_float(msg, 20);
340}
341
342/**
343 * @brief Decode a pid_tuning message into a struct
344 *
345 * @param msg The message to decode
346 * @param pid_tuning C-struct to decode the message contents into
347 */
348static inline void mavlink_msg_pid_tuning_decode(const mavlink_message_t* msg, mavlink_pid_tuning_t* pid_tuning)
349{
350#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
351 pid_tuning->desired = mavlink_msg_pid_tuning_get_desired(msg);
352 pid_tuning->achieved = mavlink_msg_pid_tuning_get_achieved(msg);
353 pid_tuning->FF = mavlink_msg_pid_tuning_get_FF(msg);
354 pid_tuning->P = mavlink_msg_pid_tuning_get_P(msg);
355 pid_tuning->I = mavlink_msg_pid_tuning_get_I(msg);
356 pid_tuning->D = mavlink_msg_pid_tuning_get_D(msg);
357 pid_tuning->axis = mavlink_msg_pid_tuning_get_axis(msg);
358#else
359 uint8_t len = msg->len < MAVLINK_MSG_ID_PID_TUNING_LEN? msg->len : MAVLINK_MSG_ID_PID_TUNING_LEN;
360 memset(pid_tuning, 0, MAVLINK_MSG_ID_PID_TUNING_LEN);
361 memcpy(pid_tuning, _MAV_PAYLOAD(msg), len);
362#endif
363}