aboutsummaryrefslogtreecommitdiff
path: root/mavlink/include/mavlink/v1.0/common/mavlink_msg_setpoint_6dof.h
diff options
context:
space:
mode:
Diffstat (limited to 'mavlink/include/mavlink/v1.0/common/mavlink_msg_setpoint_6dof.h')
-rw-r--r--mavlink/include/mavlink/v1.0/common/mavlink_msg_setpoint_6dof.h43
1 files changed, 31 insertions, 12 deletions
diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_setpoint_6dof.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_setpoint_6dof.h
index fec38a6a4..f352617a2 100644
--- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_setpoint_6dof.h
+++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_setpoint_6dof.h
@@ -16,6 +16,9 @@ typedef struct __mavlink_setpoint_6dof_t
#define MAVLINK_MSG_ID_SETPOINT_6DOF_LEN 25
#define MAVLINK_MSG_ID_149_LEN 25
+#define MAVLINK_MSG_ID_SETPOINT_6DOF_CRC 15
+#define MAVLINK_MSG_ID_149_CRC 15
+
#define MAVLINK_MESSAGE_INFO_SETPOINT_6DOF { \
@@ -51,7 +54,7 @@ static inline uint16_t mavlink_msg_setpoint_6dof_pack(uint8_t system_id, uint8_t
uint8_t target_system, float trans_x, float trans_y, float trans_z, float rot_x, float rot_y, float rot_z)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[25];
+ char buf[MAVLINK_MSG_ID_SETPOINT_6DOF_LEN];
_mav_put_float(buf, 0, trans_x);
_mav_put_float(buf, 4, trans_y);
_mav_put_float(buf, 8, trans_z);
@@ -60,7 +63,7 @@ static inline uint16_t mavlink_msg_setpoint_6dof_pack(uint8_t system_id, uint8_t
_mav_put_float(buf, 20, rot_z);
_mav_put_uint8_t(buf, 24, target_system);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 25);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SETPOINT_6DOF_LEN);
#else
mavlink_setpoint_6dof_t packet;
packet.trans_x = trans_x;
@@ -71,11 +74,15 @@ static inline uint16_t mavlink_msg_setpoint_6dof_pack(uint8_t system_id, uint8_t
packet.rot_z = rot_z;
packet.target_system = target_system;
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 25);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SETPOINT_6DOF_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_SETPOINT_6DOF;
- return mavlink_finalize_message(msg, system_id, component_id, 25, 15);
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SETPOINT_6DOF_LEN, MAVLINK_MSG_ID_SETPOINT_6DOF_CRC);
+#else
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SETPOINT_6DOF_LEN);
+#endif
}
/**
@@ -98,7 +105,7 @@ static inline uint16_t mavlink_msg_setpoint_6dof_pack_chan(uint8_t system_id, ui
uint8_t target_system,float trans_x,float trans_y,float trans_z,float rot_x,float rot_y,float rot_z)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[25];
+ char buf[MAVLINK_MSG_ID_SETPOINT_6DOF_LEN];
_mav_put_float(buf, 0, trans_x);
_mav_put_float(buf, 4, trans_y);
_mav_put_float(buf, 8, trans_z);
@@ -107,7 +114,7 @@ static inline uint16_t mavlink_msg_setpoint_6dof_pack_chan(uint8_t system_id, ui
_mav_put_float(buf, 20, rot_z);
_mav_put_uint8_t(buf, 24, target_system);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 25);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SETPOINT_6DOF_LEN);
#else
mavlink_setpoint_6dof_t packet;
packet.trans_x = trans_x;
@@ -118,11 +125,15 @@ static inline uint16_t mavlink_msg_setpoint_6dof_pack_chan(uint8_t system_id, ui
packet.rot_z = rot_z;
packet.target_system = target_system;
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 25);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SETPOINT_6DOF_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_SETPOINT_6DOF;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 25, 15);
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SETPOINT_6DOF_LEN, MAVLINK_MSG_ID_SETPOINT_6DOF_CRC);
+#else
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SETPOINT_6DOF_LEN);
+#endif
}
/**
@@ -155,7 +166,7 @@ static inline uint16_t mavlink_msg_setpoint_6dof_encode(uint8_t system_id, uint8
static inline void mavlink_msg_setpoint_6dof_send(mavlink_channel_t chan, uint8_t target_system, float trans_x, float trans_y, float trans_z, float rot_x, float rot_y, float rot_z)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[25];
+ char buf[MAVLINK_MSG_ID_SETPOINT_6DOF_LEN];
_mav_put_float(buf, 0, trans_x);
_mav_put_float(buf, 4, trans_y);
_mav_put_float(buf, 8, trans_z);
@@ -164,7 +175,11 @@ static inline void mavlink_msg_setpoint_6dof_send(mavlink_channel_t chan, uint8_
_mav_put_float(buf, 20, rot_z);
_mav_put_uint8_t(buf, 24, target_system);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SETPOINT_6DOF, buf, 25, 15);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SETPOINT_6DOF, buf, MAVLINK_MSG_ID_SETPOINT_6DOF_LEN, MAVLINK_MSG_ID_SETPOINT_6DOF_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SETPOINT_6DOF, buf, MAVLINK_MSG_ID_SETPOINT_6DOF_LEN);
+#endif
#else
mavlink_setpoint_6dof_t packet;
packet.trans_x = trans_x;
@@ -175,7 +190,11 @@ static inline void mavlink_msg_setpoint_6dof_send(mavlink_channel_t chan, uint8_
packet.rot_z = rot_z;
packet.target_system = target_system;
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SETPOINT_6DOF, (const char *)&packet, 25, 15);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SETPOINT_6DOF, (const char *)&packet, MAVLINK_MSG_ID_SETPOINT_6DOF_LEN, MAVLINK_MSG_ID_SETPOINT_6DOF_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SETPOINT_6DOF, (const char *)&packet, MAVLINK_MSG_ID_SETPOINT_6DOF_LEN);
+#endif
#endif
}
@@ -271,6 +290,6 @@ static inline void mavlink_msg_setpoint_6dof_decode(const mavlink_message_t* msg
setpoint_6dof->rot_z = mavlink_msg_setpoint_6dof_get_rot_z(msg);
setpoint_6dof->target_system = mavlink_msg_setpoint_6dof_get_target_system(msg);
#else
- memcpy(setpoint_6dof, _MAV_PAYLOAD(msg), 25);
+ memcpy(setpoint_6dof, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SETPOINT_6DOF_LEN);
#endif
}