Classes | Macros | Typedefs | Functions
mavlink_msg_set_position_target_global_int.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_set_position_target_global_int_t
 

Macros

#define MAVLINK_MESSAGE_INFO_SET_POSITION_TARGET_GLOBAL_INT
 
#define MAVLINK_MSG_ID_86_CRC   5
 
#define MAVLINK_MSG_ID_86_LEN   53
 
#define MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT   86
 
#define MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_CRC   5
 
#define MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN   53
 

Typedefs

typedef struct __mavlink_set_position_target_global_int_t mavlink_set_position_target_global_int_t
 

Functions

static void mavlink_msg_set_position_target_global_int_decode (const mavlink_message_t *msg, mavlink_set_position_target_global_int_t *set_position_target_global_int)
 Decode a set_position_target_global_int message into a struct. More...
 
static uint16_t mavlink_msg_set_position_target_global_int_encode (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_set_position_target_global_int_t *set_position_target_global_int)
 Encode a set_position_target_global_int struct. More...
 
static uint16_t mavlink_msg_set_position_target_global_int_encode_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_set_position_target_global_int_t *set_position_target_global_int)
 Encode a set_position_target_global_int struct on a channel. More...
 
static float mavlink_msg_set_position_target_global_int_get_afx (const mavlink_message_t *msg)
 Get field afx from set_position_target_global_int message. More...
 
static float mavlink_msg_set_position_target_global_int_get_afy (const mavlink_message_t *msg)
 Get field afy from set_position_target_global_int message. More...
 
static float mavlink_msg_set_position_target_global_int_get_afz (const mavlink_message_t *msg)
 Get field afz from set_position_target_global_int message. More...
 
static float mavlink_msg_set_position_target_global_int_get_alt (const mavlink_message_t *msg)
 Get field alt from set_position_target_global_int message. More...
 
static uint8_t mavlink_msg_set_position_target_global_int_get_coordinate_frame (const mavlink_message_t *msg)
 Get field coordinate_frame from set_position_target_global_int message. More...
 
static int32_t mavlink_msg_set_position_target_global_int_get_lat_int (const mavlink_message_t *msg)
 Get field lat_int from set_position_target_global_int message. More...
 
static int32_t mavlink_msg_set_position_target_global_int_get_lon_int (const mavlink_message_t *msg)
 Get field lon_int from set_position_target_global_int message. More...
 
static uint8_t mavlink_msg_set_position_target_global_int_get_target_component (const mavlink_message_t *msg)
 Get field target_component from set_position_target_global_int message. More...
 
static uint8_t mavlink_msg_set_position_target_global_int_get_target_system (const mavlink_message_t *msg)
 Get field target_system from set_position_target_global_int message. More...
 
static uint32_t mavlink_msg_set_position_target_global_int_get_time_boot_ms (const mavlink_message_t *msg)
 Send a set_position_target_global_int message. More...
 
static uint16_t mavlink_msg_set_position_target_global_int_get_type_mask (const mavlink_message_t *msg)
 Get field type_mask from set_position_target_global_int message. More...
 
static float mavlink_msg_set_position_target_global_int_get_vx (const mavlink_message_t *msg)
 Get field vx from set_position_target_global_int message. More...
 
static float mavlink_msg_set_position_target_global_int_get_vy (const mavlink_message_t *msg)
 Get field vy from set_position_target_global_int message. More...
 
static float mavlink_msg_set_position_target_global_int_get_vz (const mavlink_message_t *msg)
 Get field vz from set_position_target_global_int message. More...
 
static float mavlink_msg_set_position_target_global_int_get_yaw (const mavlink_message_t *msg)
 Get field yaw from set_position_target_global_int message. More...
 
static float mavlink_msg_set_position_target_global_int_get_yaw_rate (const mavlink_message_t *msg)
 Get field yaw_rate from set_position_target_global_int message. More...
 
static uint16_t mavlink_msg_set_position_target_global_int_pack (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint8_t coordinate_frame, uint16_t type_mask, int32_t lat_int, int32_t lon_int, float alt, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate)
 Pack a set_position_target_global_int message. More...
 
static uint16_t mavlink_msg_set_position_target_global_int_pack_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint8_t coordinate_frame, uint16_t type_mask, int32_t lat_int, int32_t lon_int, float alt, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate)
 Pack a set_position_target_global_int message on a channel. More...
 

Macro Definition Documentation

#define MAVLINK_MESSAGE_INFO_SET_POSITION_TARGET_GLOBAL_INT
Value:
{ \
"SET_POSITION_TARGET_GLOBAL_INT", \
16, \
{ { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_set_position_target_global_int_t, time_boot_ms) }, \
{ "lat_int", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_set_position_target_global_int_t, lat_int) }, \
{ "lon_int", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_set_position_target_global_int_t, lon_int) }, \
{ "yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_set_position_target_global_int_t, yaw_rate) }, \
{ "type_mask", NULL, MAVLINK_TYPE_UINT16_T, 0, 48, offsetof(mavlink_set_position_target_global_int_t, type_mask) }, \
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_set_position_target_global_int_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 51, offsetof(mavlink_set_position_target_global_int_t, target_component) }, \
{ "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 52, offsetof(mavlink_set_position_target_global_int_t, coordinate_frame) }, \
} \
}
float alt(float press)
Definition: turbomath.cpp:470
#define NULL
Definition: usbd_def.h:50

