3 #define MAVLINK_MSG_ID_FOLLOW_TARGET 144 20 #define MAVLINK_MSG_ID_FOLLOW_TARGET_LEN 93 21 #define MAVLINK_MSG_ID_144_LEN 93 23 #define MAVLINK_MSG_ID_FOLLOW_TARGET_CRC 127 24 #define MAVLINK_MSG_ID_144_CRC 127 26 #define MAVLINK_MSG_FOLLOW_TARGET_FIELD_VEL_LEN 3 27 #define MAVLINK_MSG_FOLLOW_TARGET_FIELD_ACC_LEN 3 28 #define MAVLINK_MSG_FOLLOW_TARGET_FIELD_ATTITUDE_Q_LEN 4 29 #define MAVLINK_MSG_FOLLOW_TARGET_FIELD_RATES_LEN 3 30 #define MAVLINK_MSG_FOLLOW_TARGET_FIELD_POSITION_COV_LEN 3 32 #define MAVLINK_MESSAGE_INFO_FOLLOW_TARGET { \ 35 { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_follow_target_t, timestamp) }, \ 36 { "custom_state", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_follow_target_t, custom_state) }, \ 37 { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_follow_target_t, lat) }, \ 38 { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_follow_target_t, lon) }, \ 39 { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_follow_target_t, alt) }, \ 40 { "vel", NULL, MAVLINK_TYPE_FLOAT, 3, 28, offsetof(mavlink_follow_target_t, vel) }, \ 41 { "acc", NULL, MAVLINK_TYPE_FLOAT, 3, 40, offsetof(mavlink_follow_target_t, acc) }, \ 42 { "attitude_q", NULL, MAVLINK_TYPE_FLOAT, 4, 52, offsetof(mavlink_follow_target_t, attitude_q) }, \ 43 { "rates", NULL, MAVLINK_TYPE_FLOAT, 3, 68, offsetof(mavlink_follow_target_t, rates) }, \ 44 { "position_cov", NULL, MAVLINK_TYPE_FLOAT, 3, 80, offsetof(mavlink_follow_target_t, position_cov) }, \ 45 { "est_capabilities", NULL, MAVLINK_TYPE_UINT8_T, 0, 92, offsetof(mavlink_follow_target_t, est_capabilities) }, \ 70 uint64_t
timestamp, uint8_t
est_capabilities, int32_t
lat, int32_t
lon,
float alt,
const float *
vel,
const float *
acc,
const float *
attitude_q,
const float *
rates,
const float *
position_cov, uint64_t
custom_state)
72 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 80 _mav_put_float_array(buf, 28, vel, 3);
81 _mav_put_float_array(buf, 40, acc, 3);
82 _mav_put_float_array(buf, 52, attitude_q, 4);
83 _mav_put_float_array(buf, 68, rates, 3);
84 _mav_put_float_array(buf, 80, position_cov, 3);
103 #if MAVLINK_CRC_EXTRA 130 mavlink_message_t* msg,
131 uint64_t
timestamp,uint8_t
est_capabilities,int32_t
lat,int32_t
lon,
float alt,
const float *
vel,
const float *
acc,
const float *
attitude_q,
const float *
rates,
const float *
position_cov,uint64_t
custom_state)
133 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 141 _mav_put_float_array(buf, 28, vel, 3);
142 _mav_put_float_array(buf, 40, acc, 3);
143 _mav_put_float_array(buf, 52, attitude_q, 4);
144 _mav_put_float_array(buf, 68, rates, 3);
145 _mav_put_float_array(buf, 80, position_cov, 3);
164 #if MAVLINK_CRC_EXTRA 181 return mavlink_msg_follow_target_pack(system_id, component_id, msg, follow_target->
timestamp, follow_target->
est_capabilities, follow_target->
lat, follow_target->
lon, follow_target->
alt, follow_target->
vel, follow_target->
acc, follow_target->
attitude_q, follow_target->
rates, follow_target->
position_cov, follow_target->
custom_state);
195 return mavlink_msg_follow_target_pack_chan(system_id, component_id, chan, msg, follow_target->
timestamp, follow_target->
est_capabilities, follow_target->
lat, follow_target->
lon, follow_target->
alt, follow_target->
vel, follow_target->
acc, follow_target->
attitude_q, follow_target->
rates, follow_target->
position_cov, follow_target->
custom_state);
214 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS 216 static inline void mavlink_msg_follow_target_send(
mavlink_channel_t chan, uint64_t
timestamp, uint8_t
est_capabilities, int32_t
lat, int32_t
lon,
float alt,
const float *
vel,
const float *
acc,
const float *
attitude_q,
const float *
rates,
const float *
position_cov, uint64_t
custom_state)
218 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 226 _mav_put_float_array(buf, 28,
vel, 3);
227 _mav_put_float_array(buf, 40,
acc, 3);
229 _mav_put_float_array(buf, 68,
rates, 3);
231 #if MAVLINK_CRC_EXTRA 249 #if MAVLINK_CRC_EXTRA 257 #if MAVLINK_MSG_ID_FOLLOW_TARGET_LEN <= MAVLINK_MAX_PAYLOAD_LEN 265 static inline void mavlink_msg_follow_target_send_buf(mavlink_message_t *msgbuf,
mavlink_channel_t chan, uint64_t
timestamp, uint8_t
est_capabilities, int32_t
lat, int32_t
lon,
float alt,
const float *
vel,
const float *
acc,
const float *
attitude_q,
const float *
rates,
const float *
position_cov, uint64_t
custom_state)
267 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 268 char *buf = (
char *)msgbuf;
275 _mav_put_float_array(buf, 28,
vel, 3);
276 _mav_put_float_array(buf, 40,
acc, 3);
278 _mav_put_float_array(buf, 68,
rates, 3);
280 #if MAVLINK_CRC_EXTRA 298 #if MAVLINK_CRC_EXTRA 319 return _MAV_RETURN_uint64_t(msg, 0);
339 return _MAV_RETURN_int32_t(msg, 16);
349 return _MAV_RETURN_int32_t(msg, 20);
359 return _MAV_RETURN_float(msg, 24);
369 return _MAV_RETURN_float_array(msg, vel, 3, 28);
379 return _MAV_RETURN_float_array(msg, acc, 3, 40);
389 return _MAV_RETURN_float_array(msg, attitude_q, 4, 52);
399 return _MAV_RETURN_float_array(msg, rates, 3, 68);
409 return _MAV_RETURN_float_array(msg, position_cov, 3, 80);
419 return _MAV_RETURN_uint64_t(msg, 8);
430 #if MAVLINK_NEED_BYTE_SWAP static uint64_t mavlink_msg_follow_target_get_custom_state(const mavlink_message_t *msg)
Get field custom_state from follow_target message.
#define _mav_put_float(buf, wire_offset, b)
#define MAVLINK_MSG_ID_FOLLOW_TARGET_LEN
static uint16_t mavlink_msg_follow_target_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, uint64_t timestamp, uint8_t est_capabilities, int32_t lat, int32_t lon, float alt, const float *vel, const float *acc, const float *attitude_q, const float *rates, const float *position_cov, uint64_t custom_state)
Pack a follow_target message on a channel.
#define _MAV_RETURN_uint8_t(msg, wire_offset)
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.
static uint16_t mavlink_msg_follow_target_get_rates(const mavlink_message_t *msg, float *rates)
Get field rates from follow_target message.
#define _mav_put_uint8_t(buf, wire_offset, b)
#define _mav_put_uint64_t(buf, wire_offset, b)
#define _mav_put_int32_t(buf, wire_offset, b)
#define _MAV_PAYLOAD_NON_CONST(msg)
static int32_t mavlink_msg_follow_target_get_lon(const mavlink_message_t *msg)
Get field lon from follow_target message.
static uint16_t mavlink_msg_follow_target_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_follow_target_t *follow_target)
Encode a follow_target struct.
static float mavlink_msg_follow_target_get_alt(const mavlink_message_t *msg)
Get field alt from follow_target message.
#define _MAV_PAYLOAD(msg)
static uint16_t mavlink_msg_follow_target_get_attitude_q(const mavlink_message_t *msg, float *attitude_q)
Get field attitude_q from follow_target message.
static uint64_t mavlink_msg_follow_target_get_timestamp(const mavlink_message_t *msg)
Send a follow_target message.
static int32_t mavlink_msg_follow_target_get_lat(const mavlink_message_t *msg)
Get field lat from follow_target message.
#define MAVLINK_MSG_ID_FOLLOW_TARGET
static uint16_t mavlink_msg_follow_target_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_follow_target_t *follow_target)
Encode a follow_target struct on a channel.
static void mav_array_memcpy(void *dest, const void *src, size_t n)
static uint16_t mavlink_msg_follow_target_get_vel(const mavlink_message_t *msg, float *vel)
Get field vel from follow_target message.
#define MAVLINK_MSG_ID_FOLLOW_TARGET_CRC
static uint16_t mavlink_msg_follow_target_get_position_cov(const mavlink_message_t *msg, float *position_cov)
Get field position_cov from follow_target message.
struct __mavlink_follow_target_t mavlink_follow_target_t
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.
static void mavlink_msg_follow_target_decode(const mavlink_message_t *msg, mavlink_follow_target_t *follow_target)
Decode a follow_target message into a struct.
static uint8_t mavlink_msg_follow_target_get_est_capabilities(const mavlink_message_t *msg)
Get field est_capabilities from follow_target message.
static uint16_t mavlink_msg_follow_target_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint64_t timestamp, uint8_t est_capabilities, int32_t lat, int32_t lon, float alt, const float *vel, const float *acc, const float *attitude_q, const float *rates, const float *position_cov, uint64_t custom_state)
Pack a follow_target message.
static uint16_t mavlink_msg_follow_target_get_acc(const mavlink_message_t *msg, float *acc)
Get field acc from follow_target message.