Classes | Macros | Typedefs | Functions
mavlink_msg_follow_target.h File Reference
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

struct  __mavlink_follow_target_t
 

Macros

#define MAVLINK_MESSAGE_INFO_FOLLOW_TARGET
 
#define MAVLINK_MSG_FOLLOW_TARGET_FIELD_ACC_LEN   3
 
#define MAVLINK_MSG_FOLLOW_TARGET_FIELD_ATTITUDE_Q_LEN   4
 
#define MAVLINK_MSG_FOLLOW_TARGET_FIELD_POSITION_COV_LEN   3
 
#define MAVLINK_MSG_FOLLOW_TARGET_FIELD_RATES_LEN   3
 
#define MAVLINK_MSG_FOLLOW_TARGET_FIELD_VEL_LEN   3
 
#define MAVLINK_MSG_ID_144_CRC   127
 
#define MAVLINK_MSG_ID_144_LEN   93
 
#define MAVLINK_MSG_ID_FOLLOW_TARGET   144
 
#define MAVLINK_MSG_ID_FOLLOW_TARGET_CRC   127
 
#define MAVLINK_MSG_ID_FOLLOW_TARGET_LEN   93
 

Typedefs

typedef struct __mavlink_follow_target_t mavlink_follow_target_t
 

Functions

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. More...
 
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. More...
 
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. More...
 
static uint16_t mavlink_msg_follow_target_get_acc (const mavlink_message_t *msg, float *acc)
 Get field acc from follow_target message. More...
 
static float mavlink_msg_follow_target_get_alt (const mavlink_message_t *msg)
 Get field alt from follow_target message. More...
 
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. More...
 
static uint64_t mavlink_msg_follow_target_get_custom_state (const mavlink_message_t *msg)
 Get field custom_state from follow_target message. More...
 
static uint8_t mavlink_msg_follow_target_get_est_capabilities (const mavlink_message_t *msg)
 Get field est_capabilities from follow_target message. More...
 
static int32_t mavlink_msg_follow_target_get_lat (const mavlink_message_t *msg)
 Get field lat from follow_target message. More...
 
static int32_t mavlink_msg_follow_target_get_lon (const mavlink_message_t *msg)
 Get field lon from follow_target message. More...
 
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. More...
 
static uint16_t mavlink_msg_follow_target_get_rates (const mavlink_message_t *msg, float *rates)
 Get field rates from follow_target message. More...
 
static uint64_t mavlink_msg_follow_target_get_timestamp (const mavlink_message_t *msg)
 Send a follow_target message. More...
 
static uint16_t mavlink_msg_follow_target_get_vel (const mavlink_message_t *msg, float *vel)
 Get field vel from follow_target message. More...
 
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. More...
 
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. More...
 

Macro Definition Documentation