Definition at line 33 of file mavlink_msg_set_position_target_global_int.h.

#define MAVLINK_MSG_ID_86_CRC   5

Definition at line 29 of file mavlink_msg_set_position_target_global_int.h.

#define MAVLINK_MSG_ID_86_LEN   53

Definition at line 26 of file mavlink_msg_set_position_target_global_int.h.

#define MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT   86

Definition at line 3 of file mavlink_msg_set_position_target_global_int.h.

#define MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_CRC   5

Definition at line 28 of file mavlink_msg_set_position_target_global_int.h.

#define MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN   53

Definition at line 25 of file mavlink_msg_set_position_target_global_int.h.

Typedef Documentation

Function Documentation

static void mavlink_msg_set_position_target_global_int_decode ( const mavlink_message_t *  msg,
mavlink_set_position_target_global_int_t set_position_target_global_int 
)
inlinestatic

Decode a set_position_target_global_int message into a struct.

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

Definition at line 547 of file mavlink_msg_set_position_target_global_int.h.

static uint16_t mavlink_msg_set_position_target_global_int_encode ( uint8_t  system_id,
uint8_t  component_id,
mavlink_message_t *  msg,
const mavlink_set_position_target_global_int_t set_position_target_global_int 
)
inlinestatic

Encode a set_position_target_global_int 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
set_position_target_global_intC-struct to read the message contents from

Definition at line 219 of file mavlink_msg_set_position_target_global_int.h.

static uint16_t mavlink_msg_set_position_target_global_int_encode_chan ( uint8_t  system_id,
uint8_t  component_id,
uint8_t  chan,
mavlink_message_t *  msg,
const mavlink_set_position_target_global_int_t set_position_target_global_int 
)
inlinestatic

Encode a set_position_target_global_int 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
set_position_target_global_intC-struct to read the message contents from

Definition at line 233 of file mavlink_msg_set_position_target_global_int.h.

static float mavlink_msg_set_position_target_global_int_get_afx ( const mavlink_message_t *  msg)
inlinestatic

Get field afx from set_position_target_global_int message.

Returns
X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N

Definition at line 496 of file mavlink_msg_set_position_target_global_int.h.

static float mavlink_msg_set_position_target_global_int_get_afy ( const mavlink_message_t *  msg)
inlinestatic

Get field afy from set_position_target_global_int message.

Returns
Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N

Definition at line 506 of file mavlink_msg_set_position_target_global_int.h.

static float mavlink_msg_set_position_target_global_int_get_afz ( const mavlink_message_t *  msg)
inlinestatic

Get field afz from set_position_target_global_int message.

Returns
Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N

Definition at line 516 of file mavlink_msg_set_position_target_global_int.h.

static float mavlink_msg_set_position_target_global_int_get_alt ( const mavlink_message_t *  msg)
inlinestatic

Get field alt from set_position_target_global_int message.

Returns
Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT

Definition at line 456 of file mavlink_msg_set_position_target_global_int.h.

static uint8_t mavlink_msg_set_position_target_global_int_get_coordinate_frame ( const mavlink_message_t *  msg)
inlinestatic

Get field coordinate_frame from set_position_target_global_int message.

Returns
Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11

Definition at line 416 of file mavlink_msg_set_position_target_global_int.h.

static int32_t mavlink_msg_set_position_target_global_int_get_lat_int ( const mavlink_message_t *  msg)
inlinestatic

Get field lat_int from set_position_target_global_int message.

Returns
X Position in WGS84 frame in 1e7 * meters

Definition at line 436 of file mavlink_msg_set_position_target_global_int.h.

static int32_t mavlink_msg_set_position_target_global_int_get_lon_int ( const mavlink_message_t *  msg)
inlinestatic

Get field lon_int from set_position_target_global_int message.

Returns
Y Position in WGS84 frame in 1e7 * meters

Definition at line 446 of file mavlink_msg_set_position_target_global_int.h.

static uint8_t mavlink_msg_set_position_target_global_int_get_target_component ( const mavlink_message_t *  msg)
inlinestatic

Get field target_component from set_position_target_global_int message.

Returns
Component ID

Definition at line 406 of file mavlink_msg_set_position_target_global_int.h.

static uint8_t mavlink_msg_set_position_target_global_int_get_target_system ( const mavlink_message_t *  msg)
inlinestatic

Get field target_system from set_position_target_global_int message.

Returns
System ID

Definition at line 396 of file mavlink_msg_set_position_target_global_int.h.

static uint32_t mavlink_msg_set_position_target_global_int_get_time_boot_ms ( const mavlink_message_t *  msg)
inlinestatic

Send a set_position_target_global_int message.

