mavlink_msg_battery_status.h
Go to the documentation of this file.
1 // MESSAGE BATTERY_STATUS PACKING
2 
3 #define MAVLINK_MSG_ID_BATTERY_STATUS 147
4 
6 {
7  int32_t current_consumed; /*< Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide mAh consumption estimate*/
8  int32_t energy_consumed; /*< Consumed energy, in 100*Joules (intergrated U*I*dt) (1 = 100 Joule), -1: autopilot does not provide energy consumption estimate*/
9  int16_t temperature; /*< Temperature of the battery in centi-degrees celsius. INT16_MAX for unknown temperature.*/
10  uint16_t voltages[10]; /*< Battery voltage of cells, in millivolts (1 = 1 millivolt). Cells above the valid cell count for this battery should have the UINT16_MAX value.*/
11  int16_t current_battery; /*< Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current*/
12  uint8_t id; /*< Battery ID*/
13  uint8_t battery_function; /*< Function of the battery*/
14  uint8_t type; /*< Type (chemistry) of the battery*/
15  int8_t battery_remaining; /*< Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery*/
17 
18 #define MAVLINK_MSG_ID_BATTERY_STATUS_LEN 36
19 #define MAVLINK_MSG_ID_147_LEN 36
20 
21 #define MAVLINK_MSG_ID_BATTERY_STATUS_CRC 154
22 #define MAVLINK_MSG_ID_147_CRC 154
23 
24 #define MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_LEN 10
25 
26 #define MAVLINK_MESSAGE_INFO_BATTERY_STATUS { \
27  "BATTERY_STATUS", \
28  9, \
29  { { "current_consumed", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_battery_status_t, current_consumed) }, \
30  { "energy_consumed", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_battery_status_t, energy_consumed) }, \
31  { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_battery_status_t, temperature) }, \
32  { "voltages", NULL, MAVLINK_TYPE_UINT16_T, 10, 10, offsetof(mavlink_battery_status_t, voltages) }, \
33  { "current_battery", NULL, MAVLINK_TYPE_INT16_T, 0, 30, offsetof(mavlink_battery_status_t, current_battery) }, \
34  { "id", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_battery_status_t, id) }, \
35  { "battery_function", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_battery_status_t, battery_function) }, \
36  { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_battery_status_t, type) }, \
37  { "battery_remaining", NULL, MAVLINK_TYPE_INT8_T, 0, 35, offsetof(mavlink_battery_status_t, battery_remaining) }, \
38  } \
39 }
40 
41 
59 static inline uint16_t mavlink_msg_battery_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
60  uint8_t id, uint8_t battery_function, uint8_t type, int16_t temperature, const uint16_t *voltages, int16_t current_battery, int32_t current_consumed, int32_t energy_consumed, int8_t battery_remaining)
61 {
62 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
64  _mav_put_int32_t(buf, 0, current_consumed);
65  _mav_put_int32_t(buf, 4, energy_consumed);
66  _mav_put_int16_t(buf, 8, temperature);
67  _mav_put_int16_t(buf, 30, current_battery);
68  _mav_put_uint8_t(buf, 32, id);
69  _mav_put_uint8_t(buf, 33, battery_function);
70  _mav_put_uint8_t(buf, 34, type);
71  _mav_put_int8_t(buf, 35, battery_remaining);
72  _mav_put_uint16_t_array(buf, 10, voltages, 10);
74 #else
78  packet.temperature = temperature;
80  packet.id = id;
82  packet.type = type;
84  mav_array_memcpy(packet.voltages, voltages, sizeof(uint16_t)*10);
86 #endif
87 
88  msg->msgid = MAVLINK_MSG_ID_BATTERY_STATUS;
89 #if MAVLINK_CRC_EXTRA
91 #else
92  return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_BATTERY_STATUS_LEN);
93 #endif
94 }
95 
113 static inline uint16_t mavlink_msg_battery_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
114  mavlink_message_t* msg,
115  uint8_t id,uint8_t battery_function,uint8_t type,int16_t temperature,const uint16_t *voltages,int16_t current_battery,int32_t current_consumed,int32_t energy_consumed,int8_t battery_remaining)
116 {
117 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
119  _mav_put_int32_t(buf, 0, current_consumed);
120  _mav_put_int32_t(buf, 4, energy_consumed);
121  _mav_put_int16_t(buf, 8, temperature);
122  _mav_put_int16_t(buf, 30, current_battery);
123  _mav_put_uint8_t(buf, 32, id);
124  _mav_put_uint8_t(buf, 33, battery_function);
125  _mav_put_uint8_t(buf, 34, type);
126  _mav_put_int8_t(buf, 35, battery_remaining);
127  _mav_put_uint16_t_array(buf, 10, voltages, 10);
129 #else
133  packet.temperature = temperature;
135  packet.id = id;
137  packet.type = type;
139  mav_array_memcpy(packet.voltages, voltages, sizeof(uint16_t)*10);
141 #endif
142 
143  msg->msgid = MAVLINK_MSG_ID_BATTERY_STATUS;
144 #if MAVLINK_CRC_EXTRA
146 #else
147  return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_BATTERY_STATUS_LEN);
148 #endif
149 }
150 
159 static inline uint16_t mavlink_msg_battery_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_battery_status_t* battery_status)
160 {
161  return mavlink_msg_battery_status_pack(system_id, component_id, msg, battery_status->id, battery_status->battery_function, battery_status->type, battery_status->temperature, battery_status->voltages, battery_status->current_battery, battery_status->current_consumed, battery_status->energy_consumed, battery_status->battery_remaining);
162 }
163 
173 static inline uint16_t mavlink_msg_battery_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_battery_status_t* battery_status)
174 {
175  return mavlink_msg_battery_status_pack_chan(system_id, component_id, chan, msg, battery_status->id, battery_status->battery_function, battery_status->type, battery_status->temperature, battery_status->voltages, battery_status->current_battery, battery_status->current_consumed, battery_status->energy_consumed, battery_status->battery_remaining);
176 }
177 
192 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
193 
194 static inline void mavlink_msg_battery_status_send(mavlink_channel_t chan, uint8_t id, uint8_t battery_function, uint8_t type, int16_t temperature, const uint16_t *voltages, int16_t current_battery, int32_t current_consumed, int32_t energy_consumed, int8_t battery_remaining)
195 {
196 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
200  _mav_put_int16_t(buf, 8, temperature);
202  _mav_put_uint8_t(buf, 32, id);
204  _mav_put_uint8_t(buf, 34, type);
205  _mav_put_int8_t(buf, 35, battery_remaining);
206  _mav_put_uint16_t_array(buf, 10, voltages, 10);
207 #if MAVLINK_CRC_EXTRA
209 #else
210  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY_STATUS, buf, MAVLINK_MSG_ID_BATTERY_STATUS_LEN);
211 #endif
212 #else
216  packet.temperature = temperature;
218  packet.id = id;
220  packet.type = type;
222  mav_array_memcpy(packet.voltages, voltages, sizeof(uint16_t)*10);
223 #if MAVLINK_CRC_EXTRA
224  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY_STATUS, (const char *)&packet, MAVLINK_MSG_ID_BATTERY_STATUS_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_CRC);
225 #else
226  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY_STATUS, (const char *)&packet, MAVLINK_MSG_ID_BATTERY_STATUS_LEN);
227 #endif
228 #endif
229 }
230 
231 #if MAVLINK_MSG_ID_BATTERY_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
232 /*
233  This varient of _send() can be used to save stack space by re-using
234  memory from the receive buffer. The caller provides a
235  mavlink_message_t which is the size of a full mavlink message. This
236  is usually the receive buffer for the channel, and allows a reply to an
237  incoming message with minimum stack space usage.
238  */
239 static inline void mavlink_msg_battery_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t id, uint8_t battery_function, uint8_t type, int16_t temperature, const uint16_t *voltages, int16_t current_battery, int32_t current_consumed, int32_t energy_consumed, int8_t battery_remaining)
240 {
241 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
242  char *buf = (char *)msgbuf;
245  _mav_put_int16_t(buf, 8, temperature);
247  _mav_put_uint8_t(buf, 32, id);
249  _mav_put_uint8_t(buf, 34, type);
250  _mav_put_int8_t(buf, 35, battery_remaining);
251  _mav_put_uint16_t_array(buf, 10, voltages, 10);
252 #if MAVLINK_CRC_EXTRA
254 #else
255  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY_STATUS, buf, MAVLINK_MSG_ID_BATTERY_STATUS_LEN);
256 #endif
257 #else
261  packet->temperature = temperature;
263  packet->id = id;
265  packet->type = type;
267  mav_array_memcpy(packet->voltages, voltages, sizeof(uint16_t)*10);
268 #if MAVLINK_CRC_EXTRA
269  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY_STATUS, (const char *)packet, MAVLINK_MSG_ID_BATTERY_STATUS_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_CRC);
270 #else
271  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY_STATUS, (const char *)packet, MAVLINK_MSG_ID_BATTERY_STATUS_LEN);
272 #endif
273 #endif
274 }
275 #endif
276 
277 #endif
278 
279 // MESSAGE BATTERY_STATUS UNPACKING
280 
281 
287 static inline uint8_t mavlink_msg_battery_status_get_id(const mavlink_message_t* msg)
288 {
289  return _MAV_RETURN_uint8_t(msg, 32);
290 }
291 
297 static inline uint8_t mavlink_msg_battery_status_get_battery_function(const mavlink_message_t* msg)
298 {
299  return _MAV_RETURN_uint8_t(msg, 33);
300 }
301 
307 static inline uint8_t mavlink_msg_battery_status_get_type(const mavlink_message_t* msg)
308 {
309  return _MAV_RETURN_uint8_t(msg, 34);
310 }
311 
317 static inline int16_t mavlink_msg_battery_status_get_temperature(const mavlink_message_t* msg)
318 {
319  return _MAV_RETURN_int16_t(msg, 8);
320 }
321 
327 static inline uint16_t mavlink_msg_battery_status_get_voltages(const mavlink_message_t* msg, uint16_t *voltages)
328 {
329  return _MAV_RETURN_uint16_t_array(msg, voltages, 10, 10);
330 }
331 
337 static inline int16_t mavlink_msg_battery_status_get_current_battery(const mavlink_message_t* msg)
338 {
339  return _MAV_RETURN_int16_t(msg, 30);
340 }
341 
347 static inline int32_t mavlink_msg_battery_status_get_current_consumed(const mavlink_message_t* msg)
348 {
349  return _MAV_RETURN_int32_t(msg, 0);
350 }
351 
357 static inline int32_t mavlink_msg_battery_status_get_energy_consumed(const mavlink_message_t* msg)
358 {
359  return _MAV_RETURN_int32_t(msg, 4);
360 }
361 
367 static inline int8_t mavlink_msg_battery_status_get_battery_remaining(const mavlink_message_t* msg)
368 {
369  return _MAV_RETURN_int8_t(msg, 35);
370 }
371 
378 static inline void mavlink_msg_battery_status_decode(const mavlink_message_t* msg, mavlink_battery_status_t* battery_status)
379 {
380 #if MAVLINK_NEED_BYTE_SWAP
386  battery_status->id = mavlink_msg_battery_status_get_id(msg);
388  battery_status->type = mavlink_msg_battery_status_get_type(msg);
390 #else
391  memcpy(battery_status, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_BATTERY_STATUS_LEN);
392 #endif
393 }
#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_int32_t(buf, wire_offset, b)
Definition: protocol.h:148
#define _MAV_RETURN_int8_t(msg, wire_offset)
Definition: protocol.h:243
#define _mav_put_int8_t(buf, wire_offset, b)
Definition: protocol.h:141
static void mav_array_memcpy(void *dest, const void *src, size_t n)
Definition: protocol.h:176
#define _mav_put_int16_t(buf, wire_offset, b)
Definition: protocol.h:146


rosflight_firmware
Author(s): Daniel Koch , James Jackson
autogenerated on Thu Apr 15 2021 05:07:46