aboutsummaryrefslogtreecommitdiff
path: root/mavlink/include/mavlink/v1.0/common/mavlink_msg_rc_channels_scaled.h
diff options
context:
space:
mode:
Diffstat (limited to 'mavlink/include/mavlink/v1.0/common/mavlink_msg_rc_channels_scaled.h')
-rw-r--r--mavlink/include/mavlink/v1.0/common/mavlink_msg_rc_channels_scaled.h43
1 files changed, 31 insertions, 12 deletions
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_rc_channels_scaled.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_rc_channels_scaled.h
index dd21d4162..be6322bcd 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_rc_channels_scaled.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_rc_channels_scaled.h
@@ -20,6 +20,9 @@ typedef struct __mavlink_rc_channels_scaled_t
#define MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN 22
#define MAVLINK_MSG_ID_34_LEN 22
+#define MAVLINK_MSG_ID_RC_CHANNELS_SCALED_CRC 237
+#define MAVLINK_MSG_ID_34_CRC 237
+
#define MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED { \
@@ -63,7 +66,7 @@ static inline uint16_t mavlink_msg_rc_channels_scaled_pack(uint8_t system_id, ui
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)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[22];
+ char buf[MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_int16_t(buf, 4, chan1_scaled);
_mav_put_int16_t(buf, 6, chan2_scaled);
@@ -76,7 +79,7 @@ static inline uint16_t mavlink_msg_rc_channels_scaled_pack(uint8_t system_id, ui
_mav_put_uint8_t(buf, 20, port);
_mav_put_uint8_t(buf, 21, rssi);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 22);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN);
#else
mavlink_rc_channels_scaled_t packet;
packet.time_boot_ms = time_boot_ms;
@@ -91,11 +94,15 @@ static inline uint16_t mavlink_msg_rc_channels_scaled_pack(uint8_t system_id, ui
packet.port = port;
packet.rssi = rssi;
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 22);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS_SCALED;
- return mavlink_finalize_message(msg, system_id, component_id, 22, 237);
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_CRC);
+#else
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN);
+#endif
}
/**
@@ -122,7 +129,7 @@ static inline uint16_t mavlink_msg_rc_channels_scaled_pack_chan(uint8_t system_i
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)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[22];
+ char buf[MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_int16_t(buf, 4, chan1_scaled);
_mav_put_int16_t(buf, 6, chan2_scaled);
@@ -135,7 +142,7 @@ static inline uint16_t mavlink_msg_rc_channels_scaled_pack_chan(uint8_t system_i
_mav_put_uint8_t(buf, 20, port);
_mav_put_uint8_t(buf, 21, rssi);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 22);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN);
#else
mavlink_rc_channels_scaled_t packet;
packet.time_boot_ms = time_boot_ms;
@@ -150,11 +157,15 @@ static inline uint16_t mavlink_msg_rc_channels_scaled_pack_chan(uint8_t system_i
packet.port = port;
packet.rssi = rssi;
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 22);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS_SCALED;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 22, 237);
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_CRC);
+#else
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN);
+#endif
}
/**
@@ -191,7 +202,7 @@ static inline uint16_t mavlink_msg_rc_channels_scaled_encode(uint8_t system_id,
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)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[22];
+ char buf[MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_int16_t(buf, 4, chan1_scaled);
_mav_put_int16_t(buf, 6, chan2_scaled);
@@ -204,7 +215,11 @@ static inline void mavlink_msg_rc_channels_scaled_send(mavlink_channel_t chan, u
_mav_put_uint8_t(buf, 20, port);
_mav_put_uint8_t(buf, 21, rssi);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_SCALED, buf, 22, 237);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_SCALED, buf, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_SCALED, buf, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN);
+#endif
#else
mavlink_rc_channels_scaled_t packet;
packet.time_boot_ms = time_boot_ms;
@@ -219,7 +234,11 @@ static inline void mavlink_msg_rc_channels_scaled_send(mavlink_channel_t chan, u
packet.port = port;
packet.rssi = rssi;
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_SCALED, (const char *)&packet, 22, 237);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_SCALED, (const char *)&packet, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_SCALED, (const char *)&packet, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN);
+#endif
#endif
}
@@ -359,6 +378,6 @@ static inline void mavlink_msg_rc_channels_scaled_decode(const mavlink_message_t
rc_channels_scaled->port = mavlink_msg_rc_channels_scaled_get_port(msg);
rc_channels_scaled->rssi = mavlink_msg_rc_channels_scaled_get_rssi(msg);
#else
- memcpy(rc_channels_scaled, _MAV_PAYLOAD(msg), 22);
+ memcpy(rc_channels_scaled, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN);
#endif
}