Classes | Macros | Typedefs | Functions
mavlink_msg_position_target_local_ned.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_position_target_local_ned_t
 

Macros

#define MAVLINK_MESSAGE_INFO_POSITION_TARGET_LOCAL_NED
 
#define MAVLINK_MSG_ID_85_CRC   140
 
#define MAVLINK_MSG_ID_85_LEN   51
 
#define MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED   85
 
#define MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_CRC   140
 
#define MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN   51
 

Typedefs

typedef struct __mavlink_position_target_local_ned_t mavlink_position_target_local_ned_t
 

Functions

static void mavlink_msg_position_target_local_ned_decode (const mavlink_message_t *msg, mavlink_position_target_local_ned_t *position_target_local_ned)
 Decode a position_target_local_ned message into a struct. More...
 
static uint16_t mavlink_msg_position_target_local_ned_encode (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_position_target_local_ned_t *position_target_local_ned)
 Encode a position_target_local_ned struct. More...
 
static uint16_t mavlink_msg_position_target_local_ned_encode_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_position_target_local_ned_t *position_target_local_ned)
 Encode a position_target_local_ned struct on a channel. More...
 
static float mavlink_msg_position_target_local_ned_get_afx (const mavlink_message_t *msg)
 Get field afx from position_target_local_ned message. More...
 
static float mavlink_msg_position_target_local_ned_get_afy (const mavlink_message_t *msg)
 Get field afy from position_target_local_ned message. More...
 
static float mavlink_msg_position_target_local_ned_get_afz (const mavlink_message_t *msg)
 Get field afz from position_target_local_ned message. More...
 
static uint8_t mavlink_msg_position_target_local_ned_get_coordinate_frame (const mavlink_message_t *msg)
 Get field coordinate_frame from position_target_local_ned message. More...
 
static uint32_t mavlink_msg_position_target_local_ned_get_time_boot_ms (const mavlink_message_t *msg)
 Send a position_target_local_ned message. More...
 
static uint16_t mavlink_msg_position_target_local_ned_get_type_mask (const mavlink_message_t *msg)
 Get field type_mask from position_target_local_ned message. More...
 
static float mavlink_msg_position_target_local_ned_get_vx (const mavlink_message_t *msg)
 Get field vx from position_target_local_ned message. More...
 
static float mavlink_msg_position_target_local_ned_get_vy (const mavlink_message_t *msg)
 Get field vy from position_target_local_ned message. More...
 
static float mavlink_msg_position_target_local_ned_get_vz (const mavlink_message_t *msg)
 Get field vz from position_target_local_ned message. More...
 
static float mavlink_msg_position_target_local_ned_get_x (const mavlink_message_t *msg)
 Get field x from position_target_local_ned message. More...
 
static float mavlink_msg_position_target_local_ned_get_y (const mavlink_message_t *msg)
 Get field y from position_target_local_ned message. More...
 
static float mavlink_msg_position_target_local_ned_get_yaw (const mavlink_message_t *msg)
 Get field yaw from position_target_local_ned message. More...
 
static float mavlink_msg_position_target_local_ned_get_yaw_rate (const mavlink_message_t *msg)
 Get field yaw_rate from position_target_local_ned message. More...
 
static float mavlink_msg_position_target_local_ned_get_z (const mavlink_message_t *msg)
 Get field z from position_target_local_ned message. More...
 
static uint16_t mavlink_msg_position_target_local_ned_pack (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint32_t time_boot_ms, uint8_t coordinate_frame, uint16_t type_mask, float x, float y, float z, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate)
 Pack a position_target_local_ned message. More...
 
static uint16_t mavlink_msg_position_target_local_ned_pack_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, uint32_t time_boot_ms, uint8_t coordinate_frame, uint16_t type_mask, float x, float y, float z, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate)
 Pack a position_target_local_ned message on a channel. More...
 

Macro Definition Documentation

