mavlink_msg_position_target.h 5.9 KB
Newer Older
James Goppert's avatar
James Goppert committed
1 2 3
// MESSAGE POSITION_TARGET PACKING

#define MAVLINK_MSG_ID_POSITION_TARGET 63
lm's avatar
lm committed
4 5
#define MAVLINK_MSG_ID_POSITION_TARGET_LEN 16
#define MAVLINK_MSG_63_LEN 16
lm's avatar
lm committed
6 7
#define MAVLINK_MSG_ID_POSITION_TARGET_KEY 0x4B
#define MAVLINK_MSG_63_KEY 0x4B
James Goppert's avatar
James Goppert committed
8 9 10

typedef struct __mavlink_position_target_t 
{
lm's avatar
lm committed
11 12 13 14
	float x;	///< x position
	float y;	///< y position
	float z;	///< z position
	float yaw;	///< yaw orientation in radians, 0 = NORTH
James Goppert's avatar
James Goppert committed
15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31

} mavlink_position_target_t;

/**
 * @brief Pack a position_target message
 * @param system_id ID of this system
 * @param component_id ID of this component (e.g. 200 for IMU)
 * @param msg The MAVLink message to compress the data into
 *
 * @param x x position
 * @param y y position
 * @param z z position
 * @param yaw yaw orientation in radians, 0 = NORTH
 * @return length of the message in bytes (excluding serial stream start sign)
 */
static inline uint16_t mavlink_msg_position_target_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, float x, float y, float z, float yaw)
{
lm's avatar
lm committed
32
	mavlink_position_target_t *p = (mavlink_position_target_t *)&msg->payload[0];
James Goppert's avatar
James Goppert committed
33 34
	msg->msgid = MAVLINK_MSG_ID_POSITION_TARGET;

lm's avatar
lm committed
35 36 37 38
	p->x = x;	// float:x position
	p->y = y;	// float:y position
	p->z = z;	// float:z position
	p->yaw = yaw;	// float:yaw orientation in radians, 0 = NORTH
James Goppert's avatar
James Goppert committed
39

lm's avatar
lm committed
40
	return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_POSITION_TARGET_LEN);
James Goppert's avatar
James Goppert committed
41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56
}

/**
 * @brief Pack a position_target message
 * @param system_id ID of this system
 * @param component_id ID of this component (e.g. 200 for IMU)
 * @param chan The MAVLink channel this message was sent over
 * @param msg The MAVLink message to compress the data into
 * @param x x position
 * @param y y position
 * @param z z position
 * @param yaw yaw orientation in radians, 0 = NORTH
 * @return length of the message in bytes (excluding serial stream start sign)
 */
static inline uint16_t mavlink_msg_position_target_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, float x, float y, float z, float yaw)
{
lm's avatar
lm committed
57
	mavlink_position_target_t *p = (mavlink_position_target_t *)&msg->payload[0];
James Goppert's avatar
James Goppert committed
58 59
	msg->msgid = MAVLINK_MSG_ID_POSITION_TARGET;

lm's avatar
lm committed
60 61 62 63
	p->x = x;	// float:x position
	p->y = y;	// float:y position
	p->z = z;	// float:z position
	p->yaw = yaw;	// float:yaw orientation in radians, 0 = NORTH
James Goppert's avatar
James Goppert committed
64

lm's avatar
lm committed
65
	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_POSITION_TARGET_LEN);
James Goppert's avatar
James Goppert committed
66 67 68 69 70 71 72 73 74 75 76 77 78 79 80
}

/**
 * @brief Encode a position_target struct into a message
 *
 * @param system_id ID of this system
 * @param component_id ID of this component (e.g. 200 for IMU)
 * @param msg The MAVLink message to compress the data into
 * @param position_target C-struct to read the message contents from
 */
static inline uint16_t mavlink_msg_position_target_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_position_target_t* position_target)
{
	return mavlink_msg_position_target_pack(system_id, component_id, msg, position_target->x, position_target->y, position_target->z, position_target->yaw);
}

lm's avatar
lm committed
81 82

#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
James Goppert's avatar
James Goppert committed
83 84 85 86 87 88 89 90 91
/**
 * @brief Send a position_target message
 * @param chan MAVLink channel to send the message
 *
 * @param x x position
 * @param y y position
 * @param z z position
 * @param yaw yaw orientation in radians, 0 = NORTH
 */
