RflySimSDK v3.08
RflySimSDK说明文档
载入中...
搜索中...
未找到
mavlink_msg_volt_sensor.h
1#pragma once
2// MESSAGE VOLT_SENSOR PACKING
3
4#define MAVLINK_MSG_ID_VOLT_SENSOR 191
5
6MAVPACKED(
7typedef struct __mavlink_volt_sensor_t {
8 uint16_t voltage; /*< Voltage in uS of PWM. 0 uS = 0V, 20 uS = 21.5V */
9 uint16_t reading2; /*< Depends on the value of r2Type (0) Current consumption in uS of PWM, 20 uS = 90Amp (1) Distance in cm (2) Distance in cm (3) Absolute value*/
10 uint8_t r2Type; /*< It is the value of reading 2: 0 - Current, 1 - Foreward Sonar, 2 - Back Sonar, 3 - RPM*/
11}) mavlink_volt_sensor_t;
12
13#define MAVLINK_MSG_ID_VOLT_SENSOR_LEN 5
14#define MAVLINK_MSG_ID_VOLT_SENSOR_MIN_LEN 5
15#define MAVLINK_MSG_ID_191_LEN 5
16#define MAVLINK_MSG_ID_191_MIN_LEN 5
17
18#define MAVLINK_MSG_ID_VOLT_SENSOR_CRC 17
19#define MAVLINK_MSG_ID_191_CRC 17
20
21
22
23#if MAVLINK_COMMAND_24BIT
24#define MAVLINK_MESSAGE_INFO_VOLT_SENSOR { \
25 191, \
26 "VOLT_SENSOR", \
27 3, \
28 { { "r2Type", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_volt_sensor_t, r2Type) }, \
29 { "voltage", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_volt_sensor_t, voltage) }, \
30 { "reading2", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_volt_sensor_t, reading2) }, \
31 } \
32}
33#else
34#define MAVLINK_MESSAGE_INFO_VOLT_SENSOR { \
35 "VOLT_SENSOR", \
36 3, \
37 { { "r2Type", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_volt_sensor_t, r2Type) }, \
38 { "voltage", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_volt_sensor_t, voltage) }, \
39 { "reading2", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_volt_sensor_t, reading2) }, \
40 } \
41}
42#endif
43
44/**
45 * @brief Pack a volt_sensor message
46 * @param system_id ID of this system
47 * @param component_id ID of this component (e.g. 200 for IMU)
48 * @param msg The MAVLink message to compress the data into
49 *
50 * @param r2Type It is the value of reading 2: 0 - Current, 1 - Foreward Sonar, 2 - Back Sonar, 3 - RPM
51 * @param voltage Voltage in uS of PWM. 0 uS = 0V, 20 uS = 21.5V
52 * @param reading2 Depends on the value of r2Type (0) Current consumption in uS of PWM, 20 uS = 90Amp (1) Distance in cm (2) Distance in cm (3) Absolute value
53 * @return length of the message in bytes (excluding serial stream start sign)
54 */
55static inline uint16_t mavlink_msg_volt_sensor_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
56 uint8_t r2Type, uint16_t voltage, uint16_t reading2)
57{
58#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
59 char buf[MAVLINK_MSG_ID_VOLT_SENSOR_LEN];
60 _mav_put_uint16_t(buf, 0, voltage);
61 _mav_put_uint16_t(buf, 2, reading2);
62 _mav_put_uint8_t(buf, 4, r2Type);
63
64 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VOLT_SENSOR_LEN);
65#else
66 mavlink_volt_sensor_t packet;
67 packet.voltage = voltage;
68 packet.reading2 = reading2;
69 packet.r2Type = r2Type;
70
71 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VOLT_SENSOR_LEN);
72#endif
73
74 msg->msgid = MAVLINK_MSG_ID_VOLT_SENSOR;
75 return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_VOLT_SENSOR_MIN_LEN, MAVLINK_MSG_ID_VOLT_SENSOR_LEN, MAVLINK_MSG_ID_VOLT_SENSOR_CRC);
76}
77
78/**
79 * @brief Pack a volt_sensor message on a channel
80 * @param system_id ID of this system
81 * @param component_id ID of this component (e.g. 200 for IMU)
82 * @param chan The MAVLink channel this message will be sent over
83 * @param msg The MAVLink message to compress the data into
84 * @param r2Type It is the value of reading 2: 0 - Current, 1 - Foreward Sonar, 2 - Back Sonar, 3 - RPM
85 * @param voltage Voltage in uS of PWM. 0 uS = 0V, 20 uS = 21.5V
86 * @param reading2 Depends on the value of r2Type (0) Current consumption in uS of PWM, 20 uS = 90Amp (1) Distance in cm (2) Distance in cm (3) Absolute value
87 * @return length of the message in bytes (excluding serial stream start sign)
88 */
89static inline uint16_t mavlink_msg_volt_sensor_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
90 mavlink_message_t* msg,
91 uint8_t r2Type,uint16_t voltage,uint16_t reading2)
92{
93#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
94 char buf[MAVLINK_MSG_ID_VOLT_SENSOR_LEN];
95 _mav_put_uint16_t(buf, 0, voltage);
96 _mav_put_uint16_t(buf, 2, reading2);
97 _mav_put_uint8_t(buf, 4, r2Type);
98
99 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VOLT_SENSOR_LEN);
100#else
101 mavlink_volt_sensor_t packet;
102 packet.voltage = voltage;
103 packet.reading2 = reading2;
104 packet.r2Type = r2Type;
105
106 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VOLT_SENSOR_LEN);
107#endif
108
109 msg->msgid = MAVLINK_MSG_ID_VOLT_SENSOR;
110 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_VOLT_SENSOR_MIN_LEN, MAVLINK_MSG_ID_VOLT_SENSOR_LEN, MAVLINK_MSG_ID_VOLT_SENSOR_CRC);
111}
112
113/**
114 * @brief Encode a volt_sensor struct
115 *
116 * @param system_id ID of this system
117 * @param component_id ID of this component (e.g. 200 for IMU)
118 * @param msg The MAVLink message to compress the data into
119 * @param volt_sensor C-struct to read the message contents from
120 */
121static 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)
122{
123 return mavlink_msg_volt_sensor_pack(system_id, component_id, msg, volt_sensor->r2Type, volt_sensor->voltage, volt_sensor->reading2);
124}
125
126/**
127 * @brief Encode a volt_sensor struct on a channel
128 *
129 * @param system_id ID of this system
130 * @param component_id ID of this component (e.g. 200 for IMU)
131 * @param chan The MAVLink channel this message will be sent over
132 * @param msg The MAVLink message to compress the data into
133 * @param volt_sensor C-struct to read the message contents from
134 */
135static 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)
136{
137 return mavlink_msg_volt_sensor_pack_chan(system_id, component_id, chan, msg, volt_sensor->r2Type, volt_sensor->voltage, volt_sensor->reading2);
138}
139
140/**
141 * @brief Send a volt_sensor message
142 * @param chan MAVLink channel to send the message
143 *
144 * @param r2Type It is the value of reading 2: 0 - Current, 1 - Foreward Sonar, 2 - Back Sonar, 3 - RPM
145 * @param voltage Voltage in uS of PWM. 0 uS = 0V, 20 uS = 21.5V
146 * @param reading2 Depends on the value of r2Type (0) Current consumption in uS of PWM, 20 uS = 90Amp (1) Distance in cm (2) Distance in cm (3) Absolute value
147 */
148#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
149
150static inline void mavlink_msg_volt_sensor_send(mavlink_channel_t chan, uint8_t r2Type, uint16_t voltage, uint16_t reading2)
151{
152#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
153 char buf[MAVLINK_MSG_ID_VOLT_SENSOR_LEN];
154 _mav_put_uint16_t(buf, 0, voltage);
155 _mav_put_uint16_t(buf, 2, reading2);
156 _mav_put_uint8_t(buf, 4, r2Type);
157
158 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VOLT_SENSOR, buf, MAVLINK_MSG_ID_VOLT_SENSOR_MIN_LEN, MAVLINK_MSG_ID_VOLT_SENSOR_LEN, MAVLINK_MSG_ID_VOLT_SENSOR_CRC);
159#else
160 mavlink_volt_sensor_t packet;
161 packet.voltage = voltage;
162 packet.reading2 = reading2;
163 packet.r2Type = r2Type;
164
165 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VOLT_SENSOR, (const char *)&packet, MAVLINK_MSG_ID_VOLT_SENSOR_MIN_LEN, MAVLINK_MSG_ID_VOLT_SENSOR_LEN, MAVLINK_MSG_ID_VOLT_SENSOR_CRC);
166#endif
167}
168
169/**
170 * @brief Send a volt_sensor message
171 * @param chan MAVLink channel to send the message
172 * @param struct The MAVLink struct to serialize
173 */
174static inline void mavlink_msg_volt_sensor_send_struct(mavlink_channel_t chan, const mavlink_volt_sensor_t* volt_sensor)
175{
176#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
177 mavlink_msg_volt_sensor_send(chan, volt_sensor->r2Type, volt_sensor->voltage, volt_sensor->reading2);
178#else
179 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VOLT_SENSOR, (const char *)volt_sensor, MAVLINK_MSG_ID_VOLT_SENSOR_MIN_LEN, MAVLINK_MSG_ID_VOLT_SENSOR_LEN, MAVLINK_MSG_ID_VOLT_SENSOR_CRC);
180#endif
181}
182
183#if MAVLINK_MSG_ID_VOLT_SENSOR_LEN <= MAVLINK_MAX_PAYLOAD_LEN
184/*
185 This varient of _send() can be used to save stack space by re-using
186 memory from the receive buffer. The caller provides a
187 mavlink_message_t which is the size of a full mavlink message. This
188 is usually the receive buffer for the channel, and allows a reply to an
189 incoming message with minimum stack space usage.
190 */
191static 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)
192{
193#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
194 char *buf = (char *)msgbuf;
195 _mav_put_uint16_t(buf, 0, voltage);
196 _mav_put_uint16_t(buf, 2, reading2);
197 _mav_put_uint8_t(buf, 4, r2Type);
198
199 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VOLT_SENSOR, buf, MAVLINK_MSG_ID_VOLT_SENSOR_MIN_LEN, MAVLINK_MSG_ID_VOLT_SENSOR_LEN, MAVLINK_MSG_ID_VOLT_SENSOR_CRC);
200#else
201 mavlink_volt_sensor_t *packet = (mavlink_volt_sensor_t *)msgbuf;
202 packet->voltage = voltage;
203 packet->reading2 = reading2;
204 packet->r2Type = r2Type;
205
206 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VOLT_SENSOR, (const char *)packet, MAVLINK_MSG_ID_VOLT_SENSOR_MIN_LEN, MAVLINK_MSG_ID_VOLT_SENSOR_LEN, MAVLINK_MSG_ID_VOLT_SENSOR_CRC);
207#endif
208}
209#endif
210
211#endif
212
213// MESSAGE VOLT_SENSOR UNPACKING
214
215
216/**
217 * @brief Get field r2Type from volt_sensor message
218 *
219 * @return It is the value of reading 2: 0 - Current, 1 - Foreward Sonar, 2 - Back Sonar, 3 - RPM
220 */
221static inline uint8_t mavlink_msg_volt_sensor_get_r2Type(const mavlink_message_t* msg)
222{
223 return _MAV_RETURN_uint8_t(msg, 4);
224}
225
226/**
227 * @brief Get field voltage from volt_sensor message
228 *
229 * @return Voltage in uS of PWM. 0 uS = 0V, 20 uS = 21.5V
230 */
231static inline uint16_t mavlink_msg_volt_sensor_get_voltage(const mavlink_message_t* msg)
232{
233 return _MAV_RETURN_uint16_t(msg, 0);
234}
235
236/**
237 * @brief Get field reading2 from volt_sensor message
238 *
239 * @return Depends on the value of r2Type (0) Current consumption in uS of PWM, 20 uS = 90Amp (1) Distance in cm (2) Distance in cm (3) Absolute value
240 */
241static inline uint16_t mavlink_msg_volt_sensor_get_reading2(const mavlink_message_t* msg)
242{
243 return _MAV_RETURN_uint16_t(msg, 2);
244}
245
246/**
247 * @brief Decode a volt_sensor message into a struct
248 *
249 * @param msg The message to decode
250 * @param volt_sensor C-struct to decode the message contents into
251 */
252static inline void mavlink_msg_volt_sensor_decode(const mavlink_message_t* msg, mavlink_volt_sensor_t* volt_sensor)
253{
254#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
255 volt_sensor->voltage = mavlink_msg_volt_sensor_get_voltage(msg);
256 volt_sensor->reading2 = mavlink_msg_volt_sensor_get_reading2(msg);
257 volt_sensor->r2Type = mavlink_msg_volt_sensor_get_r2Type(msg);
258#else
259 uint8_t len = msg->len < MAVLINK_MSG_ID_VOLT_SENSOR_LEN? msg->len : MAVLINK_MSG_ID_VOLT_SENSOR_LEN;
260 memset(volt_sensor, 0, MAVLINK_MSG_ID_VOLT_SENSOR_LEN);
261 memcpy(volt_sensor, _MAV_PAYLOAD(msg), len);
262#endif
263}