#define MAVLINK_MESSAGE_INFO_FOLLOW_TARGET
Value:
{ \
"FOLLOW_TARGET", \
11, \
{ { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_follow_target_t, timestamp) }, \
{ "custom_state", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_follow_target_t, custom_state) }, \
{ "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_follow_target_t, lat) }, \
{ "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_follow_target_t, lon) }, \
{ "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_follow_target_t, alt) }, \
{ "vel", NULL, MAVLINK_TYPE_FLOAT, 3, 28, offsetof(mavlink_follow_target_t, vel) }, \
{ "acc", NULL, MAVLINK_TYPE_FLOAT, 3, 40, offsetof(mavlink_follow_target_t, acc) }, \
{ "attitude_q", NULL, MAVLINK_TYPE_FLOAT, 4, 52, offsetof(mavlink_follow_target_t, attitude_q) }, \
{ "rates", NULL, MAVLINK_TYPE_FLOAT, 3, 68, offsetof(mavlink_follow_target_t, rates) }, \
{ "position_cov", NULL, MAVLINK_TYPE_FLOAT, 3, 80, offsetof(mavlink_follow_target_t, position_cov) }, \
{ "est_capabilities", NULL, MAVLINK_TYPE_UINT8_T, 0, 92, offsetof(mavlink_follow_target_t, est_capabilities) }, \
} \
}
float alt(float press)
Definition: turbomath.cpp:470
#define NULL
Definition: usbd_def.h:50

Definition at line 32 of file mavlink_msg_follow_target.h.

#define MAVLINK_MSG_FOLLOW_TARGET_FIELD_ACC_LEN   3

Definition at line 27 of file mavlink_msg_follow_target.h.

#define MAVLINK_MSG_FOLLOW_TARGET_FIELD_ATTITUDE_Q_LEN   4

Definition at line 28 of file mavlink_msg_follow_target.h.

#define MAVLINK_MSG_FOLLOW_TARGET_FIELD_POSITION_COV_LEN   3

Definition at line 30 of file mavlink_msg_follow_target.h.

#define MAVLINK_MSG_FOLLOW_TARGET_FIELD_RATES_LEN   3

Definition at line 29 of file mavlink_msg_follow_target.h.

#define MAVLINK_MSG_FOLLOW_TARGET_FIELD_VEL_LEN   3

Definition at line 26 of file mavlink_msg_follow_target.h.

#define MAVLINK_MSG_ID_144_CRC   127

Definition at line 24 of file mavlink_msg_follow_target.h.

#define MAVLINK_MSG_ID_144_LEN   93

Definition at line 21 of file mavlink_msg_follow_target.h.

#define MAVLINK_MSG_ID_FOLLOW_TARGET   144

Definition at line 3 of file mavlink_msg_follow_target.h.

#define MAVLINK_MSG_ID_FOLLOW_TARGET_CRC   127

Definition at line 23 of file mavlink_msg_follow_target.h.

#define MAVLINK_MSG_ID_FOLLOW_TARGET_LEN   93

Definition at line 20 of file mavlink_msg_follow_target.h.

Typedef Documentation

Function Documentation

static void mavlink_msg_follow_target_decode ( const mavlink_message_t *  msg,
mavlink_follow_target_t follow_target 
)
inlinestatic

Decode a follow_target message into a struct.

Parameters
msgThe message to decode
follow_targetC-struct to decode the message contents into

Definition at line 428 of file mavlink_msg_follow_target.h.

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 
)
inlinestatic

Encode a follow_target struct.

Parameters
system_idID of this system
component_idID of this component (e.g. 200 for IMU)
msgThe MAVLink message to compress the data into
follow_targetC-struct to read the message contents from

Definition at line 179 of file mavlink_msg_follow_target.h.

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 
)
inlinestatic

Encode a follow_target struct on a channel.

Parameters
system_idID of this system
component_idID of this component (e.g. 200 for IMU)
chanThe MAVLink channel this message will be sent over
msgThe MAVLink message to compress the data into
follow_targetC-struct to read the message contents from

Definition at line 193 of file mavlink_msg_follow_target.h.

static uint16_t mavlink_msg_follow_target_get_acc ( const mavlink_message_t *  msg,
float *  acc 
)
inlinestatic

Get field acc from follow_target message.

Returns
linear target acceleration (0,0,0) for unknown

Definition at line 377 of file mavlink_msg_follow_target.h.

static float mavlink_msg_follow_target_get_alt ( const mavlink_message_t *  msg)
inlinestatic

Get field alt from follow_target message.

Returns
AMSL, in meters

Definition at line 357 of file mavlink_msg_follow_target.h.

static uint16_t mavlink_msg_follow_target_get_attitude_q ( const mavlink_message_t *  msg,
float *  attitude_q 
)
inlinestatic

Get field attitude_q from follow_target message.

Returns
(1 0 0 0 for unknown)

Definition at line 387 of file mavlink_msg_follow_target.h.

static uint64_t mavlink_msg_follow_target_get_custom_state ( const mavlink_message_t *  msg)
inlinestatic

Get field custom_state from follow_target message.

Returns
button states or switches of a tracker device

Definition at line 417 of file mavlink_msg_follow_target.h.

static uint8_t mavlink_msg_follow_target_get_est_capabilities ( const mavlink_message_t *  msg)
inlinestatic

Get field est_capabilities from follow_target message.

Returns
bit positions for tracker reporting capabilities (POS = 0, VEL = 1, ACCEL = 2, ATT + RATES = 3)

Definition at line 327 of file mavlink_msg_follow_target.h.

static int32_t mavlink_msg_follow_target_get_lat ( const mavlink_message_t *  msg)
inlinestatic