#define MAVLINK_MESSAGE_INFO_POSITION_TARGET_LOCAL_NED
Value:
{ \
"POSITION_TARGET_LOCAL_NED", \
14, \
{ { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_position_target_local_ned_t, time_boot_ms) }, \
{ "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_position_target_local_ned_t, vx) }, \
{ "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_position_target_local_ned_t, vy) }, \
{ "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_position_target_local_ned_t, vz) }, \
{ "afx", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_position_target_local_ned_t, afx) }, \
{ "afy", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_position_target_local_ned_t, afy) }, \
{ "afz", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_position_target_local_ned_t, afz) }, \
{ "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_position_target_local_ned_t, yaw) }, \
{ "yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_position_target_local_ned_t, yaw_rate) }, \
{ "type_mask", NULL, MAVLINK_TYPE_UINT16_T, 0, 48, offsetof(mavlink_position_target_local_ned_t, type_mask) }, \
{ "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_position_target_local_ned_t, coordinate_frame) }, \
} \
}
#define NULL
Definition: usbd_def.h:50

Definition at line 31 of file mavlink_msg_position_target_local_ned.h.

#define MAVLINK_MSG_ID_85_CRC   140

Definition at line 27 of file mavlink_msg_position_target_local_ned.h.

#define MAVLINK_MSG_ID_85_LEN   51

Definition at line 24 of file mavlink_msg_position_target_local_ned.h.

#define MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED   85

Definition at line 3 of file mavlink_msg_position_target_local_ned.h.

#define MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_CRC   140

Definition at line 26 of file mavlink_msg_position_target_local_ned.h.

#define MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN   51

Definition at line 23 of file mavlink_msg_position_target_local_ned.h.

Typedef Documentation

Function Documentation

static void mavlink_msg_position_target_local_ned_decode ( const mavlink_message_t *  msg,
mavlink_position_target_local_ned_t position_target_local_ned 
)
inlinestatic

Decode a position_target_local_ned message into a struct.

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

Definition at line 501 of file mavlink_msg_position_target_local_ned.h.

static uint16_t mavlink_msg_position_target_local_ned_encode ( uint8_t  system_id,
uint8_t  component_id,
mavlink_message_t *  msg,
const mavlink_position_target_local_ned_t position_target_local_ned 
)
inlinestatic

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

Definition at line 203 of file mavlink_msg_position_target_local_ned.h.

static uint16_t mavlink_msg_position_target_local_ned_encode_chan ( uint8_t  system_id,
uint8_t  component_id,
uint8_t  chan,
mavlink_message_t *  msg,
const mavlink_position_target_local_ned_t position_target_local_ned 
)
inlinestatic

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

Definition at line 217 of file mavlink_msg_position_target_local_ned.h.

static float mavlink_msg_position_target_local_ned_get_afx ( const mavlink_message_t *  msg)
inlinestatic

Get field afx from position_target_local_ned 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 450 of file mavlink_msg_position_target_local_ned.h.

static float mavlink_msg_position_target_local_ned_get_afy ( const mavlink_message_t *  msg)
inlinestatic

Get field afy from position_target_local_ned 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 460 of file mavlink_msg_position_target_local_ned.h.

static float mavlink_msg_position_target_local_ned_get_afz ( const mavlink_message_t *  msg)
inlinestatic

Get field afz from position_target_local_ned 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 470 of file mavlink_msg_position_target_local_ned.h.

static uint8_t mavlink_msg_position_target_local_ned_get_coordinate_frame ( const mavlink_message_t *  msg)
inlinestatic

Get field coordinate_frame from position_target_local_ned message.

Returns
Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9

Definition at line 370 of file mavlink_msg_position_target_local_ned.h.

static uint32_t mavlink_msg_position_target_local_ned_get_time_boot_ms ( const mavlink_message_t *  msg)
inlinestatic

Send a position_target_local_ned message.

Parameters
chanMAVLink channel to send the message
time_boot_msTimestamp in milliseconds since system boot
coordinate_frameValid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9
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
xX Position in NED frame in meters
yY Position in NED frame in meters
zZ Position in NED frame in meters (note, altitude is negative in NED)
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 position_target_local_ned message
Returns
Timestamp in milliseconds since system boot

Definition at line 360 of file mavlink_msg_position_target_local_ned.h.

