mavlink_msg_waypoint_request.h 5.74 KB
Newer Older
James Goppert's avatar
James Goppert committed
1 2 3
// MESSAGE WAYPOINT_REQUEST PACKING

#define MAVLINK_MSG_ID_WAYPOINT_REQUEST 40
lm's avatar
lm committed
4 5
#define MAVLINK_MSG_ID_WAYPOINT_REQUEST_LEN 4
#define MAVLINK_MSG_40_LEN 4
lm's avatar
lm committed
6 7
#define MAVLINK_MSG_ID_WAYPOINT_REQUEST_KEY 0xC0
#define MAVLINK_MSG_40_KEY 0xC0
James Goppert's avatar
James Goppert committed
8 9 10

typedef struct __mavlink_waypoint_request_t 
{
lm's avatar
lm committed
11 12 13
	uint16_t seq;	///< Sequence
	uint8_t target_system;	///< System ID
	uint8_t target_component;	///< Component ID
James Goppert's avatar
James Goppert committed
14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29

} mavlink_waypoint_request_t;

/**
 * @brief Pack a waypoint_request 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 target_system System ID
 * @param target_component Component ID
 * @param seq Sequence
 * @return length of the message in bytes (excluding serial stream start sign)
 */
static inline uint16_t mavlink_msg_waypoint_request_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, uint16_t seq)
{
lm's avatar
lm committed
30
	mavlink_waypoint_request_t *p = (mavlink_waypoint_request_t *)&msg->payload[0];
James Goppert's avatar
James Goppert committed
31 32
	msg->msgid = MAVLINK_MSG_ID_WAYPOINT_REQUEST;

lm's avatar
lm committed
33 34 35
	p->target_system = target_system;	// uint8_t:System ID
	p->target_component = target_component;	// uint8_t:Component ID
	p->seq = seq;	// uint16_t:Sequence
James Goppert's avatar
James Goppert committed
36

lm's avatar
lm committed
37
	return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_WAYPOINT_REQUEST_LEN);
James Goppert's avatar
James Goppert committed
38 39 40 41 42 43 44 45 46 47 48 49 50 51 52
}

/**
 * @brief Pack a waypoint_request 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 target_system System ID
 * @param target_component Component ID
 * @param seq Sequence
 * @return length of the message in bytes (excluding serial stream start sign)
 */
static inline uint16_t mavlink_msg_waypoint_request_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t target_system, uint8_t target_component, uint16_t seq)
{
lm's avatar
lm committed
53
	mavlink_waypoint_request_t *p = (mavlink_waypoint_request_t *)&msg->payload[0];
James Goppert's avatar
James Goppert committed
54 55
	msg->msgid = MAVLINK_MSG_ID_WAYPOINT_REQUEST;

lm's avatar
lm committed
56 57 58
	p->target_system = target_system;	// uint8_t:System ID
	p->target_component = target_component;	// uint8_t:Component ID
	p->seq = seq;	// uint16_t:Sequence
James Goppert's avatar
James Goppert committed
59

lm's avatar
lm committed
60
	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_WAYPOINT_REQUEST_LEN);
James Goppert's avatar
James Goppert committed
61 62 63 64 65 66 67 68 69 70 71 72 73 74 75
}

/**
 * @brief Encode a waypoint_request 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 waypoint_request C-struct to read the message contents from
 */
static inline uint16_t mavlink_msg_waypoint_request_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_waypoint_request_t* waypoint_request)
{
	return mavlink_msg_waypoint_request_pack(system_id, component_id, msg, waypoint_request->target_system, waypoint_request->target_component, waypoint_request->seq);
}

lm's avatar
lm committed
76 77

#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
James Goppert's avatar
James Goppert committed
78 79 80 81 82 83 84 85
/**
 * @brief Send a waypoint_request message
 * @param chan MAVLink channel to send the message
 *
 * @param target_system System ID
 * @param target_component Component ID
 * @param seq Sequence
 */
lm's avatar
lm committed
86 87 88 89 90
static inline void mavlink_msg_waypoint_request_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t seq)
{
	mavlink_header_t hdr;
	mavlink_waypoint_request_t payload;

lm's avatar
lm committed
91 92 93 94
	MAVLINK_BUFFER_CHECK_START( chan, MAVLINK_MSG_ID_WAYPOINT_REQUEST_LEN )
	payload.target_system = target_system;	// uint8_t:System ID
	payload.target_component = target_component;	// uint8_t:Component ID
	payload.seq = seq;	// uint16_t:Sequence
lm's avatar
lm committed
95 96 97 98 99 100 101 102 103 104

	hdr.STX = MAVLINK_STX;
	hdr.len = MAVLINK_MSG_ID_WAYPOINT_REQUEST_LEN;
	hdr.msgid = MAVLINK_MSG_ID_WAYPOINT_REQUEST;
	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
105 106 107 108 109 110
	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( 0xC0, &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
111 112 113 114 115 116 117 118 119 120 121 122
}

#endif
// MESSAGE WAYPOINT_REQUEST UNPACKING

/**
 * @brief Get field target_system from waypoint_request message
 *
 * @return System ID
 */
static inline uint8_t mavlink_msg_waypoint_request_get_target_system(const mavlink_message_t* msg)
{
lm's avatar
lm committed
123 124
	mavlink_waypoint_request_t *p = (mavlink_waypoint_request_t *)&msg->payload[0];
	return (uint8_t)(p->target_system);
James Goppert's avatar
James Goppert committed
125 126 127 128 129 130 131 132 133
}

/**
 * @brief Get field target_component from waypoint_request message
 *
 * @return Component ID
 */
static inline uint8_t mavlink_msg_waypoint_request_get_target_component(const mavlink_message_t* msg)
{
lm's avatar
lm committed
134 135
	mavlink_waypoint_request_t *p = (mavlink_waypoint_request_t *)&msg->payload[0];
	return (uint8_t)(p->target_component);
James Goppert's avatar
James Goppert committed
136 137 138 139 140 141 142 143 144
}

/**
 * @brief Get field seq from waypoint_request message
 *
 * @return Sequence
 */
static inline uint16_t mavlink_msg_waypoint_request_get_seq(const mavlink_message_t* msg)
{
lm's avatar
lm committed
145 146
	mavlink_waypoint_request_t *p = (mavlink_waypoint_request_t *)&msg->payload[0];
	return (uint16_t)(p->seq);
James Goppert's avatar
James Goppert committed
147 148 149 150 151 152 153 154 155 156
}

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