2 // MESSAGE HIL_ACTUATOR_CONTROLS PACKING
4 #define MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS 93
7 typedef struct __mavlink_hil_actuator_controls_t
{
8 uint64_t time_usec
; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/
9 uint64_t flags
; /*< Flags as bitfield, 1: indicate simulation using lockstep.*/
10 float controls
[16]; /*< Control outputs -1 .. 1. Channel assignment depends on the simulated hardware.*/
11 uint8_t mode
; /*< System mode. Includes arming state.*/
12 } mavlink_hil_actuator_controls_t
;
14 #define MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_LEN 81
15 #define MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_MIN_LEN 81
16 #define MAVLINK_MSG_ID_93_LEN 81
17 #define MAVLINK_MSG_ID_93_MIN_LEN 81
19 #define MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_CRC 47
20 #define MAVLINK_MSG_ID_93_CRC 47
22 #define MAVLINK_MSG_HIL_ACTUATOR_CONTROLS_FIELD_CONTROLS_LEN 16
24 #if MAVLINK_COMMAND_24BIT
25 #define MAVLINK_MESSAGE_INFO_HIL_ACTUATOR_CONTROLS { \
27 "HIL_ACTUATOR_CONTROLS", \
29 { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_actuator_controls_t, time_usec) }, \
30 { "controls", NULL, MAVLINK_TYPE_FLOAT, 16, 16, offsetof(mavlink_hil_actuator_controls_t, controls) }, \
31 { "mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 80, offsetof(mavlink_hil_actuator_controls_t, mode) }, \
32 { "flags", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_hil_actuator_controls_t, flags) }, \
36 #define MAVLINK_MESSAGE_INFO_HIL_ACTUATOR_CONTROLS { \
37 "HIL_ACTUATOR_CONTROLS", \
39 { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_actuator_controls_t, time_usec) }, \
40 { "controls", NULL, MAVLINK_TYPE_FLOAT, 16, 16, offsetof(mavlink_hil_actuator_controls_t, controls) }, \
41 { "mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 80, offsetof(mavlink_hil_actuator_controls_t, mode) }, \
42 { "flags", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_hil_actuator_controls_t, flags) }, \
48 * @brief Pack a hil_actuator_controls message
49 * @param system_id ID of this system
50 * @param component_id ID of this component (e.g. 200 for IMU)
51 * @param msg The MAVLink message to compress the data into
53 * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
54 * @param controls Control outputs -1 .. 1. Channel assignment depends on the simulated hardware.
55 * @param mode System mode. Includes arming state.
56 * @param flags Flags as bitfield, 1: indicate simulation using lockstep.
57 * @return length of the message in bytes (excluding serial stream start sign)
59 static inline uint16_t mavlink_msg_hil_actuator_controls_pack(uint8_t system_id
, uint8_t component_id
, mavlink_message_t
* msg
,
60 uint64_t time_usec
, const float *controls
, uint8_t mode
, uint64_t flags
)
62 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
63 char buf
[MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_LEN
];
64 _mav_put_uint64_t(buf
, 0, time_usec
);
65 _mav_put_uint64_t(buf
, 8, flags
);
66 _mav_put_uint8_t(buf
, 80, mode
);
67 _mav_put_float_array(buf
, 16, controls
, 16);
68 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_LEN
);
70 mavlink_hil_actuator_controls_t packet
;
71 packet
.time_usec
= time_usec
;
74 mav_array_memcpy(packet
.controls
, controls
, sizeof(float)*16);
75 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_LEN
);
78 msg
->msgid
= MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS
;
79 return mavlink_finalize_message(msg
, system_id
, component_id
, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_MIN_LEN
, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_LEN
, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_CRC
);
83 * @brief Pack a hil_actuator_controls message on a channel
84 * @param system_id ID of this system
85 * @param component_id ID of this component (e.g. 200 for IMU)
86 * @param chan The MAVLink channel this message will be sent over
87 * @param msg The MAVLink message to compress the data into
88 * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
89 * @param controls Control outputs -1 .. 1. Channel assignment depends on the simulated hardware.
90 * @param mode System mode. Includes arming state.
91 * @param flags Flags as bitfield, 1: indicate simulation using lockstep.
92 * @return length of the message in bytes (excluding serial stream start sign)
94 static inline uint16_t mavlink_msg_hil_actuator_controls_pack_chan(uint8_t system_id
, uint8_t component_id
, uint8_t chan
,
95 mavlink_message_t
* msg
,
96 uint64_t time_usec
,const float *controls
,uint8_t mode
,uint64_t flags
)
98 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
99 char buf
[MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_LEN
];
100 _mav_put_uint64_t(buf
, 0, time_usec
);
101 _mav_put_uint64_t(buf
, 8, flags
);
102 _mav_put_uint8_t(buf
, 80, mode
);
103 _mav_put_float_array(buf
, 16, controls
, 16);
104 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_LEN
);
106 mavlink_hil_actuator_controls_t packet
;
107 packet
.time_usec
= time_usec
;
108 packet
.flags
= flags
;
110 mav_array_memcpy(packet
.controls
, controls
, sizeof(float)*16);
111 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_LEN
);
114 msg
->msgid
= MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS
;
115 return mavlink_finalize_message_chan(msg
, system_id
, component_id
, chan
, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_MIN_LEN
, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_LEN
, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_CRC
);
119 * @brief Encode a hil_actuator_controls struct
121 * @param system_id ID of this system
122 * @param component_id ID of this component (e.g. 200 for IMU)
123 * @param msg The MAVLink message to compress the data into
124 * @param hil_actuator_controls C-struct to read the message contents from
126 static inline uint16_t mavlink_msg_hil_actuator_controls_encode(uint8_t system_id
, uint8_t component_id
, mavlink_message_t
* msg
, const mavlink_hil_actuator_controls_t
* hil_actuator_controls
)
128 return mavlink_msg_hil_actuator_controls_pack(system_id
, component_id
, msg
, hil_actuator_controls
->time_usec
, hil_actuator_controls
->controls
, hil_actuator_controls
->mode
, hil_actuator_controls
->flags
);
132 * @brief Encode a hil_actuator_controls struct on a channel
134 * @param system_id ID of this system
135 * @param component_id ID of this component (e.g. 200 for IMU)
136 * @param chan The MAVLink channel this message will be sent over
137 * @param msg The MAVLink message to compress the data into
138 * @param hil_actuator_controls C-struct to read the message contents from
140 static inline uint16_t mavlink_msg_hil_actuator_controls_encode_chan(uint8_t system_id
, uint8_t component_id
, uint8_t chan
, mavlink_message_t
* msg
, const mavlink_hil_actuator_controls_t
* hil_actuator_controls
)
142 return mavlink_msg_hil_actuator_controls_pack_chan(system_id
, component_id
, chan
, msg
, hil_actuator_controls
->time_usec
, hil_actuator_controls
->controls
, hil_actuator_controls
->mode
, hil_actuator_controls
->flags
);
146 * @brief Send a hil_actuator_controls message
147 * @param chan MAVLink channel to send the message
149 * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
150 * @param controls Control outputs -1 .. 1. Channel assignment depends on the simulated hardware.
151 * @param mode System mode. Includes arming state.
152 * @param flags Flags as bitfield, 1: indicate simulation using lockstep.
154 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
156 static inline void mavlink_msg_hil_actuator_controls_send(mavlink_channel_t chan
, uint64_t time_usec
, const float *controls
, uint8_t mode
, uint64_t flags
)
158 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
159 char buf
[MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_LEN
];
160 _mav_put_uint64_t(buf
, 0, time_usec
);
161 _mav_put_uint64_t(buf
, 8, flags
);
162 _mav_put_uint8_t(buf
, 80, mode
);
163 _mav_put_float_array(buf
, 16, controls
, 16);
164 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS
, buf
, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_MIN_LEN
, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_LEN
, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_CRC
);
166 mavlink_hil_actuator_controls_t packet
;
167 packet
.time_usec
= time_usec
;
168 packet
.flags
= flags
;
170 mav_array_memcpy(packet
.controls
, controls
, sizeof(float)*16);
171 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS
, (const char *)&packet
, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_MIN_LEN
, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_LEN
, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_CRC
);
176 * @brief Send a hil_actuator_controls message
177 * @param chan MAVLink channel to send the message
178 * @param struct The MAVLink struct to serialize
180 static inline void mavlink_msg_hil_actuator_controls_send_struct(mavlink_channel_t chan
, const mavlink_hil_actuator_controls_t
* hil_actuator_controls
)
182 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
183 mavlink_msg_hil_actuator_controls_send(chan
, hil_actuator_controls
->time_usec
, hil_actuator_controls
->controls
, hil_actuator_controls
->mode
, hil_actuator_controls
->flags
);
185 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS
, (const char *)hil_actuator_controls
, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_MIN_LEN
, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_LEN
, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_CRC
);
189 #if MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
191 This varient of _send() can be used to save stack space by re-using
192 memory from the receive buffer. The caller provides a
193 mavlink_message_t which is the size of a full mavlink message. This
194 is usually the receive buffer for the channel, and allows a reply to an
195 incoming message with minimum stack space usage.
197 static inline void mavlink_msg_hil_actuator_controls_send_buf(mavlink_message_t
*msgbuf
, mavlink_channel_t chan
, uint64_t time_usec
, const float *controls
, uint8_t mode
, uint64_t flags
)
199 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
200 char *buf
= (char *)msgbuf
;
201 _mav_put_uint64_t(buf
, 0, time_usec
);
202 _mav_put_uint64_t(buf
, 8, flags
);
203 _mav_put_uint8_t(buf
, 80, mode
);
204 _mav_put_float_array(buf
, 16, controls
, 16);
205 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS
, buf
, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_MIN_LEN
, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_LEN
, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_CRC
);
207 mavlink_hil_actuator_controls_t
*packet
= (mavlink_hil_actuator_controls_t
*)msgbuf
;
208 packet
->time_usec
= time_usec
;
209 packet
->flags
= flags
;
211 mav_array_memcpy(packet
->controls
, controls
, sizeof(float)*16);
212 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS
, (const char *)packet
, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_MIN_LEN
, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_LEN
, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_CRC
);
219 // MESSAGE HIL_ACTUATOR_CONTROLS UNPACKING
223 * @brief Get field time_usec from hil_actuator_controls message
225 * @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
227 static inline uint64_t mavlink_msg_hil_actuator_controls_get_time_usec(const mavlink_message_t
* msg
)
229 return _MAV_RETURN_uint64_t(msg
, 0);
233 * @brief Get field controls from hil_actuator_controls message
235 * @return Control outputs -1 .. 1. Channel assignment depends on the simulated hardware.
237 static inline uint16_t mavlink_msg_hil_actuator_controls_get_controls(const mavlink_message_t
* msg
, float *controls
)
239 return _MAV_RETURN_float_array(msg
, controls
, 16, 16);
243 * @brief Get field mode from hil_actuator_controls message
245 * @return System mode. Includes arming state.
247 static inline uint8_t mavlink_msg_hil_actuator_controls_get_mode(const mavlink_message_t
* msg
)
249 return _MAV_RETURN_uint8_t(msg
, 80);
253 * @brief Get field flags from hil_actuator_controls message
255 * @return Flags as bitfield, 1: indicate simulation using lockstep.
257 static inline uint64_t mavlink_msg_hil_actuator_controls_get_flags(const mavlink_message_t
* msg
)
259 return _MAV_RETURN_uint64_t(msg
, 8);
263 * @brief Decode a hil_actuator_controls message into a struct
265 * @param msg The message to decode
266 * @param hil_actuator_controls C-struct to decode the message contents into
268 static inline void mavlink_msg_hil_actuator_controls_decode(const mavlink_message_t
* msg
, mavlink_hil_actuator_controls_t
* hil_actuator_controls
)
270 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
271 hil_actuator_controls
->time_usec
= mavlink_msg_hil_actuator_controls_get_time_usec(msg
);
272 hil_actuator_controls
->flags
= mavlink_msg_hil_actuator_controls_get_flags(msg
);
273 mavlink_msg_hil_actuator_controls_get_controls(msg
, hil_actuator_controls
->controls
);
274 hil_actuator_controls
->mode
= mavlink_msg_hil_actuator_controls_get_mode(msg
);
276 uint8_t len
= msg
->len
< MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_LEN
? msg
->len
: MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_LEN
;
277 memset(hil_actuator_controls
, 0, MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS_LEN
);
278 memcpy(hil_actuator_controls
, _MAV_PAYLOAD(msg
), len
);