3 #define MAVLINK_MSG_ID_RC_CHANNELS_SCALED 34
20 #define MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN 22
21 #define MAVLINK_MSG_ID_34_LEN 22
23 #define MAVLINK_MSG_ID_RC_CHANNELS_SCALED_CRC 237
24 #define MAVLINK_MSG_ID_34_CRC 237
28 #define MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED { \
29 "RC_CHANNELS_SCALED", \
31 { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_rc_channels_scaled_t, time_boot_ms) }, \
32 { "chan1_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_rc_channels_scaled_t, chan1_scaled) }, \
33 { "chan2_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 6, offsetof(mavlink_rc_channels_scaled_t, chan2_scaled) }, \
34 { "chan3_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_rc_channels_scaled_t, chan3_scaled) }, \
35 { "chan4_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_rc_channels_scaled_t, chan4_scaled) }, \
36 { "chan5_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_rc_channels_scaled_t, chan5_scaled) }, \
37 { "chan6_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_rc_channels_scaled_t, chan6_scaled) }, \
38 { "chan7_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_rc_channels_scaled_t, chan7_scaled) }, \
39 { "chan8_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 18, offsetof(mavlink_rc_channels_scaled_t, chan8_scaled) }, \
40 { "port", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_rc_channels_scaled_t, port) }, \
41 { "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 21, offsetof(mavlink_rc_channels_scaled_t, rssi) }, \
65 static inline uint16_t mavlink_msg_rc_channels_scaled_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
66 uint32_t time_boot_ms, uint8_t port, int16_t chan1_scaled, int16_t chan2_scaled, int16_t chan3_scaled, int16_t chan4_scaled, int16_t chan5_scaled, int16_t chan6_scaled, int16_t chan7_scaled, int16_t chan8_scaled, uint8_t rssi)
68 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
101 #if MAVLINK_CRC_EXTRA
127 static inline uint16_t mavlink_msg_rc_channels_scaled_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
128 mavlink_message_t* msg,
129 uint32_t time_boot_ms,uint8_t port,int16_t chan1_scaled,int16_t chan2_scaled,int16_t chan3_scaled,int16_t chan4_scaled,int16_t chan5_scaled,int16_t chan6_scaled,int16_t chan7_scaled,int16_t chan8_scaled,uint8_t rssi)
131 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
164 #if MAVLINK_CRC_EXTRA
179 static inline uint16_t mavlink_msg_rc_channels_scaled_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
const mavlink_rc_channels_scaled_t* rc_channels_scaled)
181 return mavlink_msg_rc_channels_scaled_pack(system_id, component_id, msg, rc_channels_scaled->
time_boot_ms, rc_channels_scaled->
port, rc_channels_scaled->
chan1_scaled, rc_channels_scaled->
chan2_scaled, rc_channels_scaled->
chan3_scaled, rc_channels_scaled->
chan4_scaled, rc_channels_scaled->
chan5_scaled, rc_channels_scaled->
chan6_scaled, rc_channels_scaled->
chan7_scaled, rc_channels_scaled->
chan8_scaled, rc_channels_scaled->
rssi);
193 static inline uint16_t mavlink_msg_rc_channels_scaled_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg,
const mavlink_rc_channels_scaled_t* rc_channels_scaled)
195 return mavlink_msg_rc_channels_scaled_pack_chan(system_id, component_id, chan, msg, rc_channels_scaled->
time_boot_ms, rc_channels_scaled->
port, rc_channels_scaled->
chan1_scaled, rc_channels_scaled->
chan2_scaled, rc_channels_scaled->
chan3_scaled, rc_channels_scaled->
chan4_scaled, rc_channels_scaled->
chan5_scaled, rc_channels_scaled->
chan6_scaled, rc_channels_scaled->
chan7_scaled, rc_channels_scaled->
chan8_scaled, rc_channels_scaled->
rssi);
214 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
216 static inline void mavlink_msg_rc_channels_scaled_send(
mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t port, int16_t chan1_scaled, int16_t chan2_scaled, int16_t chan3_scaled, int16_t chan4_scaled, int16_t chan5_scaled, int16_t chan6_scaled, int16_t chan7_scaled, int16_t chan8_scaled, uint8_t rssi)
218 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
232 #if MAVLINK_CRC_EXTRA
251 #if MAVLINK_CRC_EXTRA
259 #if MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN <= MAVLINK_MAX_PAYLOAD_LEN
267 static inline void mavlink_msg_rc_channels_scaled_send_buf(mavlink_message_t *msgbuf,
mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t port, int16_t chan1_scaled, int16_t chan2_scaled, int16_t chan3_scaled, int16_t chan4_scaled, int16_t chan5_scaled, int16_t chan6_scaled, int16_t chan7_scaled, int16_t chan8_scaled, uint8_t rssi)
269 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
270 char *buf = (
char *)msgbuf;
283 #if MAVLINK_CRC_EXTRA
302 #if MAVLINK_CRC_EXTRA
321 static inline uint32_t mavlink_msg_rc_channels_scaled_get_time_boot_ms(
const mavlink_message_t* msg)
323 return _MAV_RETURN_uint32_t(msg, 0);
331 static inline uint8_t mavlink_msg_rc_channels_scaled_get_port(
const mavlink_message_t* msg)
341 static inline int16_t mavlink_msg_rc_channels_scaled_get_chan1_scaled(
const mavlink_message_t* msg)
343 return _MAV_RETURN_int16_t(msg, 4);
351 static inline int16_t mavlink_msg_rc_channels_scaled_get_chan2_scaled(
const mavlink_message_t* msg)
353 return _MAV_RETURN_int16_t(msg, 6);
361 static inline int16_t mavlink_msg_rc_channels_scaled_get_chan3_scaled(
const mavlink_message_t* msg)
363 return _MAV_RETURN_int16_t(msg, 8);
371 static inline int16_t mavlink_msg_rc_channels_scaled_get_chan4_scaled(
const mavlink_message_t* msg)
373 return _MAV_RETURN_int16_t(msg, 10);
381 static inline int16_t mavlink_msg_rc_channels_scaled_get_chan5_scaled(
const mavlink_message_t* msg)
383 return _MAV_RETURN_int16_t(msg, 12);
391 static inline int16_t mavlink_msg_rc_channels_scaled_get_chan6_scaled(
const mavlink_message_t* msg)
393 return _MAV_RETURN_int16_t(msg, 14);
401 static inline int16_t mavlink_msg_rc_channels_scaled_get_chan7_scaled(
const mavlink_message_t* msg)
403 return _MAV_RETURN_int16_t(msg, 16);
411 static inline int16_t mavlink_msg_rc_channels_scaled_get_chan8_scaled(
const mavlink_message_t* msg)
413 return _MAV_RETURN_int16_t(msg, 18);
421 static inline uint8_t mavlink_msg_rc_channels_scaled_get_rssi(
const mavlink_message_t* msg)
432 static inline void mavlink_msg_rc_channels_scaled_decode(
const mavlink_message_t* msg,
mavlink_rc_channels_scaled_t* rc_channels_scaled)
434 #if MAVLINK_NEED_BYTE_SWAP
435 rc_channels_scaled->
time_boot_ms = mavlink_msg_rc_channels_scaled_get_time_boot_ms(msg);
436 rc_channels_scaled->
chan1_scaled = mavlink_msg_rc_channels_scaled_get_chan1_scaled(msg);
437 rc_channels_scaled->
chan2_scaled = mavlink_msg_rc_channels_scaled_get_chan2_scaled(msg);
438 rc_channels_scaled->
chan3_scaled = mavlink_msg_rc_channels_scaled_get_chan3_scaled(msg);
439 rc_channels_scaled->
chan4_scaled = mavlink_msg_rc_channels_scaled_get_chan4_scaled(msg);
440 rc_channels_scaled->
chan5_scaled = mavlink_msg_rc_channels_scaled_get_chan5_scaled(msg);
441 rc_channels_scaled->
chan6_scaled = mavlink_msg_rc_channels_scaled_get_chan6_scaled(msg);
442 rc_channels_scaled->
chan7_scaled = mavlink_msg_rc_channels_scaled_get_chan7_scaled(msg);
443 rc_channels_scaled->
chan8_scaled = mavlink_msg_rc_channels_scaled_get_chan8_scaled(msg);
444 rc_channels_scaled->
port = mavlink_msg_rc_channels_scaled_get_port(msg);
445 rc_channels_scaled->
rssi = mavlink_msg_rc_channels_scaled_get_rssi(msg);
uint8_t rssi
Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown.
Definition: mavlink_msg_rc_channels_scaled.h:17
int16_t chan5_scaled
RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
Definition: mavlink_msg_rc_channels_scaled.h:12
#define MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN
Definition: mavlink_msg_rc_channels_scaled.h:20
struct __mavlink_rc_channels_scaled_t mavlink_rc_channels_scaled_t
int16_t chan3_scaled
RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
Definition: mavlink_msg_rc_channels_scaled.h:10
#define _MAV_RETURN_uint8_t(msg, wire_offset)
Definition: protocol.h:238
#define MAVLINK_MSG_ID_RC_CHANNELS_SCALED_CRC
Definition: mavlink_msg_rc_channels_scaled.h:23
int16_t chan4_scaled
RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
Definition: mavlink_msg_rc_channels_scaled.h:11
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
int16_t chan1_scaled
RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
Definition: mavlink_msg_rc_channels_scaled.h:8
#define _mav_put_uint8_t(buf, wire_offset, b)
Definition: protocol.h:134
int16_t chan8_scaled
RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
Definition: mavlink_msg_rc_channels_scaled.h:15
#define _MAV_PAYLOAD_NON_CONST(msg)
Definition: mavlink_types.h:172
mavlink_channel_t
Definition: mavlink_types.h:178
#define MAVLINK_MSG_ID_RC_CHANNELS_SCALED
Definition: mavlink_msg_rc_channels_scaled.h:3
#define _MAV_PAYLOAD(msg)
Definition: mavlink_types.h:171
int16_t chan2_scaled
RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
Definition: mavlink_msg_rc_channels_scaled.h:9
int16_t chan7_scaled
RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
Definition: mavlink_msg_rc_channels_scaled.h:14
uint8_t port
Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more ...
Definition: mavlink_msg_rc_channels_scaled.h:16
uint32_t time_boot_ms
Timestamp (milliseconds since system boot)
Definition: mavlink_msg_rc_channels_scaled.h:7
int16_t chan6_scaled
RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
Definition: mavlink_msg_rc_channels_scaled.h:13
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
#define _mav_put_int16_t(buf, wire_offset, b)
Definition: protocol.h:140
Definition: mavlink_msg_rc_channels_scaled.h:5
#define _mav_put_uint32_t(buf, wire_offset, b)
Definition: protocol.h:141