mavlink_msg_actuator_control_target.h
Go to the documentation of this file.
1 // MESSAGE ACTUATOR_CONTROL_TARGET PACKING
2 
3 #define MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET 140
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.*/
11 
12 #define MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN 41
13 #define MAVLINK_MSG_ID_140_LEN 41
14 
15 #define MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_CRC 181
16 #define MAVLINK_MSG_ID_140_CRC 181
17 
18 #define MAVLINK_MSG_ACTUATOR_CONTROL_TARGET_FIELD_CONTROLS_LEN 8
19 
20 #define MAVLINK_MESSAGE_INFO_ACTUATOR_CONTROL_TARGET { \
21  "ACTUATOR_CONTROL_TARGET", \
22  3, \
23  { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_actuator_control_target_t, time_usec) }, \
24  { "controls", NULL, MAVLINK_TYPE_FLOAT, 8, 8, offsetof(mavlink_actuator_control_target_t, controls) }, \
25  { "group_mlx", NULL, MAVLINK_TYPE_UINT8_T, 0, 40, offsetof(mavlink_actuator_control_target_t, group_mlx) }, \
26  } \
27 }
28 
29 
41 static inline uint16_t mavlink_msg_actuator_control_target_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
42  uint64_t time_usec, uint8_t group_mlx, const float *controls)
43 {
44 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
46  _mav_put_uint64_t(buf, 0, time_usec);
47  _mav_put_uint8_t(buf, 40, group_mlx);
48  _mav_put_float_array(buf, 8, controls, 8);
50 #else
52  packet.time_usec = time_usec;
53  packet.group_mlx = group_mlx;
54  mav_array_memcpy(packet.controls, controls, sizeof(float)*8);
56 #endif
57 
59 #if MAVLINK_CRC_EXTRA
61 #else
62  return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN);
63 #endif
64 }
65 
77 static inline uint16_t mavlink_msg_actuator_control_target_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
78  mavlink_message_t* msg,
79  uint64_t time_usec,uint8_t group_mlx,const float *controls)
80 {
81 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
83  _mav_put_uint64_t(buf, 0, time_usec);
84  _mav_put_uint8_t(buf, 40, group_mlx);
85  _mav_put_float_array(buf, 8, controls, 8);
87 #else
89  packet.time_usec = time_usec;
90  packet.group_mlx = group_mlx;
91  mav_array_memcpy(packet.controls, controls, sizeof(float)*8);
93 #endif
94 
96 #if MAVLINK_CRC_EXTRA
98 #else
99  return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN);
100 #endif
101 }
102 
111 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)
112 {
113  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);
114 }
115 
125 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)
126 {
127  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);
128 }
129 
138 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
139 
140 static inline void mavlink_msg_actuator_control_target_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t group_mlx, const float *controls)
141 {
142 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
144  _mav_put_uint64_t(buf, 0, time_usec);
145  _mav_put_uint8_t(buf, 40, group_mlx);
146  _mav_put_float_array(buf, 8, controls, 8);
147 #if MAVLINK_CRC_EXTRA
149 #else
150  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET, buf, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN);
151 #endif
152 #else
154  packet.time_usec = time_usec;
155  packet.group_mlx = group_mlx;
156  mav_array_memcpy(packet.controls, controls, sizeof(float)*8);
157 #if MAVLINK_CRC_EXTRA
159 #else
160  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET, (const char *)&packet, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN);
161 #endif
162 #endif
163 }
164 
165 #if MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN <= MAVLINK_MAX_PAYLOAD_LEN
166 /*
167  This varient of _send() can be used to save stack space by re-using
168  memory from the receive buffer. The caller provides a
169  mavlink_message_t which is the size of a full mavlink message. This
170  is usually the receive buffer for the channel, and allows a reply to an
171  incoming message with minimum stack space usage.
172  */
173 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)
174 {
175 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
176  char *buf = (char *)msgbuf;
177  _mav_put_uint64_t(buf, 0, time_usec);
178  _mav_put_uint8_t(buf, 40, group_mlx);
179  _mav_put_float_array(buf, 8, controls, 8);
180 #if MAVLINK_CRC_EXTRA
182 #else
183  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET, buf, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN);
184 #endif
185 #else
187  packet->time_usec = time_usec;
188  packet->group_mlx = group_mlx;
189  mav_array_memcpy(packet->controls, controls, sizeof(float)*8);
190 #if MAVLINK_CRC_EXTRA
192 #else
193  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET, (const char *)packet, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN);
194 #endif
195 #endif
196 }
197 #endif
198 
199 #endif
200 
201 // MESSAGE ACTUATOR_CONTROL_TARGET UNPACKING
202 
203 
209 static inline uint64_t mavlink_msg_actuator_control_target_get_time_usec(const mavlink_message_t* msg)
210 {
211  return _MAV_RETURN_uint64_t(msg, 0);
212 }
213 
219 static inline uint8_t mavlink_msg_actuator_control_target_get_group_mlx(const mavlink_message_t* msg)
220 {
221  return _MAV_RETURN_uint8_t(msg, 40);
222 }
223 
229 static inline uint16_t mavlink_msg_actuator_control_target_get_controls(const mavlink_message_t* msg, float *controls)
230 {
231  return _MAV_RETURN_float_array(msg, controls, 8, 8);
232 }
233 
240 static inline void mavlink_msg_actuator_control_target_decode(const mavlink_message_t* msg, mavlink_actuator_control_target_t* actuator_control_target)
241 {
242 #if MAVLINK_NEED_BYTE_SWAP
243  actuator_control_target->time_usec = mavlink_msg_actuator_control_target_get_time_usec(msg);
244  mavlink_msg_actuator_control_target_get_controls(msg, actuator_control_target->controls);
245  actuator_control_target->group_mlx = mavlink_msg_actuator_control_target_get_group_mlx(msg);
246 #else
247  memcpy(actuator_control_target, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN);
248 #endif
249 }
#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:12