NinjaFlight
 All Data Structures Files Functions Variables Typedefs Enumerations Enumerator Macros Groups Pages
mavlink_msg_volt_sensor.h
Go to the documentation of this file.
1 // MESSAGE VOLT_SENSOR PACKING
2 
3 #define MAVLINK_MSG_ID_VOLT_SENSOR 191
4 
5 typedef struct __mavlink_volt_sensor_t
6 {
7  uint16_t voltage;
8  uint16_t reading2;
9  uint8_t r2Type;
11 
12 #define MAVLINK_MSG_ID_VOLT_SENSOR_LEN 5
13 #define MAVLINK_MSG_ID_191_LEN 5
14 
15 #define MAVLINK_MSG_ID_VOLT_SENSOR_CRC 17
16 #define MAVLINK_MSG_ID_191_CRC 17
17 
18 
19 
20 #define MAVLINK_MESSAGE_INFO_VOLT_SENSOR { \
21  "VOLT_SENSOR", \
22  3, \
23  { { "voltage", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_volt_sensor_t, voltage) }, \
24  { "reading2", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_volt_sensor_t, reading2) }, \
25  { "r2Type", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_volt_sensor_t, r2Type) }, \
26  } \
27 }
28 
29 
41 static inline uint16_t mavlink_msg_volt_sensor_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
42  uint8_t r2Type, uint16_t voltage, uint16_t reading2)
43 {
44 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
46  _mav_put_uint16_t(buf, 0, voltage);
47  _mav_put_uint16_t(buf, 2, reading2);
48  _mav_put_uint8_t(buf, 4, r2Type);
49 
51 #else
52  mavlink_volt_sensor_t packet;
53  packet.voltage = voltage;
54  packet.reading2 = reading2;
55  packet.r2Type = r2Type;
56 
58 #endif
59 
60  msg->msgid = MAVLINK_MSG_ID_VOLT_SENSOR;
61 #if MAVLINK_CRC_EXTRA
63 #else
64  return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_VOLT_SENSOR_LEN);
65 #endif
66 }
67 
79 static inline uint16_t mavlink_msg_volt_sensor_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
80  mavlink_message_t* msg,
81  uint8_t r2Type,uint16_t voltage,uint16_t reading2)
82 {
83 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
85  _mav_put_uint16_t(buf, 0, voltage);
86  _mav_put_uint16_t(buf, 2, reading2);
87  _mav_put_uint8_t(buf, 4, r2Type);
88 
90 #else
91  mavlink_volt_sensor_t packet;
92  packet.voltage = voltage;
93  packet.reading2 = reading2;
94  packet.r2Type = r2Type;
95 
97 #endif
98 
99  msg->msgid = MAVLINK_MSG_ID_VOLT_SENSOR;
100 #if MAVLINK_CRC_EXTRA
102 #else
103  return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_VOLT_SENSOR_LEN);
104 #endif
105 }
106 
115 static inline uint16_t mavlink_msg_volt_sensor_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_volt_sensor_t* volt_sensor)
116 {
117  return mavlink_msg_volt_sensor_pack(system_id, component_id, msg, volt_sensor->r2Type, volt_sensor->voltage, volt_sensor->reading2);
118 }
119 
129 static inline uint16_t mavlink_msg_volt_sensor_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_volt_sensor_t* volt_sensor)
130 {
131  return mavlink_msg_volt_sensor_pack_chan(system_id, component_id, chan, msg, volt_sensor->r2Type, volt_sensor->voltage, volt_sensor->reading2);
132 }
133 
142 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
143 
144 static inline void mavlink_msg_volt_sensor_send(mavlink_channel_t chan, uint8_t r2Type, uint16_t voltage, uint16_t reading2)
145 {
146 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
148  _mav_put_uint16_t(buf, 0, voltage);
149  _mav_put_uint16_t(buf, 2, reading2);
150  _mav_put_uint8_t(buf, 4, r2Type);
151 
152 #if MAVLINK_CRC_EXTRA
154 #else
155  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VOLT_SENSOR, buf, MAVLINK_MSG_ID_VOLT_SENSOR_LEN);
156 #endif
157 #else
158  mavlink_volt_sensor_t packet;
159  packet.voltage = voltage;
160  packet.reading2 = reading2;
161  packet.r2Type = r2Type;
162 
163 #if MAVLINK_CRC_EXTRA
164  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VOLT_SENSOR, (const char *)&packet, MAVLINK_MSG_ID_VOLT_SENSOR_LEN, MAVLINK_MSG_ID_VOLT_SENSOR_CRC);
165 #else
166  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VOLT_SENSOR, (const char *)&packet, MAVLINK_MSG_ID_VOLT_SENSOR_LEN);
167 #endif
168 #endif
169 }
170 
171 #if MAVLINK_MSG_ID_VOLT_SENSOR_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_volt_sensor_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t r2Type, uint16_t voltage, uint16_t reading2)
180 {
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_uint16_t(buf, 2, reading2);
185  _mav_put_uint8_t(buf, 4, r2Type);
186 
187 #if MAVLINK_CRC_EXTRA
189 #else
190  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VOLT_SENSOR, buf, MAVLINK_MSG_ID_VOLT_SENSOR_LEN);
191 #endif
192 #else
193  mavlink_volt_sensor_t *packet = (mavlink_volt_sensor_t *)msgbuf;
194  packet->voltage = voltage;
195  packet->reading2 = reading2;
196  packet->r2Type = r2Type;
197 
198 #if MAVLINK_CRC_EXTRA
199  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VOLT_SENSOR, (const char *)packet, MAVLINK_MSG_ID_VOLT_SENSOR_LEN, MAVLINK_MSG_ID_VOLT_SENSOR_CRC);
200 #else
201  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VOLT_SENSOR, (const char *)packet, MAVLINK_MSG_ID_VOLT_SENSOR_LEN);
202 #endif
203 #endif
204 }
205 #endif
206 
207 #endif
208 
209 // MESSAGE VOLT_SENSOR UNPACKING
210 
211 
217 static inline uint8_t mavlink_msg_volt_sensor_get_r2Type(const mavlink_message_t* msg)
218 {
219  return _MAV_RETURN_uint8_t(msg, 4);
220 }
221 
227 static inline uint16_t mavlink_msg_volt_sensor_get_voltage(const mavlink_message_t* msg)
228 {
229  return _MAV_RETURN_uint16_t(msg, 0);
230 }
231 
237 static inline uint16_t mavlink_msg_volt_sensor_get_reading2(const mavlink_message_t* msg)
238 {
239  return _MAV_RETURN_uint16_t(msg, 2);
240 }
241 
248 static inline void mavlink_msg_volt_sensor_decode(const mavlink_message_t* msg, mavlink_volt_sensor_t* volt_sensor)
249 {
250 #if MAVLINK_NEED_BYTE_SWAP
251  volt_sensor->voltage = mavlink_msg_volt_sensor_get_voltage(msg);
252  volt_sensor->reading2 = mavlink_msg_volt_sensor_get_reading2(msg);
253  volt_sensor->r2Type = mavlink_msg_volt_sensor_get_r2Type(msg);
254 #else
255  memcpy(volt_sensor, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_VOLT_SENSOR_LEN);
256 #endif
257 }
#define _MAV_RETURN_uint8_t(msg, wire_offset)
Definition: protocol.h:238
#define _mav_put_uint8_t(buf, wire_offset, b)
Definition: protocol.h:134
#define _mav_put_uint16_t(buf, wire_offset, b)
Definition: protocol.h:139