3 #define MAVLINK_MSG_ID_BATTERY_STATUS 147
18 #define MAVLINK_MSG_ID_BATTERY_STATUS_LEN 36
19 #define MAVLINK_MSG_ID_147_LEN 36
21 #define MAVLINK_MSG_ID_BATTERY_STATUS_CRC 154
22 #define MAVLINK_MSG_ID_147_CRC 154
24 #define MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_LEN 10
26 #define MAVLINK_MESSAGE_INFO_BATTERY_STATUS { \
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) }, \
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)
62 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
63 char buf[MAVLINK_MSG_ID_BATTERY_STATUS_LEN];
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);
73 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_BATTERY_STATUS_LEN);
84 mav_array_memcpy(packet.
voltages, voltages,
sizeof(uint16_t)*10);
85 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_BATTERY_STATUS_LEN);
88 msg->msgid = MAVLINK_MSG_ID_BATTERY_STATUS;
90 return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_BATTERY_STATUS_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_CRC);
92 return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_BATTERY_STATUS_LEN);
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)
117 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
118 char buf[MAVLINK_MSG_ID_BATTERY_STATUS_LEN];
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);
128 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_BATTERY_STATUS_LEN);
139 mav_array_memcpy(packet.
voltages, voltages,
sizeof(uint16_t)*10);
140 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_BATTERY_STATUS_LEN);
143 msg->msgid = MAVLINK_MSG_ID_BATTERY_STATUS;
144 #if MAVLINK_CRC_EXTRA
145 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_BATTERY_STATUS_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_CRC);
147 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_BATTERY_STATUS_LEN);
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)
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);
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)
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);
192 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
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)
196 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
197 char buf[MAVLINK_MSG_ID_BATTERY_STATUS_LEN];
198 _mav_put_int32_t(buf, 0, current_consumed);
199 _mav_put_int32_t(buf, 4, energy_consumed);
200 _mav_put_int16_t(buf, 8, temperature);
201 _mav_put_int16_t(buf, 30, current_battery);
202 _mav_put_uint8_t(buf, 32,
id);
203 _mav_put_uint8_t(buf, 33, battery_function);
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
208 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY_STATUS, buf, MAVLINK_MSG_ID_BATTERY_STATUS_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_CRC);
210 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY_STATUS, buf, MAVLINK_MSG_ID_BATTERY_STATUS_LEN);
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);
226 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY_STATUS, (
const char *)&packet, MAVLINK_MSG_ID_BATTERY_STATUS_LEN);
231 #if MAVLINK_MSG_ID_BATTERY_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
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)
241 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
242 char *buf = (
char *)msgbuf;
243 _mav_put_int32_t(buf, 0, current_consumed);
244 _mav_put_int32_t(buf, 4, energy_consumed);
245 _mav_put_int16_t(buf, 8, temperature);
246 _mav_put_int16_t(buf, 30, current_battery);
247 _mav_put_uint8_t(buf, 32,
id);
248 _mav_put_uint8_t(buf, 33, battery_function);
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
253 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY_STATUS, buf, MAVLINK_MSG_ID_BATTERY_STATUS_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_CRC);
255 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY_STATUS, buf, MAVLINK_MSG_ID_BATTERY_STATUS_LEN);
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);
271 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY_STATUS, (
const char *)packet, MAVLINK_MSG_ID_BATTERY_STATUS_LEN);
287 static inline uint8_t mavlink_msg_battery_status_get_id(
const mavlink_message_t* msg)
289 return _MAV_RETURN_uint8_t(msg, 32);
297 static inline uint8_t mavlink_msg_battery_status_get_battery_function(
const mavlink_message_t* msg)
299 return _MAV_RETURN_uint8_t(msg, 33);
307 static inline uint8_t mavlink_msg_battery_status_get_type(
const mavlink_message_t* msg)
309 return _MAV_RETURN_uint8_t(msg, 34);
317 static inline int16_t mavlink_msg_battery_status_get_temperature(
const mavlink_message_t* msg)
319 return _MAV_RETURN_int16_t(msg, 8);
327 static inline uint16_t mavlink_msg_battery_status_get_voltages(
const mavlink_message_t* msg, uint16_t *voltages)
329 return _MAV_RETURN_uint16_t_array(msg, voltages, 10, 10);
337 static inline int16_t mavlink_msg_battery_status_get_current_battery(
const mavlink_message_t* msg)
339 return _MAV_RETURN_int16_t(msg, 30);
347 static inline int32_t mavlink_msg_battery_status_get_current_consumed(
const mavlink_message_t* msg)
349 return _MAV_RETURN_int32_t(msg, 0);
357 static inline int32_t mavlink_msg_battery_status_get_energy_consumed(
const mavlink_message_t* msg)
359 return _MAV_RETURN_int32_t(msg, 4);
367 static inline int8_t mavlink_msg_battery_status_get_battery_remaining(
const mavlink_message_t* msg)
369 return _MAV_RETURN_int8_t(msg, 35);
378 static inline void mavlink_msg_battery_status_decode(
const mavlink_message_t* msg,
mavlink_battery_status_t* battery_status)
380 #if MAVLINK_NEED_BYTE_SWAP
381 battery_status->
current_consumed = mavlink_msg_battery_status_get_current_consumed(msg);
382 battery_status->
energy_consumed = mavlink_msg_battery_status_get_energy_consumed(msg);
383 battery_status->
temperature = mavlink_msg_battery_status_get_temperature(msg);
384 mavlink_msg_battery_status_get_voltages(msg, battery_status->
voltages);
385 battery_status->
current_battery = mavlink_msg_battery_status_get_current_battery(msg);
386 battery_status->
id = mavlink_msg_battery_status_get_id(msg);
387 battery_status->
battery_function = mavlink_msg_battery_status_get_battery_function(msg);
388 battery_status->
type = mavlink_msg_battery_status_get_type(msg);
389 battery_status->
battery_remaining = mavlink_msg_battery_status_get_battery_remaining(msg);
391 memcpy(battery_status, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_BATTERY_STATUS_LEN);
int16_t current_battery
Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current...
Definition: mavlink_msg_battery_status.h:11
uint8_t id
Battery ID.
Definition: mavlink_msg_battery_status.h:12
int16_t temperature
Temperature of the battery in centi-degrees celsius. INT16_MAX for unknown temperature.
Definition: mavlink_msg_battery_status.h:9
int32_t current_consumed
Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide mAh consumption est...
Definition: mavlink_msg_battery_status.h:7
int32_t energy_consumed
Consumed energy, in 100*Joules (intergrated U*I*dt) (1 = 100 Joule), -1: autopilot does not provide e...
Definition: mavlink_msg_battery_status.h:8
int8_t battery_remaining
Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery...
Definition: mavlink_msg_battery_status.h:15
uint8_t battery_function
Function of the battery.
Definition: mavlink_msg_battery_status.h:13
Definition: mavlink_msg_battery_status.h:5
uint16_t voltages[10]
Battery voltage of cells, in millivolts (1 = 1 millivolt)
Definition: mavlink_msg_battery_status.h:10
uint8_t type
Type (chemistry) of the battery.
Definition: mavlink_msg_battery_status.h:14