lm's avatar
lm committed
92 93 94 95 96
static inline void mavlink_msg_position_target_send(mavlink_channel_t chan, float x, float y, float z, float yaw)
{
	mavlink_header_t hdr;
	mavlink_position_target_t payload;

lm's avatar
lm committed
97 98 99 100 101
	MAVLINK_BUFFER_CHECK_START( chan, MAVLINK_MSG_ID_POSITION_TARGET_LEN )
	payload.x = x;	// float:x position
	payload.y = y;	// float:y position
	payload.z = z;	// float:z position
	payload.yaw = yaw;	// float:yaw orientation in radians, 0 = NORTH
lm's avatar
lm committed
102 103 104 105 106 107 108 109 110 111

	hdr.STX = MAVLINK_STX;
	hdr.len = MAVLINK_MSG_ID_POSITION_TARGET_LEN;
	hdr.msgid = MAVLINK_MSG_ID_POSITION_TARGET;
	hdr.sysid = mavlink_system.sysid;
	hdr.compid = mavlink_system.compid;
	hdr.seq = mavlink_get_channel_status(chan)->current_tx_seq;
	mavlink_get_channel_status(chan)->current_tx_seq = hdr.seq + 1;
	mavlink_send_mem(chan, (uint8_t *)&hdr.STX, MAVLINK_NUM_HEADER_BYTES );

lm's avatar
lm committed
112 113 114 115 116 117
	crc_init(&hdr.ck);
	crc_calculate_mem((uint8_t *)&hdr.len, &hdr.ck, MAVLINK_CORE_HEADER_LEN);
	crc_calculate_mem((uint8_t *)&payload, &hdr.ck, hdr.len );
	crc_accumulate( 0x4B, &hdr.ck); /// include key in X25 checksum
	mavlink_send_mem(chan, (uint8_t *)&hdr.ck, MAVLINK_NUM_CHECKSUM_BYTES);
	MAVLINK_BUFFER_CHECK_END
James Goppert's avatar
James Goppert committed
118 119 120 121 122 123 124 125 126 127 128 129
}

#endif
// MESSAGE POSITION_TARGET UNPACKING

/**
 * @brief Get field x from position_target message
 *
 * @return x position
 */
static inline float mavlink_msg_position_target_get_x(const mavlink_message_t* msg)
{
lm's avatar
lm committed
130 131
	mavlink_position_target_t *p = (mavlink_position_target_t *)&msg->payload[0];
	return (float)(p->x);
James Goppert's avatar
James Goppert committed
132 133 134 135 136 137 138 139 140
}

/**
 * @brief Get field y from position_target message
 *
 * @return y position
 */
static inline float mavlink_msg_position_target_get_y(const mavlink_message_t* msg)
{
lm's avatar
lm committed
141 142
	mavlink_position_target_t *p = (mavlink_position_target_t *)&msg->payload[0];
	return (float)(p->y);
James Goppert's avatar
James Goppert committed
143 144 145 146 147 148 149 150 151
}

/**
 * @brief Get field z from position_target message
 *
 * @return z position
 */
static inline float mavlink_msg_position_target_get_z(const mavlink_message_t* msg)
{
lm's avatar
lm committed
152 153
	mavlink_position_target_t *p = (mavlink_position_target_t *)&msg->payload[0];
	return (float)(p->z);
James Goppert's avatar
James Goppert committed
154 155 156 157 158 159 160 161 162
}

/**
 * @brief Get field yaw from position_target message
 *
 * @return yaw orientation in radians, 0 = NORTH
 */
static inline float mavlink_msg_position_target_get_yaw(const mavlink_message_t* msg)
{
lm's avatar
lm committed
163 164
	mavlink_position_target_t *p = (mavlink_position_target_t *)&msg->payload[0];
	return (float)(p->yaw);
James Goppert's avatar
James Goppert committed
165 166 167 168 169 170 171 172 173 174
}

/**
 * @brief Decode a position_target message into a struct
 *
 * @param msg The message to decode
 * @param position_target C-struct to decode the message contents into
 */
static inline void mavlink_msg_position_target_decode(const mavlink_message_t* msg, mavlink_position_target_t* position_target)
{
lm's avatar
lm committed
175
	memcpy( position_target, msg->payload, sizeof(mavlink_position_target_t));
James Goppert's avatar
James Goppert committed
176
}