3 #define MAVLINK_MSG_ID_VOLT_SENSOR 191
12 #define MAVLINK_MSG_ID_VOLT_SENSOR_LEN 5
13 #define MAVLINK_MSG_ID_191_LEN 5
15 #define MAVLINK_MSG_ID_VOLT_SENSOR_CRC 17
16 #define MAVLINK_MSG_ID_191_CRC 17
20 #define MAVLINK_MESSAGE_INFO_VOLT_SENSOR { \
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) }, \
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)
44 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
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)
83 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
100 #if MAVLINK_CRC_EXTRA
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)
117 return mavlink_msg_volt_sensor_pack(system_id, component_id, msg, volt_sensor->
r2Type, volt_sensor->
voltage, volt_sensor->
reading2);
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)
131 return mavlink_msg_volt_sensor_pack_chan(system_id, component_id, chan, msg, volt_sensor->
r2Type, volt_sensor->
voltage, volt_sensor->
reading2);
142 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
144 static inline void mavlink_msg_volt_sensor_send(
mavlink_channel_t chan, uint8_t r2Type, uint16_t voltage, uint16_t reading2)
146 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
152 #if MAVLINK_CRC_EXTRA
163 #if MAVLINK_CRC_EXTRA
171 #if MAVLINK_MSG_ID_VOLT_SENSOR_LEN <= MAVLINK_MAX_PAYLOAD_LEN
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)
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 uint8_t mavlink_msg_volt_sensor_get_r2Type(
const mavlink_message_t* msg)
227 static inline uint16_t mavlink_msg_volt_sensor_get_voltage(
const mavlink_message_t* msg)
229 return _MAV_RETURN_uint16_t(msg, 0);
237 static inline uint16_t mavlink_msg_volt_sensor_get_reading2(
const mavlink_message_t* msg)
239 return _MAV_RETURN_uint16_t(msg, 2);
248 static inline void mavlink_msg_volt_sensor_decode(
const mavlink_message_t* msg,
mavlink_volt_sensor_t* volt_sensor)
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);
struct __mavlink_volt_sensor_t mavlink_volt_sensor_t
Definition: mavlink_msg_volt_sensor.h:5
#define _MAV_RETURN_uint8_t(msg, wire_offset)
Definition: protocol.h:238
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_put_uint8_t(buf, wire_offset, b)
Definition: protocol.h:134
#define _MAV_PAYLOAD_NON_CONST(msg)
Definition: mavlink_types.h:172
mavlink_channel_t
Definition: mavlink_types.h:178
uint16_t reading2
Depends on the value of r2Type (0) Current consumption in uS of PWM, 20 uS = 90Amp (1) Distance in cm...
Definition: mavlink_msg_volt_sensor.h:8
#define MAVLINK_MSG_ID_VOLT_SENSOR_LEN
Definition: mavlink_msg_volt_sensor.h:12
#define _MAV_PAYLOAD(msg)
Definition: mavlink_types.h:171
uint16_t voltage
Voltage in uS of PWM. 0 uS = 0V, 20 uS = 21.5V.
Definition: mavlink_msg_volt_sensor.h:7
uint8_t r2Type
It is the value of reading 2: 0 - Current, 1 - Foreward Sonar, 2 - Back Sonar, 3 - RPM...
Definition: mavlink_msg_volt_sensor.h:9
#define MAVLINK_MSG_ID_VOLT_SENSOR_CRC
Definition: mavlink_msg_volt_sensor.h:15
#define _mav_put_uint16_t(buf, wire_offset, b)
Definition: protocol.h:139
#define MAVLINK_MSG_ID_VOLT_SENSOR
Definition: mavlink_msg_volt_sensor.h:3
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