3 #define MAVLINK_MSG_ID_POWER_STATUS 125
12 #define MAVLINK_MSG_ID_POWER_STATUS_LEN 6
13 #define MAVLINK_MSG_ID_125_LEN 6
15 #define MAVLINK_MSG_ID_POWER_STATUS_CRC 203
16 #define MAVLINK_MSG_ID_125_CRC 203
20 #define MAVLINK_MESSAGE_INFO_POWER_STATUS { \
23 { { "Vcc", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_power_status_t, Vcc) }, \
24 { "Vservo", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_power_status_t, Vservo) }, \
25 { "flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_power_status_t, flags) }, \
41 static inline uint16_t mavlink_msg_power_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
42 uint16_t Vcc, uint16_t Vservo, uint16_t
flags)
44 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
79 static inline uint16_t mavlink_msg_power_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
80 mavlink_message_t* msg,
81 uint16_t Vcc,uint16_t Vservo,uint16_t
flags)
83 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
100 #if MAVLINK_CRC_EXTRA
115 static inline uint16_t mavlink_msg_power_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
const mavlink_power_status_t* power_status)
117 return mavlink_msg_power_status_pack(system_id, component_id, msg, power_status->
Vcc, power_status->
Vservo, power_status->
flags);
129 static inline uint16_t mavlink_msg_power_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg,
const mavlink_power_status_t* power_status)
131 return mavlink_msg_power_status_pack_chan(system_id, component_id, chan, msg, power_status->
Vcc, power_status->
Vservo, power_status->
flags);
142 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
144 static inline void mavlink_msg_power_status_send(
mavlink_channel_t chan, uint16_t Vcc, uint16_t Vservo, uint16_t flags)
146 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
152 #if MAVLINK_CRC_EXTRA
163 #if MAVLINK_CRC_EXTRA
171 #if MAVLINK_MSG_ID_POWER_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
179 static inline void mavlink_msg_power_status_send_buf(mavlink_message_t *msgbuf,
mavlink_channel_t chan, uint16_t Vcc, uint16_t Vservo, uint16_t flags)
181 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
182 char *buf = (
char *)msgbuf;
187 #if MAVLINK_CRC_EXTRA
198 #if MAVLINK_CRC_EXTRA
217 static inline uint16_t mavlink_msg_power_status_get_Vcc(
const mavlink_message_t* msg)
219 return _MAV_RETURN_uint16_t(msg, 0);
227 static inline uint16_t mavlink_msg_power_status_get_Vservo(
const mavlink_message_t* msg)
229 return _MAV_RETURN_uint16_t(msg, 2);
237 static inline uint16_t mavlink_msg_power_status_get_flags(
const mavlink_message_t* msg)
239 return _MAV_RETURN_uint16_t(msg, 4);
248 static inline void mavlink_msg_power_status_decode(
const mavlink_message_t* msg,
mavlink_power_status_t* power_status)
250 #if MAVLINK_NEED_BYTE_SWAP
251 power_status->
Vcc = mavlink_msg_power_status_get_Vcc(msg);
252 power_status->
Vservo = mavlink_msg_power_status_get_Vservo(msg);
253 power_status->
flags = mavlink_msg_power_status_get_flags(msg);
uint16_t Vcc
5V rail voltage in millivolts
Definition: mavlink_msg_power_status.h:7
#define MAVLINK_MSG_ID_POWER_STATUS_CRC
Definition: mavlink_msg_power_status.h:15
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
uint16_t Vservo
servo rail voltage in millivolts
Definition: mavlink_msg_power_status.h:8
#define _MAV_PAYLOAD_NON_CONST(msg)
Definition: mavlink_types.h:172
struct __mavlink_power_status_t mavlink_power_status_t
mavlink_channel_t
Definition: mavlink_types.h:178
#define MAVLINK_MSG_ID_POWER_STATUS
Definition: mavlink_msg_power_status.h:3
#define _MAV_PAYLOAD(msg)
Definition: mavlink_types.h:171
uint16_t flags
Definition: ledstrip.h:11
Definition: mavlink_msg_power_status.h:5
#define MAVLINK_MSG_ID_POWER_STATUS_LEN
Definition: mavlink_msg_power_status.h:12
uint16_t flags
power supply status flags (see MAV_POWER_STATUS enum)
Definition: mavlink_msg_power_status.h:9
#define _mav_put_uint16_t(buf, wire_offset, b)
Definition: protocol.h:139
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