3 #define MAVLINK_MSG_ID_BATTERY2 181
11 #define MAVLINK_MSG_ID_BATTERY2_LEN 4
12 #define MAVLINK_MSG_ID_181_LEN 4
14 #define MAVLINK_MSG_ID_BATTERY2_CRC 174
15 #define MAVLINK_MSG_ID_181_CRC 174
19 #define MAVLINK_MESSAGE_INFO_BATTERY2 { \
22 { { "voltage", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_battery2_t, voltage) }, \
23 { "current_battery", NULL, MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_battery2_t, current_battery) }, \
38 static inline uint16_t mavlink_msg_battery2_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
39 uint16_t voltage, int16_t current_battery)
41 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
73 static inline uint16_t mavlink_msg_battery2_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
74 mavlink_message_t* msg,
75 uint16_t voltage,int16_t current_battery)
77 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
107 static inline uint16_t mavlink_msg_battery2_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
const mavlink_battery2_t* battery2)
109 return mavlink_msg_battery2_pack(system_id, component_id, msg, battery2->
voltage, battery2->
current_battery);
121 static 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)
123 return mavlink_msg_battery2_pack_chan(system_id, component_id, chan, msg, battery2->
voltage, battery2->
current_battery);
133 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
135 static inline void mavlink_msg_battery2_send(
mavlink_channel_t chan, uint16_t voltage, int16_t current_battery)
137 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
142 #if MAVLINK_CRC_EXTRA
152 #if MAVLINK_CRC_EXTRA
160 #if MAVLINK_MSG_ID_BATTERY2_LEN <= MAVLINK_MAX_PAYLOAD_LEN
168 static inline void mavlink_msg_battery2_send_buf(mavlink_message_t *msgbuf,
mavlink_channel_t chan, uint16_t voltage, int16_t current_battery)
170 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
171 char *buf = (
char *)msgbuf;
175 #if MAVLINK_CRC_EXTRA
185 #if MAVLINK_CRC_EXTRA
204 static inline uint16_t mavlink_msg_battery2_get_voltage(
const mavlink_message_t* msg)
206 return _MAV_RETURN_uint16_t(msg, 0);
214 static inline int16_t mavlink_msg_battery2_get_current_battery(
const mavlink_message_t* msg)
216 return _MAV_RETURN_int16_t(msg, 2);
225 static inline void mavlink_msg_battery2_decode(
const mavlink_message_t* msg,
mavlink_battery2_t* battery2)
227 #if MAVLINK_NEED_BYTE_SWAP
228 battery2->
voltage = mavlink_msg_battery2_get_voltage(msg);
229 battery2->
current_battery = mavlink_msg_battery2_get_current_battery(msg);
int16_t current_battery
Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current...
Definition: mavlink_msg_battery2.h:8
MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t *msg, uint8_t system_id, uint8_t component_id, uint8_t length)
Finalize a MAVLink message with MAVLINK_COMM_0 as default channel.
Definition: mavlink_helpers.h:105
#define _MAV_PAYLOAD_NON_CONST(msg)
Definition: mavlink_types.h:172
mavlink_channel_t
Definition: mavlink_types.h:178
#define MAVLINK_MSG_ID_BATTERY2_LEN
Definition: mavlink_msg_battery2.h:11
#define _MAV_PAYLOAD(msg)
Definition: mavlink_types.h:171
struct __mavlink_battery2_t mavlink_battery2_t
#define MAVLINK_MSG_ID_BATTERY2_CRC
Definition: mavlink_msg_battery2.h:14
#define MAVLINK_MSG_ID_BATTERY2
Definition: mavlink_msg_battery2.h:3
Definition: mavlink_msg_battery2.h:5
#define _mav_put_uint16_t(buf, wire_offset, b)
Definition: protocol.h:139
uint16_t voltage
voltage in millivolts
Definition: mavlink_msg_battery2.h:7
MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t *msg, uint8_t system_id, uint8_t component_id, uint8_t chan, uint8_t length)
Finalize a MAVLink message with channel assignment.
Definition: mavlink_helpers.h:71
#define _mav_put_int16_t(buf, wire_offset, b)
Definition: protocol.h:140