Parameters
chanMAVLink channel to send the message
time_boot_msTimestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency.
target_systemSystem ID
target_componentComponent ID
coordinate_frameValid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11
type_maskBitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate
lat_intX Position in WGS84 frame in 1e7 * meters
lon_intY Position in WGS84 frame in 1e7 * meters
altAltitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT
vxX velocity in NED frame in meter / s
vyY velocity in NED frame in meter / s
vzZ velocity in NED frame in meter / s
afxX acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
afyY acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
afzZ acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
yawyaw setpoint in rad
yaw_rateyaw rate setpoint in rad/s Get field time_boot_ms from set_position_target_global_int message
Returns
Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency.

Definition at line 386 of file mavlink_msg_set_position_target_global_int.h.

static uint16_t mavlink_msg_set_position_target_global_int_get_type_mask ( const mavlink_message_t *  msg)
inlinestatic

Get field type_mask from set_position_target_global_int message.

Returns
Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate

Definition at line 426 of file mavlink_msg_set_position_target_global_int.h.

static float mavlink_msg_set_position_target_global_int_get_vx ( const mavlink_message_t *  msg)
inlinestatic

Get field vx from set_position_target_global_int message.

Returns
X velocity in NED frame in meter / s

Definition at line 466 of file mavlink_msg_set_position_target_global_int.h.

static float mavlink_msg_set_position_target_global_int_get_vy ( const mavlink_message_t *  msg)
inlinestatic

Get field vy from set_position_target_global_int message.

Returns
Y velocity in NED frame in meter / s

Definition at line 476 of file mavlink_msg_set_position_target_global_int.h.

static float mavlink_msg_set_position_target_global_int_get_vz ( const mavlink_message_t *  msg)
inlinestatic

Get field vz from set_position_target_global_int message.

Returns
Z velocity in NED frame in meter / s

Definition at line 486 of file mavlink_msg_set_position_target_global_int.h.

static float mavlink_msg_set_position_target_global_int_get_yaw ( const mavlink_message_t *  msg)
inlinestatic

Get field yaw from set_position_target_global_int message.

Returns
yaw setpoint in rad

Definition at line 526 of file mavlink_msg_set_position_target_global_int.h.

static float mavlink_msg_set_position_target_global_int_get_yaw_rate ( const mavlink_message_t *  msg)
inlinestatic

Get field yaw_rate from set_position_target_global_int message.

Returns
yaw rate setpoint in rad/s

Definition at line 536 of file mavlink_msg_set_position_target_global_int.h.

static uint16_t mavlink_msg_set_position_target_global_int_pack ( uint8_t  system_id,
uint8_t  component_id,
mavlink_message_t *  msg,
uint32_t  time_boot_ms,
uint8_t  target_system,
uint8_t  target_component,
uint8_t  coordinate_frame,
uint16_t  type_mask,
int32_t  lat_int,
int32_t  lon_int,
float  alt,
float  vx,
float  vy,
float  vz,
float  afx,
float  afy,
float  afz,
float  yaw,
float  yaw_rate 
)
inlinestatic

Pack a set_position_target_global_int 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
time_boot_msTimestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency.
target_systemSystem ID
target_componentComponent ID
coordinate_frameValid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11
type_maskBitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate
lat_intX Position in WGS84 frame in 1e7 * meters
lon_intY Position in WGS84 frame in 1e7 * meters
altAltitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT
vxX velocity in NED frame in meter / s
vyY velocity in NED frame in meter / s
vzZ velocity in NED frame in meter / s
afxX acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
afyY acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
afzZ acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
yawyaw setpoint in rad
yaw_rateyaw rate setpoint in rad/s
Returns
length of the message in bytes (excluding serial stream start sign)

Definition at line 80 of file mavlink_msg_set_position_target_global_int.h.

static uint16_t mavlink_msg_set_position_target_global_int_pack_chan ( uint8_t  system_id,
uint8_t  component_id,
uint8_t  chan,
mavlink_message_t *  msg,
uint32_t  time_boot_ms,
uint8_t  target_system,
uint8_t  target_component,
uint8_t  coordinate_frame,
uint16_t  type_mask,
int32_t  lat_int,
int32_t  lon_int,
float  alt,
float  vx,
float  vy,
float  vz,
float  afx,
float  afy,
float  afz,
float  yaw,
float  yaw_rate 
)
inlinestatic

Pack a set_position_target_global_int 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
time_boot_msTimestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency.
target_systemSystem ID
target_componentComponent ID
coordinate_frameValid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11
type_maskBitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate
lat_intX Position in WGS84 frame in 1e7 * meters
lon_intY Position in WGS84 frame in 1e7 * meters
altAltitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT
vxX velocity in NED frame in meter / s
vyY velocity in NED frame in meter / s
vzZ velocity in NED frame in meter / s
afxX acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
afyY acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
afzZ acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
yawyaw setpoint in rad
yaw_rateyaw rate setpoint in rad/s
Returns
length of the message in bytes (excluding serial stream start sign)

Definition at line 157 of file mavlink_msg_set_position_target_global_int.h.



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