NinjaFlight
 All Data Structures Files Functions Variables Typedefs Enumerations Enumerator Macros Groups Pages
mavlink_msg_sens_batmon.h
Go to the documentation of this file.
1 // MESSAGE SENS_BATMON PACKING
2 
3 #define MAVLINK_MSG_ID_SENS_BATMON 209
4 
5 typedef struct __mavlink_sens_batmon_t
6 {
7  uint16_t temperature;
8  uint16_t voltage;
9  uint16_t current;
10  uint16_t batterystatus;
11  uint16_t serialnumber;
12  uint16_t hostfetcontrol;
13  uint16_t cellvoltage1;
14  uint16_t cellvoltage2;
15  uint16_t cellvoltage3;
16  uint16_t cellvoltage4;
17  uint16_t cellvoltage5;
18  uint16_t cellvoltage6;
20 
21 #define MAVLINK_MSG_ID_SENS_BATMON_LEN 24
22 #define MAVLINK_MSG_ID_209_LEN 24
23 
24 #define MAVLINK_MSG_ID_SENS_BATMON_CRC 12
25 #define MAVLINK_MSG_ID_209_CRC 12
26 
27 
28 
29 #define MAVLINK_MESSAGE_INFO_SENS_BATMON { \
30  "SENS_BATMON", \
31  12, \
32  { { "temperature", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_sens_batmon_t, temperature) }, \
33  { "voltage", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_sens_batmon_t, voltage) }, \
34  { "current", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_sens_batmon_t, current) }, \
35  { "batterystatus", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_sens_batmon_t, batterystatus) }, \
36  { "serialnumber", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_sens_batmon_t, serialnumber) }, \
37  { "hostfetcontrol", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_sens_batmon_t, hostfetcontrol) }, \
38  { "cellvoltage1", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_sens_batmon_t, cellvoltage1) }, \
39  { "cellvoltage2", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_sens_batmon_t, cellvoltage2) }, \
40  { "cellvoltage3", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_sens_batmon_t, cellvoltage3) }, \
41  { "cellvoltage4", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_sens_batmon_t, cellvoltage4) }, \
42  { "cellvoltage5", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_sens_batmon_t, cellvoltage5) }, \
43  { "cellvoltage6", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_sens_batmon_t, cellvoltage6) }, \
44  } \
45 }
46 
47 
68 static inline uint16_t mavlink_msg_sens_batmon_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
69  uint16_t temperature, uint16_t voltage, uint16_t current, uint16_t batterystatus, uint16_t serialnumber, uint16_t hostfetcontrol, uint16_t cellvoltage1, uint16_t cellvoltage2, uint16_t cellvoltage3, uint16_t cellvoltage4, uint16_t cellvoltage5, uint16_t cellvoltage6)
70 {
71 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
73  _mav_put_uint16_t(buf, 0, temperature);
74  _mav_put_uint16_t(buf, 2, voltage);
75  _mav_put_uint16_t(buf, 4, current);
76  _mav_put_uint16_t(buf, 6, batterystatus);
77  _mav_put_uint16_t(buf, 8, serialnumber);
78  _mav_put_uint16_t(buf, 10, hostfetcontrol);
79  _mav_put_uint16_t(buf, 12, cellvoltage1);
80  _mav_put_uint16_t(buf, 14, cellvoltage2);
81  _mav_put_uint16_t(buf, 16, cellvoltage3);
82  _mav_put_uint16_t(buf, 18, cellvoltage4);
83  _mav_put_uint16_t(buf, 20, cellvoltage5);
84  _mav_put_uint16_t(buf, 22, cellvoltage6);
85 
87 #else
88  mavlink_sens_batmon_t packet;
89  packet.temperature = temperature;
90  packet.voltage = voltage;
91  packet.current = current;
92  packet.batterystatus = batterystatus;
93  packet.serialnumber = serialnumber;
94  packet.hostfetcontrol = hostfetcontrol;
95  packet.cellvoltage1 = cellvoltage1;
96  packet.cellvoltage2 = cellvoltage2;
97  packet.cellvoltage3 = cellvoltage3;
98  packet.cellvoltage4 = cellvoltage4;
99  packet.cellvoltage5 = cellvoltage5;
100  packet.cellvoltage6 = cellvoltage6;
101 
103 #endif
104 
105  msg->msgid = MAVLINK_MSG_ID_SENS_BATMON;
106 #if MAVLINK_CRC_EXTRA
108 #else
109  return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SENS_BATMON_LEN);
110 #endif
111 }
112 
133 static inline uint16_t mavlink_msg_sens_batmon_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
134  mavlink_message_t* msg,
135  uint16_t temperature,uint16_t voltage,uint16_t current,uint16_t batterystatus,uint16_t serialnumber,uint16_t hostfetcontrol,uint16_t cellvoltage1,uint16_t cellvoltage2,uint16_t cellvoltage3,uint16_t cellvoltage4,uint16_t cellvoltage5,uint16_t cellvoltage6)
136 {
137 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
139  _mav_put_uint16_t(buf, 0, temperature);
140  _mav_put_uint16_t(buf, 2, voltage);
141  _mav_put_uint16_t(buf, 4, current);
142  _mav_put_uint16_t(buf, 6, batterystatus);
143  _mav_put_uint16_t(buf, 8, serialnumber);
144  _mav_put_uint16_t(buf, 10, hostfetcontrol);
145  _mav_put_uint16_t(buf, 12, cellvoltage1);
146  _mav_put_uint16_t(buf, 14, cellvoltage2);
147  _mav_put_uint16_t(buf, 16, cellvoltage3);
148  _mav_put_uint16_t(buf, 18, cellvoltage4);
149  _mav_put_uint16_t(buf, 20, cellvoltage5);
150  _mav_put_uint16_t(buf, 22, cellvoltage6);
151 
153 #else
154  mavlink_sens_batmon_t packet;
155  packet.temperature = temperature;
156  packet.voltage = voltage;
157  packet.current = current;
158  packet.batterystatus = batterystatus;
159  packet.serialnumber = serialnumber;
160  packet.hostfetcontrol = hostfetcontrol;
161  packet.cellvoltage1 = cellvoltage1;
162  packet.cellvoltage2 = cellvoltage2;
163  packet.cellvoltage3 = cellvoltage3;
164  packet.cellvoltage4 = cellvoltage4;
165  packet.cellvoltage5 = cellvoltage5;
166  packet.cellvoltage6 = cellvoltage6;
167 
169 #endif
170 
171  msg->msgid = MAVLINK_MSG_ID_SENS_BATMON;
172 #if MAVLINK_CRC_EXTRA
174 #else
175  return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SENS_BATMON_LEN);
176 #endif
177 }
178 
187 static inline uint16_t mavlink_msg_sens_batmon_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_sens_batmon_t* sens_batmon)
188 {
189  return mavlink_msg_sens_batmon_pack(system_id, component_id, msg, sens_batmon->temperature, sens_batmon->voltage, sens_batmon->current, sens_batmon->batterystatus, sens_batmon->serialnumber, sens_batmon->hostfetcontrol, sens_batmon->cellvoltage1, sens_batmon->cellvoltage2, sens_batmon->cellvoltage3, sens_batmon->cellvoltage4, sens_batmon->cellvoltage5, sens_batmon->cellvoltage6);
190 }
191 
201 static inline uint16_t mavlink_msg_sens_batmon_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_sens_batmon_t* sens_batmon)
202 {
203  return mavlink_msg_sens_batmon_pack_chan(system_id, component_id, chan, msg, sens_batmon->temperature, sens_batmon->voltage, sens_batmon->current, sens_batmon->batterystatus, sens_batmon->serialnumber, sens_batmon->hostfetcontrol, sens_batmon->cellvoltage1, sens_batmon->cellvoltage2, sens_batmon->cellvoltage3, sens_batmon->cellvoltage4, sens_batmon->cellvoltage5, sens_batmon->cellvoltage6);
204 }
205 
223 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
224 
225 static inline void mavlink_msg_sens_batmon_send(mavlink_channel_t chan, uint16_t temperature, uint16_t voltage, uint16_t current, uint16_t batterystatus, uint16_t serialnumber, uint16_t hostfetcontrol, uint16_t cellvoltage1, uint16_t cellvoltage2, uint16_t cellvoltage3, uint16_t cellvoltage4, uint16_t cellvoltage5, uint16_t cellvoltage6)
226 {
227 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
229  _mav_put_uint16_t(buf, 0, temperature);
230  _mav_put_uint16_t(buf, 2, voltage);
231  _mav_put_uint16_t(buf, 4, current);
232  _mav_put_uint16_t(buf, 6, batterystatus);
233  _mav_put_uint16_t(buf, 8, serialnumber);
234  _mav_put_uint16_t(buf, 10, hostfetcontrol);
235  _mav_put_uint16_t(buf, 12, cellvoltage1);
236  _mav_put_uint16_t(buf, 14, cellvoltage2);
237  _mav_put_uint16_t(buf, 16, cellvoltage3);
238  _mav_put_uint16_t(buf, 18, cellvoltage4);
239  _mav_put_uint16_t(buf, 20, cellvoltage5);
240  _mav_put_uint16_t(buf, 22, cellvoltage6);
241 
242 #if MAVLINK_CRC_EXTRA
244 #else
245  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENS_BATMON, buf, MAVLINK_MSG_ID_SENS_BATMON_LEN);
246 #endif
247 #else
248  mavlink_sens_batmon_t packet;
249  packet.temperature = temperature;
250  packet.voltage = voltage;
251  packet.current = current;
252  packet.batterystatus = batterystatus;
253  packet.serialnumber = serialnumber;
254  packet.hostfetcontrol = hostfetcontrol;
255  packet.cellvoltage1 = cellvoltage1;
256  packet.cellvoltage2 = cellvoltage2;
257  packet.cellvoltage3 = cellvoltage3;
258  packet.cellvoltage4 = cellvoltage4;
259  packet.cellvoltage5 = cellvoltage5;
260  packet.cellvoltage6 = cellvoltage6;
261 
262 #if MAVLINK_CRC_EXTRA
263  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENS_BATMON, (const char *)&packet, MAVLINK_MSG_ID_SENS_BATMON_LEN, MAVLINK_MSG_ID_SENS_BATMON_CRC);
264 #else
265  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENS_BATMON, (const char *)&packet, MAVLINK_MSG_ID_SENS_BATMON_LEN);
266 #endif
267 #endif
268 }
269 
270 #if MAVLINK_MSG_ID_SENS_BATMON_LEN <= MAVLINK_MAX_PAYLOAD_LEN
271 /*
272  This varient of _send() can be used to save stack space by re-using
273  memory from the receive buffer. The caller provides a
274  mavlink_message_t which is the size of a full mavlink message. This
275  is usually the receive buffer for the channel, and allows a reply to an
276  incoming message with minimum stack space usage.
277  */
278 static inline void mavlink_msg_sens_batmon_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t temperature, uint16_t voltage, uint16_t current, uint16_t batterystatus, uint16_t serialnumber, uint16_t hostfetcontrol, uint16_t cellvoltage1, uint16_t cellvoltage2, uint16_t cellvoltage3, uint16_t cellvoltage4, uint16_t cellvoltage5, uint16_t cellvoltage6)
279 {
280 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
281  char *buf = (char *)msgbuf;
282  _mav_put_uint16_t(buf, 0, temperature);
283  _mav_put_uint16_t(buf, 2, voltage);
284  _mav_put_uint16_t(buf, 4, current);
285  _mav_put_uint16_t(buf, 6, batterystatus);
286  _mav_put_uint16_t(buf, 8, serialnumber);
287  _mav_put_uint16_t(buf, 10, hostfetcontrol);
288  _mav_put_uint16_t(buf, 12, cellvoltage1);
289  _mav_put_uint16_t(buf, 14, cellvoltage2);
290  _mav_put_uint16_t(buf, 16, cellvoltage3);
291  _mav_put_uint16_t(buf, 18, cellvoltage4);
292  _mav_put_uint16_t(buf, 20, cellvoltage5);
293  _mav_put_uint16_t(buf, 22, cellvoltage6);
294 
295 #if MAVLINK_CRC_EXTRA
297 #else
298  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENS_BATMON, buf, MAVLINK_MSG_ID_SENS_BATMON_LEN);
299 #endif
300 #else
301  mavlink_sens_batmon_t *packet = (mavlink_sens_batmon_t *)msgbuf;
302  packet->temperature = temperature;
303  packet->voltage = voltage;
304  packet->current = current;
305  packet->batterystatus = batterystatus;
306  packet->serialnumber = serialnumber;
307  packet->hostfetcontrol = hostfetcontrol;
308  packet->cellvoltage1 = cellvoltage1;
309  packet->cellvoltage2 = cellvoltage2;
310  packet->cellvoltage3 = cellvoltage3;
311  packet->cellvoltage4 = cellvoltage4;
312  packet->cellvoltage5 = cellvoltage5;
313  packet->cellvoltage6 = cellvoltage6;
314 
315 #if MAVLINK_CRC_EXTRA
316  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENS_BATMON, (const char *)packet, MAVLINK_MSG_ID_SENS_BATMON_LEN, MAVLINK_MSG_ID_SENS_BATMON_CRC);
317 #else
318  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENS_BATMON, (const char *)packet, MAVLINK_MSG_ID_SENS_BATMON_LEN);
319 #endif
320 #endif
321 }
322 #endif
323 
324 #endif
325 
326 // MESSAGE SENS_BATMON UNPACKING
327 
328 
334 static inline uint16_t mavlink_msg_sens_batmon_get_temperature(const mavlink_message_t* msg)
335 {
336  return _MAV_RETURN_uint16_t(msg, 0);
337 }
338 
344 static inline uint16_t mavlink_msg_sens_batmon_get_voltage(const mavlink_message_t* msg)
345 {
346  return _MAV_RETURN_uint16_t(msg, 2);
347 }
348 
354 static inline uint16_t mavlink_msg_sens_batmon_get_current(const mavlink_message_t* msg)
355 {
356  return _MAV_RETURN_uint16_t(msg, 4);
357 }
358 
364 static inline uint16_t mavlink_msg_sens_batmon_get_batterystatus(const mavlink_message_t* msg)
365 {
366  return _MAV_RETURN_uint16_t(msg, 6);
367 }
368 
374 static inline uint16_t mavlink_msg_sens_batmon_get_serialnumber(const mavlink_message_t* msg)
375 {
376  return _MAV_RETURN_uint16_t(msg, 8);
377 }
378 
384 static inline uint16_t mavlink_msg_sens_batmon_get_hostfetcontrol(const mavlink_message_t* msg)
385 {
386  return _MAV_RETURN_uint16_t(msg, 10);
387 }
388 
394 static inline uint16_t mavlink_msg_sens_batmon_get_cellvoltage1(const mavlink_message_t* msg)
395 {
396  return _MAV_RETURN_uint16_t(msg, 12);
397 }
398 
404 static inline uint16_t mavlink_msg_sens_batmon_get_cellvoltage2(const mavlink_message_t* msg)
405 {
406  return _MAV_RETURN_uint16_t(msg, 14);
407 }
408 
414 static inline uint16_t mavlink_msg_sens_batmon_get_cellvoltage3(const mavlink_message_t* msg)
415 {
416  return _MAV_RETURN_uint16_t(msg, 16);
417 }
418 
424 static inline uint16_t mavlink_msg_sens_batmon_get_cellvoltage4(const mavlink_message_t* msg)
425 {
426  return _MAV_RETURN_uint16_t(msg, 18);
427 }
428 
434 static inline uint16_t mavlink_msg_sens_batmon_get_cellvoltage5(const mavlink_message_t* msg)
435 {
436  return _MAV_RETURN_uint16_t(msg, 20);
437 }
438 
444 static inline uint16_t mavlink_msg_sens_batmon_get_cellvoltage6(const mavlink_message_t* msg)
445 {
446  return _MAV_RETURN_uint16_t(msg, 22);
447 }
448 
455 static inline void mavlink_msg_sens_batmon_decode(const mavlink_message_t* msg, mavlink_sens_batmon_t* sens_batmon)
456 {
457 #if MAVLINK_NEED_BYTE_SWAP
458  sens_batmon->temperature = mavlink_msg_sens_batmon_get_temperature(msg);
459  sens_batmon->voltage = mavlink_msg_sens_batmon_get_voltage(msg);
460  sens_batmon->current = mavlink_msg_sens_batmon_get_current(msg);
461  sens_batmon->batterystatus = mavlink_msg_sens_batmon_get_batterystatus(msg);
462  sens_batmon->serialnumber = mavlink_msg_sens_batmon_get_serialnumber(msg);
463  sens_batmon->hostfetcontrol = mavlink_msg_sens_batmon_get_hostfetcontrol(msg);
464  sens_batmon->cellvoltage1 = mavlink_msg_sens_batmon_get_cellvoltage1(msg);
465  sens_batmon->cellvoltage2 = mavlink_msg_sens_batmon_get_cellvoltage2(msg);
466  sens_batmon->cellvoltage3 = mavlink_msg_sens_batmon_get_cellvoltage3(msg);
467  sens_batmon->cellvoltage4 = mavlink_msg_sens_batmon_get_cellvoltage4(msg);
468  sens_batmon->cellvoltage5 = mavlink_msg_sens_batmon_get_cellvoltage5(msg);
469  sens_batmon->cellvoltage6 = mavlink_msg_sens_batmon_get_cellvoltage6(msg);
470 #else
471  memcpy(sens_batmon, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SENS_BATMON_LEN);
472 #endif
473 }
#define _mav_put_uint16_t(buf, wire_offset, b)
Definition: protocol.h:139