1 | // MESSAGE ACTUATOR_CONTROL_TARGET PACKING |
---|
2 | |
---|
3 | #define MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET 140 |
---|
4 | |
---|
5 | MAVPACKED( |
---|
6 | typedef struct __mavlink_actuator_control_target_t { |
---|
7 | uint64_t time_usec; /*< Timestamp (micros since boot or Unix epoch)*/ |
---|
8 | float controls[8]; /*< Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs.*/ |
---|
9 | uint8_t group_mlx; /*< Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances.*/ |
---|
10 | }) mavlink_actuator_control_target_t; |
---|
11 | |
---|
12 | #define MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN 41 |
---|
13 | #define MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_MIN_LEN 41 |
---|
14 | #define MAVLINK_MSG_ID_140_LEN 41 |
---|
15 | #define MAVLINK_MSG_ID_140_MIN_LEN 41 |
---|
16 | |
---|
17 | #define MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_CRC 181 |
---|
18 | #define MAVLINK_MSG_ID_140_CRC 181 |
---|
19 | |
---|
20 | #define MAVLINK_MSG_ACTUATOR_CONTROL_TARGET_FIELD_CONTROLS_LEN 8 |
---|
21 | |
---|
22 | #if MAVLINK_COMMAND_24BIT |
---|
23 | #define MAVLINK_MESSAGE_INFO_ACTUATOR_CONTROL_TARGET { \ |
---|
24 | 140, \ |
---|
25 | "ACTUATOR_CONTROL_TARGET", \ |
---|
26 | 3, \ |
---|
27 | { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_actuator_control_target_t, time_usec) }, \ |
---|
28 | { "controls", NULL, MAVLINK_TYPE_FLOAT, 8, 8, offsetof(mavlink_actuator_control_target_t, controls) }, \ |
---|
29 | { "group_mlx", NULL, MAVLINK_TYPE_UINT8_T, 0, 40, offsetof(mavlink_actuator_control_target_t, group_mlx) }, \ |
---|
30 | } \ |
---|
31 | } |
---|
32 | #else |
---|
33 | #define MAVLINK_MESSAGE_INFO_ACTUATOR_CONTROL_TARGET { \ |
---|
34 | "ACTUATOR_CONTROL_TARGET", \ |
---|
35 | 3, \ |
---|
36 | { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_actuator_control_target_t, time_usec) }, \ |
---|
37 | { "controls", NULL, MAVLINK_TYPE_FLOAT, 8, 8, offsetof(mavlink_actuator_control_target_t, controls) }, \ |
---|
38 | { "group_mlx", NULL, MAVLINK_TYPE_UINT8_T, 0, 40, offsetof(mavlink_actuator_control_target_t, group_mlx) }, \ |
---|
39 | } \ |
---|
40 | } |
---|
41 | #endif |
---|
42 | |
---|
43 | /** |
---|
44 | * @brief Pack a actuator_control_target message |
---|
45 | * @param system_id ID of this system |
---|
46 | * @param component_id ID of this component (e.g. 200 for IMU) |
---|
47 | * @param msg The MAVLink message to compress the data into |
---|
48 | * |
---|
49 | * @param time_usec Timestamp (micros since boot or Unix epoch) |
---|
50 | * @param group_mlx Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. |
---|
51 | * @param controls Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. |
---|
52 | * @return length of the message in bytes (excluding serial stream start sign) |
---|
53 | */ |
---|
54 | static inline uint16_t mavlink_msg_actuator_control_target_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, |
---|
55 | uint64_t time_usec, uint8_t group_mlx, const float *controls) |
---|
56 | { |
---|
57 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS |
---|
58 | char buf[MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN]; |
---|
59 | _mav_put_uint64_t(buf, 0, time_usec); |
---|
60 | _mav_put_uint8_t(buf, 40, group_mlx); |
---|
61 | _mav_put_float_array(buf, 8, controls, 8); |
---|
62 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN); |
---|
63 | #else |
---|
64 | mavlink_actuator_control_target_t packet; |
---|
65 | packet.time_usec = time_usec; |
---|
66 | packet.group_mlx = group_mlx; |
---|
67 | mav_array_memcpy(packet.controls, controls, sizeof(float)*8); |
---|
68 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN); |
---|
69 | #endif |
---|
70 | |
---|
71 | msg->msgid = MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET; |
---|
72 | return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_MIN_LEN, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_CRC); |
---|
73 | } |
---|
74 | |
---|
75 | /** |
---|
76 | * @brief Pack a actuator_control_target message on a channel |
---|
77 | * @param system_id ID of this system |
---|
78 | * @param component_id ID of this component (e.g. 200 for IMU) |
---|
79 | * @param chan The MAVLink channel this message will be sent over |
---|
80 | * @param msg The MAVLink message to compress the data into |
---|
81 | * @param time_usec Timestamp (micros since boot or Unix epoch) |
---|
82 | * @param group_mlx Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. |
---|
83 | * @param controls Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. |
---|
84 | * @return length of the message in bytes (excluding serial stream start sign) |
---|
85 | */ |
---|
86 | static inline uint16_t mavlink_msg_actuator_control_target_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, |
---|
87 | mavlink_message_t* msg, |
---|
88 | uint64_t time_usec,uint8_t group_mlx,const float *controls) |
---|
89 | { |
---|
90 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS |
---|
91 | char buf[MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN]; |
---|
92 | _mav_put_uint64_t(buf, 0, time_usec); |
---|
93 | _mav_put_uint8_t(buf, 40, group_mlx); |
---|
94 | _mav_put_float_array(buf, 8, controls, 8); |
---|
95 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN); |
---|
96 | #else |
---|
97 | mavlink_actuator_control_target_t packet; |
---|
98 | packet.time_usec = time_usec; |
---|
99 | packet.group_mlx = group_mlx; |
---|
100 | mav_array_memcpy(packet.controls, controls, sizeof(float)*8); |
---|
101 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN); |
---|
102 | #endif |
---|
103 | |
---|
104 | msg->msgid = MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET; |
---|
105 | return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_MIN_LEN, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_CRC); |
---|
106 | } |
---|
107 | |
---|
108 | /** |
---|
109 | * @brief Encode a actuator_control_target struct |
---|
110 | * |
---|
111 | * @param system_id ID of this system |
---|
112 | * @param component_id ID of this component (e.g. 200 for IMU) |
---|
113 | * @param msg The MAVLink message to compress the data into |
---|
114 | * @param actuator_control_target C-struct to read the message contents from |
---|
115 | */ |
---|
116 | static inline uint16_t mavlink_msg_actuator_control_target_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_actuator_control_target_t* actuator_control_target) |
---|
117 | { |
---|
118 | return mavlink_msg_actuator_control_target_pack(system_id, component_id, msg, actuator_control_target->time_usec, actuator_control_target->group_mlx, actuator_control_target->controls); |
---|
119 | } |
---|
120 | |
---|
121 | /** |
---|
122 | * @brief Encode a actuator_control_target struct on a channel |
---|
123 | * |
---|
124 | * @param system_id ID of this system |
---|
125 | * @param component_id ID of this component (e.g. 200 for IMU) |
---|
126 | * @param chan The MAVLink channel this message will be sent over |
---|
127 | * @param msg The MAVLink message to compress the data into |
---|
128 | * @param actuator_control_target C-struct to read the message contents from |
---|
129 | */ |
---|
130 | static inline uint16_t mavlink_msg_actuator_control_target_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_actuator_control_target_t* actuator_control_target) |
---|
131 | { |
---|
132 | return mavlink_msg_actuator_control_target_pack_chan(system_id, component_id, chan, msg, actuator_control_target->time_usec, actuator_control_target->group_mlx, actuator_control_target->controls); |
---|
133 | } |
---|
134 | |
---|
135 | /** |
---|
136 | * @brief Send a actuator_control_target message |
---|
137 | * @param chan MAVLink channel to send the message |
---|
138 | * |
---|
139 | * @param time_usec Timestamp (micros since boot or Unix epoch) |
---|
140 | * @param group_mlx Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. |
---|
141 | * @param controls Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. |
---|
142 | */ |
---|
143 | #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS |
---|
144 | |
---|
145 | static inline void mavlink_msg_actuator_control_target_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t group_mlx, const float *controls) |
---|
146 | { |
---|
147 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS |
---|
148 | char buf[MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN]; |
---|
149 | _mav_put_uint64_t(buf, 0, time_usec); |
---|
150 | _mav_put_uint8_t(buf, 40, group_mlx); |
---|
151 | _mav_put_float_array(buf, 8, controls, 8); |
---|
152 | _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET, buf, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_MIN_LEN, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_CRC); |
---|
153 | #else |
---|
154 | mavlink_actuator_control_target_t packet; |
---|
155 | packet.time_usec = time_usec; |
---|
156 | packet.group_mlx = group_mlx; |
---|
157 | mav_array_memcpy(packet.controls, controls, sizeof(float)*8); |
---|
158 | _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET, (const char *)&packet, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_MIN_LEN, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_CRC); |
---|
159 | #endif |
---|
160 | } |
---|
161 | |
---|
162 | /** |
---|
163 | * @brief Send a actuator_control_target message |
---|
164 | * @param chan MAVLink channel to send the message |
---|
165 | * @param struct The MAVLink struct to serialize |
---|
166 | */ |
---|
167 | static inline void mavlink_msg_actuator_control_target_send_struct(mavlink_channel_t chan, const mavlink_actuator_control_target_t* actuator_control_target) |
---|
168 | { |
---|
169 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS |
---|
170 | mavlink_msg_actuator_control_target_send(chan, actuator_control_target->time_usec, actuator_control_target->group_mlx, actuator_control_target->controls); |
---|
171 | #else |
---|
172 | _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET, (const char *)actuator_control_target, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_MIN_LEN, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_CRC); |
---|
173 | #endif |
---|
174 | } |
---|
175 | |
---|
176 | #if MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN <= MAVLINK_MAX_PAYLOAD_LEN |
---|
177 | /* |
---|
178 | This varient of _send() can be used to save stack space by re-using |
---|
179 | memory from the receive buffer. The caller provides a |
---|
180 | mavlink_message_t which is the size of a full mavlink message. This |
---|
181 | is usually the receive buffer for the channel, and allows a reply to an |
---|
182 | incoming message with minimum stack space usage. |
---|
183 | */ |
---|
184 | static inline void mavlink_msg_actuator_control_target_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint8_t group_mlx, const float *controls) |
---|
185 | { |
---|
186 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS |
---|
187 | char *buf = (char *)msgbuf; |
---|
188 | _mav_put_uint64_t(buf, 0, time_usec); |
---|
189 | _mav_put_uint8_t(buf, 40, group_mlx); |
---|
190 | _mav_put_float_array(buf, 8, controls, 8); |
---|
191 | _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET, buf, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_MIN_LEN, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_CRC); |
---|
192 | #else |
---|
193 | mavlink_actuator_control_target_t *packet = (mavlink_actuator_control_target_t *)msgbuf; |
---|
194 | packet->time_usec = time_usec; |
---|
195 | packet->group_mlx = group_mlx; |
---|
196 | mav_array_memcpy(packet->controls, controls, sizeof(float)*8); |
---|
197 | _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET, (const char *)packet, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_MIN_LEN, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_CRC); |
---|
198 | #endif |
---|
199 | } |
---|
200 | #endif |
---|
201 | |
---|
202 | #endif |
---|
203 | |
---|
204 | // MESSAGE ACTUATOR_CONTROL_TARGET UNPACKING |
---|
205 | |
---|
206 | |
---|
207 | /** |
---|
208 | * @brief Get field time_usec from actuator_control_target message |
---|
209 | * |
---|
210 | * @return Timestamp (micros since boot or Unix epoch) |
---|
211 | */ |
---|
212 | static inline uint64_t mavlink_msg_actuator_control_target_get_time_usec(const mavlink_message_t* msg) |
---|
213 | { |
---|
214 | return _MAV_RETURN_uint64_t(msg, 0); |
---|
215 | } |
---|
216 | |
---|
217 | /** |
---|
218 | * @brief Get field group_mlx from actuator_control_target message |
---|
219 | * |
---|
220 | * @return Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. |
---|
221 | */ |
---|
222 | static inline uint8_t mavlink_msg_actuator_control_target_get_group_mlx(const mavlink_message_t* msg) |
---|
223 | { |
---|
224 | return _MAV_RETURN_uint8_t(msg, 40); |
---|
225 | } |
---|
226 | |
---|
227 | /** |
---|
228 | * @brief Get field controls from actuator_control_target message |
---|
229 | * |
---|
230 | * @return Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. |
---|
231 | */ |
---|
232 | static inline uint16_t mavlink_msg_actuator_control_target_get_controls(const mavlink_message_t* msg, float *controls) |
---|
233 | { |
---|
234 | return _MAV_RETURN_float_array(msg, controls, 8, 8); |
---|
235 | } |
---|
236 | |
---|
237 | /** |
---|
238 | * @brief Decode a actuator_control_target message into a struct |
---|
239 | * |
---|
240 | * @param msg The message to decode |
---|
241 | * @param actuator_control_target C-struct to decode the message contents into |
---|
242 | */ |
---|
243 | static inline void mavlink_msg_actuator_control_target_decode(const mavlink_message_t* msg, mavlink_actuator_control_target_t* actuator_control_target) |
---|
244 | { |
---|
245 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS |
---|
246 | actuator_control_target->time_usec = mavlink_msg_actuator_control_target_get_time_usec(msg); |
---|
247 | mavlink_msg_actuator_control_target_get_controls(msg, actuator_control_target->controls); |
---|
248 | actuator_control_target->group_mlx = mavlink_msg_actuator_control_target_get_group_mlx(msg); |
---|
249 | #else |
---|
250 | uint8_t len = msg->len < MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN? msg->len : MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN; |
---|
251 | memset(actuator_control_target, 0, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN); |
---|
252 | memcpy(actuator_control_target, _MAV_PAYLOAD(msg), len); |
---|
253 | #endif |
---|
254 | } |
---|