mavlink_msg_set_actuator_control_target.h
Go to the documentation of this file.
1 // MESSAGE SET_ACTUATOR_CONTROL_TARGET PACKING
2 
3 #define MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET 139
4 
6 {
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  uint8_t target_system; /*< System ID*/
11  uint8_t target_component; /*< Component ID*/
13 
14 #define MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN 43
15 #define MAVLINK_MSG_ID_139_LEN 43
16 
17 #define MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_CRC 168
18 #define MAVLINK_MSG_ID_139_CRC 168
19 
20 #define MAVLINK_MSG_SET_ACTUATOR_CONTROL_TARGET_FIELD_CONTROLS_LEN 8
21 
22 #define MAVLINK_MESSAGE_INFO_SET_ACTUATOR_CONTROL_TARGET { \
23  "SET_ACTUATOR_CONTROL_TARGET", \
24  5, \
25  { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_set_actuator_control_target_t, time_usec) }, \
26  { "controls", NULL, MAVLINK_TYPE_FLOAT, 8, 8, offsetof(mavlink_set_actuator_control_target_t, controls) }, \
27  { "group_mlx", NULL, MAVLINK_TYPE_UINT8_T, 0, 40, offsetof(mavlink_set_actuator_control_target_t, group_mlx) }, \
28  { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 41, offsetof(mavlink_set_actuator_control_target_t, target_system) }, \
29  { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_set_actuator_control_target_t, target_component) }, \
30  } \
31 }
32 
33 
47 static inline uint16_t mavlink_msg_set_actuator_control_target_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
48  uint64_t time_usec, uint8_t group_mlx, uint8_t target_system, uint8_t target_component, const float *controls)
49 {
50 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
52  _mav_put_uint64_t(buf, 0, time_usec);
53  _mav_put_uint8_t(buf, 40, group_mlx);
54  _mav_put_uint8_t(buf, 41, target_system);
55  _mav_put_uint8_t(buf, 42, target_component);
56  _mav_put_float_array(buf, 8, controls, 8);
58 #else
60  packet.time_usec = time_usec;
61  packet.group_mlx = group_mlx;
64  mav_array_memcpy(packet.controls, controls, sizeof(float)*8);
66 #endif
67 
69 #if MAVLINK_CRC_EXTRA
71 #else
73 #endif
74 }
75 
89 static inline uint16_t mavlink_msg_set_actuator_control_target_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
90  mavlink_message_t* msg,
91  uint64_t time_usec,uint8_t group_mlx,uint8_t target_system,uint8_t target_component,const float *controls)
92 {
93 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
95  _mav_put_uint64_t(buf, 0, time_usec);
96  _mav_put_uint8_t(buf, 40, group_mlx);
97  _mav_put_uint8_t(buf, 41, target_system);
98  _mav_put_uint8_t(buf, 42, target_component);
99  _mav_put_float_array(buf, 8, controls, 8);
101 #else
103  packet.time_usec = time_usec;
104  packet.group_mlx = group_mlx;
105  packet.target_system = target_system;
107  mav_array_memcpy(packet.controls, controls, sizeof(float)*8);
109 #endif
110 
112 #if MAVLINK_CRC_EXTRA
114 #else
115  return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN);
116 #endif
117 }
118 
127 static inline uint16_t mavlink_msg_set_actuator_control_target_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_actuator_control_target_t* set_actuator_control_target)
128 {
129  return mavlink_msg_set_actuator_control_target_pack(system_id, component_id, msg, set_actuator_control_target->time_usec, set_actuator_control_target->group_mlx, set_actuator_control_target->target_system, set_actuator_control_target->target_component, set_actuator_control_target->controls);
130 }
131 
141 static inline uint16_t mavlink_msg_set_actuator_control_target_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_actuator_control_target_t* set_actuator_control_target)
142 {
143  return mavlink_msg_set_actuator_control_target_pack_chan(system_id, component_id, chan, msg, set_actuator_control_target->time_usec, set_actuator_control_target->group_mlx, set_actuator_control_target->target_system, set_actuator_control_target->target_component, set_actuator_control_target->controls);
144 }
145 
156 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
157 
158 static inline void mavlink_msg_set_actuator_control_target_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t group_mlx, uint8_t target_system, uint8_t target_component, const float *controls)
159 {
160 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
162  _mav_put_uint64_t(buf, 0, time_usec);
163  _mav_put_uint8_t(buf, 40, group_mlx);
166  _mav_put_float_array(buf, 8, controls, 8);
167 #if MAVLINK_CRC_EXTRA
169 #else
171 #endif
172 #else
174  packet.time_usec = time_usec;
175  packet.group_mlx = group_mlx;
176  packet.target_system = target_system;
178  mav_array_memcpy(packet.controls, controls, sizeof(float)*8);
179 #if MAVLINK_CRC_EXTRA
181 #else
182  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET, (const char *)&packet, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN);
183 #endif
184 #endif
185 }
186 
187 #if MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN <= MAVLINK_MAX_PAYLOAD_LEN
188 /*
189  This varient of _send() can be used to save stack space by re-using
190  memory from the receive buffer. The caller provides a
191  mavlink_message_t which is the size of a full mavlink message. This
192  is usually the receive buffer for the channel, and allows a reply to an
193  incoming message with minimum stack space usage.
194  */
195 static inline void mavlink_msg_set_actuator_control_target_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint8_t group_mlx, uint8_t target_system, uint8_t target_component, const float *controls)
196 {
197 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
198  char *buf = (char *)msgbuf;
199  _mav_put_uint64_t(buf, 0, time_usec);
200  _mav_put_uint8_t(buf, 40, group_mlx);
203  _mav_put_float_array(buf, 8, controls, 8);
204 #if MAVLINK_CRC_EXTRA
206 #else
208 #endif
209 #else
211  packet->time_usec = time_usec;
212  packet->group_mlx = group_mlx;
213  packet->target_system = target_system;
215  mav_array_memcpy(packet->controls, controls, sizeof(float)*8);
216 #if MAVLINK_CRC_EXTRA
218 #else
219  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET, (const char *)packet, MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN);
220 #endif
221 #endif
222 }
223 #endif
224 
225 #endif
226 
227 // MESSAGE SET_ACTUATOR_CONTROL_TARGET UNPACKING
228 
229 
235 static inline uint64_t mavlink_msg_set_actuator_control_target_get_time_usec(const mavlink_message_t* msg)
236 {
237  return _MAV_RETURN_uint64_t(msg, 0);
238 }
239 
245 static inline uint8_t mavlink_msg_set_actuator_control_target_get_group_mlx(const mavlink_message_t* msg)
246 {
247  return _MAV_RETURN_uint8_t(msg, 40);
248 }
249 
255 static inline uint8_t mavlink_msg_set_actuator_control_target_get_target_system(const mavlink_message_t* msg)
256 {
257  return _MAV_RETURN_uint8_t(msg, 41);
258 }
259 
265 static inline uint8_t mavlink_msg_set_actuator_control_target_get_target_component(const mavlink_message_t* msg)
266 {
267  return _MAV_RETURN_uint8_t(msg, 42);
268 }
269 
275 static inline uint16_t mavlink_msg_set_actuator_control_target_get_controls(const mavlink_message_t* msg, float *controls)
276 {
277  return _MAV_RETURN_float_array(msg, controls, 8, 8);
278 }
279 
286 static inline void mavlink_msg_set_actuator_control_target_decode(const mavlink_message_t* msg, mavlink_set_actuator_control_target_t* set_actuator_control_target)
287 {
288 #if MAVLINK_NEED_BYTE_SWAP
289  set_actuator_control_target->time_usec = mavlink_msg_set_actuator_control_target_get_time_usec(msg);
290  mavlink_msg_set_actuator_control_target_get_controls(msg, set_actuator_control_target->controls);
291  set_actuator_control_target->group_mlx = mavlink_msg_set_actuator_control_target_get_group_mlx(msg);
294 #else
295  memcpy(set_actuator_control_target, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SET_ACTUATOR_CONTROL_TARGET_LEN);
296 #endif
297 }
#define _MAV_RETURN_uint8_t(msg, wire_offset)
Definition: protocol.h:244
#define _mav_put_uint8_t(buf, wire_offset, b)
Definition: protocol.h:140
#define _mav_put_uint64_t(buf, wire_offset, b)
Definition: protocol.h:149
static void mav_array_memcpy(void *dest, const void *src, size_t n)
Definition: protocol.h:176


rosflight
Author(s): Daniel Koch , James Jackson
autogenerated on Wed Jul 3 2019 20:00:13