static uint16_t mavlink_msg_position_target_local_ned_get_type_mask ( const mavlink_message_t *  msg)
inlinestatic

Get field type_mask from position_target_local_ned 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 380 of file mavlink_msg_position_target_local_ned.h.

static float mavlink_msg_position_target_local_ned_get_vx ( const mavlink_message_t *  msg)
inlinestatic

Get field vx from position_target_local_ned message.

Returns
X velocity in NED frame in meter / s

Definition at line 420 of file mavlink_msg_position_target_local_ned.h.

static float mavlink_msg_position_target_local_ned_get_vy ( const mavlink_message_t *  msg)
inlinestatic

Get field vy from position_target_local_ned message.

Returns
Y velocity in NED frame in meter / s

Definition at line 430 of file mavlink_msg_position_target_local_ned.h.

static float mavlink_msg_position_target_local_ned_get_vz ( const mavlink_message_t *  msg)
inlinestatic

Get field vz from position_target_local_ned message.

Returns
Z velocity in NED frame in meter / s

Definition at line 440 of file mavlink_msg_position_target_local_ned.h.

static float mavlink_msg_position_target_local_ned_get_x ( const mavlink_message_t *  msg)
inlinestatic

Get field x from position_target_local_ned message.

Returns
X Position in NED frame in meters

Definition at line 390 of file mavlink_msg_position_target_local_ned.h.

static float mavlink_msg_position_target_local_ned_get_y ( const mavlink_message_t *  msg)
inlinestatic

Get field y from position_target_local_ned message.

Returns
Y Position in NED frame in meters

Definition at line 400 of file mavlink_msg_position_target_local_ned.h.

static float mavlink_msg_position_target_local_ned_get_yaw ( const mavlink_message_t *  msg)
inlinestatic

Get field yaw from position_target_local_ned message.

Returns
yaw setpoint in rad

Definition at line 480 of file mavlink_msg_position_target_local_ned.h.

static float mavlink_msg_position_target_local_ned_get_yaw_rate ( const mavlink_message_t *  msg)
inlinestatic

Get field yaw_rate from position_target_local_ned message.

Returns
yaw rate setpoint in rad/s

Definition at line 490 of file mavlink_msg_position_target_local_ned.h.

static float mavlink_msg_position_target_local_ned_get_z ( const mavlink_message_t *  msg)
inlinestatic

Get field z from position_target_local_ned message.

Returns
Z Position in NED frame in meters (note, altitude is negative in NED)

Definition at line 410 of file mavlink_msg_position_target_local_ned.h.

static uint16_t mavlink_msg_position_target_local_ned_pack ( uint8_t  system_id,
uint8_t  component_id,
mavlink_message_t *  msg,
uint32_t  time_boot_ms,
uint8_t  coordinate_frame,
uint16_t  type_mask,
float  x,
float  y,
float  z,
float  vx,
float  vy,
float  vz,
float  afx,
float  afy,
float  afz,
float  yaw,
float  yaw_rate 
)
inlinestatic

Pack a position_target_local_ned 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
coordinate_frameValid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9
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
xX Position in NED frame in meters
yY Position in NED frame in meters
zZ Position in NED frame in meters (note, altitude is negative in NED)
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 74 of file mavlink_msg_position_target_local_ned.h.

static uint16_t mavlink_msg_position_target_local_ned_pack_chan ( uint8_t  system_id,
uint8_t  component_id,
uint8_t  chan,
mavlink_message_t *  msg,
uint32_t  time_boot_ms,
uint8_t  coordinate_frame,
uint16_t  type_mask,
float  x,
float  y,
float  z,
float  vx,
float  vy,
float  vz,
float  afx,
float  afy,
float  afz,
float  yaw,
float  yaw_rate 
)
inlinestatic

Pack a position_target_local_ned 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
coordinate_frameValid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9
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
xX Position in NED frame in meters
yY Position in NED frame in meters
zZ Position in NED frame in meters (note, altitude is negative in NED)
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 145 of file mavlink_msg_position_target_local_ned.h.



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