Get field lat from follow_target message.

Returns
Latitude (WGS84), in degrees * 1E7

Definition at line 337 of file mavlink_msg_follow_target.h.

static int32_t mavlink_msg_follow_target_get_lon ( const mavlink_message_t *  msg)
inlinestatic

Get field lon from follow_target message.

Returns
Longitude (WGS84), in degrees * 1E7

Definition at line 347 of file mavlink_msg_follow_target.h.

static uint16_t mavlink_msg_follow_target_get_position_cov ( const mavlink_message_t *  msg,
float *  position_cov 
)
inlinestatic

Get field position_cov from follow_target message.

Returns
eph epv

Definition at line 407 of file mavlink_msg_follow_target.h.

static uint16_t mavlink_msg_follow_target_get_rates ( const mavlink_message_t *  msg,
float *  rates 
)
inlinestatic

Get field rates from follow_target message.

Returns
(0 0 0 for unknown)

Definition at line 397 of file mavlink_msg_follow_target.h.

static uint64_t mavlink_msg_follow_target_get_timestamp ( const mavlink_message_t *  msg)
inlinestatic

Send a follow_target message.

Parameters
chanMAVLink channel to send the message
timestampTimestamp in milliseconds since system boot
est_capabilitiesbit positions for tracker reporting capabilities (POS = 0, VEL = 1, ACCEL = 2, ATT + RATES = 3)
latLatitude (WGS84), in degrees * 1E7
lonLongitude (WGS84), in degrees * 1E7
altAMSL, in meters
veltarget velocity (0,0,0) for unknown
acclinear target acceleration (0,0,0) for unknown
attitude_q(1 0 0 0 for unknown)
rates(0 0 0 for unknown)
position_coveph epv
custom_statebutton states or switches of a tracker device Get field timestamp from follow_target message
Returns
Timestamp in milliseconds since system boot

Definition at line 317 of file mavlink_msg_follow_target.h.

static uint16_t mavlink_msg_follow_target_get_vel ( const mavlink_message_t *  msg,
float *  vel 
)
inlinestatic

Get field vel from follow_target message.

Returns
target velocity (0,0,0) for unknown

Definition at line 367 of file mavlink_msg_follow_target.h.

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 
)
inlinestatic

Pack a follow_target message.

Parameters
system_idID of this system
component_idID of this component (e.g. 200 for IMU)
msgThe MAVLink message to compress the data into
timestampTimestamp in milliseconds since system boot
est_capabilitiesbit positions for tracker reporting capabilities (POS = 0, VEL = 1, ACCEL = 2, ATT + RATES = 3)
latLatitude (WGS84), in degrees * 1E7
lonLongitude (WGS84), in degrees * 1E7
altAMSL, in meters
veltarget velocity (0,0,0) for unknown
acclinear target acceleration (0,0,0) for unknown
attitude_q(1 0 0 0 for unknown)
rates(0 0 0 for unknown)
position_coveph epv
custom_statebutton states or switches of a tracker device
Returns
length of the message in bytes (excluding serial stream start sign)

Definition at line 69 of file mavlink_msg_follow_target.h.

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 
)
inlinestatic

Pack a follow_target message on a channel.

Parameters
system_idID of this system
component_idID of this component (e.g. 200 for IMU)
chanThe MAVLink channel this message will be sent over
msgThe MAVLink message to compress the data into
timestampTimestamp in milliseconds since system boot
est_capabilitiesbit positions for tracker reporting capabilities (POS = 0, VEL = 1, ACCEL = 2, ATT + RATES = 3)
latLatitude (WGS84), in degrees * 1E7
lonLongitude (WGS84), in degrees * 1E7
altAMSL, in meters
veltarget velocity (0,0,0) for unknown
acclinear target acceleration (0,0,0) for unknown
attitude_q(1 0 0 0 for unknown)
rates(0 0 0 for unknown)
position_coveph epv
custom_statebutton states or switches of a tracker device
Returns
length of the message in bytes (excluding serial stream start sign)

Definition at line 129 of file mavlink_msg_follow_target.h.



rosflight_firmware
Author(s): Daniel Koch , James Jackson
autogenerated on Thu Apr 15 2021 05:07:51