4#define MAVLINK_MSG_ID_BATTERY2 181
7typedef struct __mavlink_battery2_t {
9 int16_t current_battery;
12#define MAVLINK_MSG_ID_BATTERY2_LEN 4
13#define MAVLINK_MSG_ID_BATTERY2_MIN_LEN 4
14#define MAVLINK_MSG_ID_181_LEN 4
15#define MAVLINK_MSG_ID_181_MIN_LEN 4
17#define MAVLINK_MSG_ID_BATTERY2_CRC 174
18#define MAVLINK_MSG_ID_181_CRC 174
22#if MAVLINK_COMMAND_24BIT
23#define MAVLINK_MESSAGE_INFO_BATTERY2 { \
27 { { "voltage", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_battery2_t, voltage) }, \
28 { "current_battery", NULL, MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_battery2_t, current_battery) }, \
32#define MAVLINK_MESSAGE_INFO_BATTERY2 { \
35 { { "voltage", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_battery2_t, voltage) }, \
36 { "current_battery", NULL, MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_battery2_t, current_battery) }, \
51static inline uint16_t mavlink_msg_battery2_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
52 uint16_t voltage, int16_t current_battery)
54#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
55 char buf[MAVLINK_MSG_ID_BATTERY2_LEN];
56 _mav_put_uint16_t(buf, 0, voltage);
57 _mav_put_int16_t(buf, 2, current_battery);
59 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_BATTERY2_LEN);
61 mavlink_battery2_t packet;
62 packet.voltage = voltage;
63 packet.current_battery = current_battery;
65 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_BATTERY2_LEN);
68 msg->msgid = MAVLINK_MSG_ID_BATTERY2;
69 return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_BATTERY2_MIN_LEN, MAVLINK_MSG_ID_BATTERY2_LEN, MAVLINK_MSG_ID_BATTERY2_CRC);
82static inline uint16_t mavlink_msg_battery2_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
83 mavlink_message_t* msg,
84 uint16_t voltage,int16_t current_battery)
86#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
87 char buf[MAVLINK_MSG_ID_BATTERY2_LEN];
88 _mav_put_uint16_t(buf, 0, voltage);
89 _mav_put_int16_t(buf, 2, current_battery);
91 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_BATTERY2_LEN);
93 mavlink_battery2_t packet;
94 packet.voltage = voltage;
95 packet.current_battery = current_battery;
97 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_BATTERY2_LEN);
100 msg->msgid = MAVLINK_MSG_ID_BATTERY2;
101 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_BATTERY2_MIN_LEN, MAVLINK_MSG_ID_BATTERY2_LEN, MAVLINK_MSG_ID_BATTERY2_CRC);
112static inline uint16_t mavlink_msg_battery2_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
const mavlink_battery2_t* battery2)
114 return mavlink_msg_battery2_pack(system_id, component_id, msg, battery2->voltage, battery2->current_battery);
126static inline uint16_t mavlink_msg_battery2_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg,
const mavlink_battery2_t* battery2)
128 return mavlink_msg_battery2_pack_chan(system_id, component_id, chan, msg, battery2->voltage, battery2->current_battery);
138#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
140static inline void mavlink_msg_battery2_send(mavlink_channel_t chan, uint16_t voltage, int16_t current_battery)
142#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
143 char buf[MAVLINK_MSG_ID_BATTERY2_LEN];
144 _mav_put_uint16_t(buf, 0, voltage);
145 _mav_put_int16_t(buf, 2, current_battery);
147 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY2, buf, MAVLINK_MSG_ID_BATTERY2_MIN_LEN, MAVLINK_MSG_ID_BATTERY2_LEN, MAVLINK_MSG_ID_BATTERY2_CRC);
149 mavlink_battery2_t packet;
150 packet.voltage = voltage;
151 packet.current_battery = current_battery;
153 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY2, (
const char *)&packet, MAVLINK_MSG_ID_BATTERY2_MIN_LEN, MAVLINK_MSG_ID_BATTERY2_LEN, MAVLINK_MSG_ID_BATTERY2_CRC);
162static inline void mavlink_msg_battery2_send_struct(mavlink_channel_t chan,
const mavlink_battery2_t* battery2)
164#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
165 mavlink_msg_battery2_send(chan, battery2->voltage, battery2->current_battery);
167 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY2, (
const char *)battery2, MAVLINK_MSG_ID_BATTERY2_MIN_LEN, MAVLINK_MSG_ID_BATTERY2_LEN, MAVLINK_MSG_ID_BATTERY2_CRC);
171#if MAVLINK_MSG_ID_BATTERY2_LEN <= MAVLINK_MAX_PAYLOAD_LEN
179static inline void mavlink_msg_battery2_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t voltage, int16_t current_battery)
181#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
182 char *buf = (
char *)msgbuf;
183 _mav_put_uint16_t(buf, 0, voltage);
184 _mav_put_int16_t(buf, 2, current_battery);
186 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY2, buf, MAVLINK_MSG_ID_BATTERY2_MIN_LEN, MAVLINK_MSG_ID_BATTERY2_LEN, MAVLINK_MSG_ID_BATTERY2_CRC);
188 mavlink_battery2_t *packet = (mavlink_battery2_t *)msgbuf;
189 packet->voltage = voltage;
190 packet->current_battery = current_battery;
192 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY2, (
const char *)packet, MAVLINK_MSG_ID_BATTERY2_MIN_LEN, MAVLINK_MSG_ID_BATTERY2_LEN, MAVLINK_MSG_ID_BATTERY2_CRC);
207static inline uint16_t mavlink_msg_battery2_get_voltage(
const mavlink_message_t* msg)
209 return _MAV_RETURN_uint16_t(msg, 0);
217static inline int16_t mavlink_msg_battery2_get_current_battery(
const mavlink_message_t* msg)
219 return _MAV_RETURN_int16_t(msg, 2);
228static inline void mavlink_msg_battery2_decode(
const mavlink_message_t* msg, mavlink_battery2_t* battery2)
230#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
231 battery2->voltage = mavlink_msg_battery2_get_voltage(msg);
232 battery2->current_battery = mavlink_msg_battery2_get_current_battery(msg);
234 uint8_t len = msg->len < MAVLINK_MSG_ID_BATTERY2_LEN? msg->len : MAVLINK_MSG_ID_BATTERY2_LEN;
235 memset(battery2, 0, MAVLINK_MSG_ID_BATTERY2_LEN);
236 memcpy(battery2, _MAV_PAYLOAD(msg), len);