mavlink_msg_power_status.h
Go to the documentation of this file.
1 // MESSAGE POWER_STATUS PACKING
2 
3 #define MAVLINK_MSG_ID_POWER_STATUS 125
4 
6 {
7  uint16_t Vcc; /*< 5V rail voltage in millivolts*/
8  uint16_t Vservo; /*< servo rail voltage in millivolts*/
9  uint16_t flags; /*< power supply status flags (see MAV_POWER_STATUS enum)*/
11 
12 #define MAVLINK_MSG_ID_POWER_STATUS_LEN 6
13 #define MAVLINK_MSG_ID_125_LEN 6
14 
15 #define MAVLINK_MSG_ID_POWER_STATUS_CRC 203
16 #define MAVLINK_MSG_ID_125_CRC 203
17 
18 
19 
20 #define MAVLINK_MESSAGE_INFO_POWER_STATUS { \
21  "POWER_STATUS", \
22  3, \
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) }, \
26  } \
27 }
28 
29 
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)
43 {
44 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
46  _mav_put_uint16_t(buf, 0, Vcc);
47  _mav_put_uint16_t(buf, 2, Vservo);
48  _mav_put_uint16_t(buf, 4, flags);
49 
51 #else
53  packet.Vcc = Vcc;
54  packet.Vservo = Vservo;
55  packet.flags = flags;
56 
58 #endif
59 
60  msg->msgid = MAVLINK_MSG_ID_POWER_STATUS;
61 #if MAVLINK_CRC_EXTRA
63 #else
64  return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_POWER_STATUS_LEN);
65 #endif
66 }
67 
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)
82 {
83 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
85  _mav_put_uint16_t(buf, 0, Vcc);
86  _mav_put_uint16_t(buf, 2, Vservo);
87  _mav_put_uint16_t(buf, 4, flags);
88 
90 #else
92  packet.Vcc = Vcc;
93  packet.Vservo = Vservo;
94  packet.flags = flags;
95 
97 #endif
98 
99  msg->msgid = MAVLINK_MSG_ID_POWER_STATUS;
100 #if MAVLINK_CRC_EXTRA
102 #else
103  return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_POWER_STATUS_LEN);
104 #endif
105 }
106 
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)
116 {
117  return mavlink_msg_power_status_pack(system_id, component_id, msg, power_status->Vcc, power_status->Vservo, power_status->flags);
118 }
119 
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)
130 {
131  return mavlink_msg_power_status_pack_chan(system_id, component_id, chan, msg, power_status->Vcc, power_status->Vservo, power_status->flags);
132 }
133 
142 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
143 
144 static inline void mavlink_msg_power_status_send(mavlink_channel_t chan, uint16_t Vcc, uint16_t Vservo, uint16_t flags)
145 {
146 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
148  _mav_put_uint16_t(buf, 0, Vcc);
149  _mav_put_uint16_t(buf, 2, Vservo);
150  _mav_put_uint16_t(buf, 4, flags);
151 
152 #if MAVLINK_CRC_EXTRA
154 #else
155  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POWER_STATUS, buf, MAVLINK_MSG_ID_POWER_STATUS_LEN);
156 #endif
157 #else
158  mavlink_power_status_t packet;
159  packet.Vcc = Vcc;
160  packet.Vservo = Vservo;
161  packet.flags = flags;
162 
163 #if MAVLINK_CRC_EXTRA
164  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POWER_STATUS, (const char *)&packet, MAVLINK_MSG_ID_POWER_STATUS_LEN, MAVLINK_MSG_ID_POWER_STATUS_CRC);
165 #else
166  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POWER_STATUS, (const char *)&packet, MAVLINK_MSG_ID_POWER_STATUS_LEN);
167 #endif
168 #endif
169 }
170 
171 #if MAVLINK_MSG_ID_POWER_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
172 /*
173  This varient of _send() can be used to save stack space by re-using
174  memory from the receive buffer. The caller provides a
175  mavlink_message_t which is the size of a full mavlink message. This
176  is usually the receive buffer for the channel, and allows a reply to an
177  incoming message with minimum stack space usage.
178  */
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)
180 {
181 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
182  char *buf = (char *)msgbuf;
183  _mav_put_uint16_t(buf, 0, Vcc);
184  _mav_put_uint16_t(buf, 2, Vservo);
185  _mav_put_uint16_t(buf, 4, flags);
186 
187 #if MAVLINK_CRC_EXTRA
189 #else
190  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POWER_STATUS, buf, MAVLINK_MSG_ID_POWER_STATUS_LEN);
191 #endif
192 #else
194  packet->Vcc = Vcc;
195  packet->Vservo = Vservo;
196  packet->flags = flags;
197 
198 #if MAVLINK_CRC_EXTRA
199  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POWER_STATUS, (const char *)packet, MAVLINK_MSG_ID_POWER_STATUS_LEN, MAVLINK_MSG_ID_POWER_STATUS_CRC);
200 #else
201  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POWER_STATUS, (const char *)packet, MAVLINK_MSG_ID_POWER_STATUS_LEN);
202 #endif
203 #endif
204 }
205 #endif
206 
207 #endif
208 
209 // MESSAGE POWER_STATUS UNPACKING
210 
211 
217 static inline uint16_t mavlink_msg_power_status_get_Vcc(const mavlink_message_t* msg)
218 {
219  return _MAV_RETURN_uint16_t(msg, 0);
220 }
221 
227 static inline uint16_t mavlink_msg_power_status_get_Vservo(const mavlink_message_t* msg)
228 {
229  return _MAV_RETURN_uint16_t(msg, 2);
230 }
231 
237 static inline uint16_t mavlink_msg_power_status_get_flags(const mavlink_message_t* msg)
238 {
239  return _MAV_RETURN_uint16_t(msg, 4);
240 }
241 
248 static inline void mavlink_msg_power_status_decode(const mavlink_message_t* msg, mavlink_power_status_t* power_status)
249 {
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);
254 #else
255  memcpy(power_status, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_POWER_STATUS_LEN);
256 #endif
257 }
#define _mav_put_uint16_t(buf, wire_offset, b)
Definition: protocol.h:145


rosflight
Author(s): Daniel Koch , James Jackson
autogenerated on Wed Jul 3 2019 20:00:13