Go to the source code of this file.
Classes | |
struct | __mavlink_position_target_global_int_t |
Macros | |
#define | MAVLINK_MESSAGE_INFO_POSITION_TARGET_GLOBAL_INT |
#define | MAVLINK_MSG_ID_87_CRC 150 |
#define | MAVLINK_MSG_ID_87_LEN 51 |
#define | MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT 87 |
#define | MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_CRC 150 |
#define | MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN 51 |
Typedefs | |
typedef struct __mavlink_position_target_global_int_t | mavlink_position_target_global_int_t |
Functions | |
static void | mavlink_msg_position_target_global_int_decode (const mavlink_message_t *msg, mavlink_position_target_global_int_t *position_target_global_int) |
Decode a position_target_global_int message into a struct. More... | |
static uint16_t | mavlink_msg_position_target_global_int_encode (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_position_target_global_int_t *position_target_global_int) |
Encode a position_target_global_int struct. More... | |
static uint16_t | mavlink_msg_position_target_global_int_encode_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_position_target_global_int_t *position_target_global_int) |
Encode a position_target_global_int struct on a channel. More... | |
static float | mavlink_msg_position_target_global_int_get_afx (const mavlink_message_t *msg) |
Get field afx from position_target_global_int message. More... | |
static float | mavlink_msg_position_target_global_int_get_afy (const mavlink_message_t *msg) |
Get field afy from position_target_global_int message. More... | |
static float | mavlink_msg_position_target_global_int_get_afz (const mavlink_message_t *msg) |
Get field afz from position_target_global_int message. More... | |
static float | mavlink_msg_position_target_global_int_get_alt (const mavlink_message_t *msg) |
Get field alt from position_target_global_int message. More... | |
static uint8_t | mavlink_msg_position_target_global_int_get_coordinate_frame (const mavlink_message_t *msg) |
Get field coordinate_frame from position_target_global_int message. More... | |
static int32_t | mavlink_msg_position_target_global_int_get_lat_int (const mavlink_message_t *msg) |
Get field lat_int from position_target_global_int message. More... | |
static int32_t | mavlink_msg_position_target_global_int_get_lon_int (const mavlink_message_t *msg) |
Get field lon_int from position_target_global_int message. More... | |
static uint32_t | mavlink_msg_position_target_global_int_get_time_boot_ms (const mavlink_message_t *msg) |
Send a position_target_global_int message. More... | |
static uint16_t | mavlink_msg_position_target_global_int_get_type_mask (const mavlink_message_t *msg) |
Get field type_mask from position_target_global_int message. More... | |
static float | mavlink_msg_position_target_global_int_get_vx (const mavlink_message_t *msg) |
Get field vx from position_target_global_int message. More... | |
static float | mavlink_msg_position_target_global_int_get_vy (const mavlink_message_t *msg) |
Get field vy from position_target_global_int message. More... | |
static float | mavlink_msg_position_target_global_int_get_vz (const mavlink_message_t *msg) |
Get field vz from position_target_global_int message. More... | |
static float | mavlink_msg_position_target_global_int_get_yaw (const mavlink_message_t *msg) |
Get field yaw from position_target_global_int message. More... | |
static float | mavlink_msg_position_target_global_int_get_yaw_rate (const mavlink_message_t *msg) |
Get field yaw_rate from position_target_global_int message. More... | |
static uint16_t | mavlink_msg_position_target_global_int_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, 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 position_target_global_int message. More... | |
static uint16_t | mavlink_msg_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 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 position_target_global_int message on a channel. More... | |
#define MAVLINK_MESSAGE_INFO_POSITION_TARGET_GLOBAL_INT |
Definition at line 31 of file mavlink_msg_position_target_global_int.h.
#define MAVLINK_MSG_ID_87_CRC 150 |
Definition at line 27 of file mavlink_msg_position_target_global_int.h.
#define MAVLINK_MSG_ID_87_LEN 51 |
Definition at line 24 of file mavlink_msg_position_target_global_int.h.
#define MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT 87 |
Definition at line 3 of file mavlink_msg_position_target_global_int.h.
#define MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_CRC 150 |
Definition at line 26 of file mavlink_msg_position_target_global_int.h.
#define MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN 51 |
Definition at line 23 of file mavlink_msg_position_target_global_int.h.
|
inlinestatic |
Decode a position_target_global_int message into a struct.
msg | The message to decode |
position_target_global_int | C-struct to decode the message contents into |
Definition at line 501 of file mavlink_msg_position_target_global_int.h.
|
inlinestatic |
Encode a position_target_global_int struct.
system_id | ID of this system |
component_id | ID of this component (e.g. 200 for IMU) |
msg | The MAVLink message to compress the data into |
position_target_global_int | C-struct to read the message contents from |
Definition at line 203 of file mavlink_msg_position_target_global_int.h.
|
inlinestatic |
Encode a position_target_global_int struct on a channel.
system_id | ID of this system |
component_id | ID of this component (e.g. 200 for IMU) |
chan | The MAVLink channel this message will be sent over |
msg | The MAVLink message to compress the data into |
position_target_global_int | C-struct to read the message contents from |
Definition at line 217 of file mavlink_msg_position_target_global_int.h.
|
inlinestatic |
Get field afx from position_target_global_int message.
Definition at line 450 of file mavlink_msg_position_target_global_int.h.
|
inlinestatic |
Get field afy from position_target_global_int message.
Definition at line 460 of file mavlink_msg_position_target_global_int.h.
|
inlinestatic |
Get field afz from position_target_global_int message.
Definition at line 470 of file mavlink_msg_position_target_global_int.h.
|
inlinestatic |
Get field alt from position_target_global_int message.
Definition at line 410 of file mavlink_msg_position_target_global_int.h.
|
inlinestatic |
Get field coordinate_frame from position_target_global_int message.
Definition at line 370 of file mavlink_msg_position_target_global_int.h.
|
inlinestatic |
Get field lat_int from position_target_global_int message.
Definition at line 390 of file mavlink_msg_position_target_global_int.h.
|
inlinestatic |
Get field lon_int from position_target_global_int message.
Definition at line 400 of file mavlink_msg_position_target_global_int.h.
|
inlinestatic |
Send a position_target_global_int message.
chan | MAVLink channel to send the message |
time_boot_ms | 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. |
coordinate_frame | Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 |
type_mask | 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 |
lat_int | X Position in WGS84 frame in 1e7 * meters |
lon_int | Y Position in WGS84 frame in 1e7 * meters |
alt | Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT |
vx | X velocity in NED frame in meter / s |
vy | Y velocity in NED frame in meter / s |
vz | Z velocity in NED frame in meter / s |
afx | X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N |
afy | Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N |
afz | Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N |
yaw | yaw setpoint in rad |
yaw_rate | yaw rate setpoint in rad/s Get field time_boot_ms from position_target_global_int message |
Definition at line 360 of file mavlink_msg_position_target_global_int.h.
|
inlinestatic |
Get field type_mask from position_target_global_int message.
Definition at line 380 of file mavlink_msg_position_target_global_int.h.
|
inlinestatic |
Get field vx from position_target_global_int message.
Definition at line 420 of file mavlink_msg_position_target_global_int.h.
|
inlinestatic |
Get field vy from position_target_global_int message.
Definition at line 430 of file mavlink_msg_position_target_global_int.h.
|
inlinestatic |
Get field vz from position_target_global_int message.
Definition at line 440 of file mavlink_msg_position_target_global_int.h.
|
inlinestatic |
Get field yaw from position_target_global_int message.
Definition at line 480 of file mavlink_msg_position_target_global_int.h.
|
inlinestatic |
Get field yaw_rate from position_target_global_int message.
Definition at line 490 of file mavlink_msg_position_target_global_int.h.
|
inlinestatic |
Pack a position_target_global_int message.
system_id | ID of this system |
component_id | ID of this component (e.g. 200 for IMU) |
msg | The MAVLink message to compress the data into |
time_boot_ms | 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. |
coordinate_frame | Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 |
type_mask | 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 |
lat_int | X Position in WGS84 frame in 1e7 * meters |
lon_int | Y Position in WGS84 frame in 1e7 * meters |
alt | Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT |
vx | X velocity in NED frame in meter / s |
vy | Y velocity in NED frame in meter / s |
vz | Z velocity in NED frame in meter / s |
afx | X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N |
afy | Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N |
afz | Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N |
yaw | yaw setpoint in rad |
yaw_rate | yaw rate setpoint in rad/s |
Definition at line 74 of file mavlink_msg_position_target_global_int.h.
|
inlinestatic |
Pack a position_target_global_int message on a channel.
system_id | ID of this system |
component_id | ID of this component (e.g. 200 for IMU) |
chan | The MAVLink channel this message will be sent over |
msg | The MAVLink message to compress the data into |
time_boot_ms | 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. |
coordinate_frame | Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11 |
type_mask | 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 |
lat_int | X Position in WGS84 frame in 1e7 * meters |
lon_int | Y Position in WGS84 frame in 1e7 * meters |
alt | Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT |
vx | X velocity in NED frame in meter / s |
vy | Y velocity in NED frame in meter / s |
vz | Z velocity in NED frame in meter / s |
afx | X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N |
afy | Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N |
afz | Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N |
yaw | yaw setpoint in rad |
yaw_rate | yaw rate setpoint in rad/s |
Definition at line 145 of file mavlink_msg_position_target_global_int.h.