Go to the source code of this file.
Classes | |
struct | __mavlink_set_position_target_local_ned_t |
Macros | |
#define | MAVLINK_MESSAGE_INFO_SET_POSITION_TARGET_LOCAL_NED |
#define | MAVLINK_MSG_ID_84_CRC 143 |
#define | MAVLINK_MSG_ID_84_LEN 53 |
#define | MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED 84 |
#define | MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_CRC 143 |
#define | MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN 53 |
Typedefs | |
typedef struct __mavlink_set_position_target_local_ned_t | mavlink_set_position_target_local_ned_t |
Functions | |
static void | mavlink_msg_set_position_target_local_ned_decode (const mavlink_message_t *msg, mavlink_set_position_target_local_ned_t *set_position_target_local_ned) |
Decode a set_position_target_local_ned message into a struct. More... | |
static uint16_t | mavlink_msg_set_position_target_local_ned_encode (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_set_position_target_local_ned_t *set_position_target_local_ned) |
Encode a set_position_target_local_ned struct. More... | |
static uint16_t | mavlink_msg_set_position_target_local_ned_encode_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_set_position_target_local_ned_t *set_position_target_local_ned) |
Encode a set_position_target_local_ned struct on a channel. More... | |
static float | mavlink_msg_set_position_target_local_ned_get_afx (const mavlink_message_t *msg) |
Get field afx from set_position_target_local_ned message. More... | |
static float | mavlink_msg_set_position_target_local_ned_get_afy (const mavlink_message_t *msg) |
Get field afy from set_position_target_local_ned message. More... | |
static float | mavlink_msg_set_position_target_local_ned_get_afz (const mavlink_message_t *msg) |
Get field afz from set_position_target_local_ned message. More... | |
static uint8_t | mavlink_msg_set_position_target_local_ned_get_coordinate_frame (const mavlink_message_t *msg) |
Get field coordinate_frame from set_position_target_local_ned message. More... | |
static uint8_t | mavlink_msg_set_position_target_local_ned_get_target_component (const mavlink_message_t *msg) |
Get field target_component from set_position_target_local_ned message. More... | |
static uint8_t | mavlink_msg_set_position_target_local_ned_get_target_system (const mavlink_message_t *msg) |
Get field target_system from set_position_target_local_ned message. More... | |
static uint32_t | mavlink_msg_set_position_target_local_ned_get_time_boot_ms (const mavlink_message_t *msg) |
Send a set_position_target_local_ned message. More... | |
static uint16_t | mavlink_msg_set_position_target_local_ned_get_type_mask (const mavlink_message_t *msg) |
Get field type_mask from set_position_target_local_ned message. More... | |
static float | mavlink_msg_set_position_target_local_ned_get_vx (const mavlink_message_t *msg) |
Get field vx from set_position_target_local_ned message. More... | |
static float | mavlink_msg_set_position_target_local_ned_get_vy (const mavlink_message_t *msg) |
Get field vy from set_position_target_local_ned message. More... | |
static float | mavlink_msg_set_position_target_local_ned_get_vz (const mavlink_message_t *msg) |
Get field vz from set_position_target_local_ned message. More... | |
static float | mavlink_msg_set_position_target_local_ned_get_x (const mavlink_message_t *msg) |
Get field x from set_position_target_local_ned message. More... | |
static float | mavlink_msg_set_position_target_local_ned_get_y (const mavlink_message_t *msg) |
Get field y from set_position_target_local_ned message. More... | |
static float | mavlink_msg_set_position_target_local_ned_get_yaw (const mavlink_message_t *msg) |
Get field yaw from set_position_target_local_ned message. More... | |
static float | mavlink_msg_set_position_target_local_ned_get_yaw_rate (const mavlink_message_t *msg) |
Get field yaw_rate from set_position_target_local_ned message. More... | |
static float | mavlink_msg_set_position_target_local_ned_get_z (const mavlink_message_t *msg) |
Get field z from set_position_target_local_ned message. More... | |
static uint16_t | mavlink_msg_set_position_target_local_ned_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, 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 set_position_target_local_ned message. More... | |
static uint16_t | mavlink_msg_set_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 target_system, uint8_t target_component, 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 set_position_target_local_ned message on a channel. More... | |
#define MAVLINK_MESSAGE_INFO_SET_POSITION_TARGET_LOCAL_NED |
Definition at line 33 of file mavlink_msg_set_position_target_local_ned.h.
#define MAVLINK_MSG_ID_84_CRC 143 |
Definition at line 29 of file mavlink_msg_set_position_target_local_ned.h.
#define MAVLINK_MSG_ID_84_LEN 53 |
Definition at line 26 of file mavlink_msg_set_position_target_local_ned.h.
#define MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED 84 |
Definition at line 3 of file mavlink_msg_set_position_target_local_ned.h.
#define MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_CRC 143 |
Definition at line 28 of file mavlink_msg_set_position_target_local_ned.h.
#define MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN 53 |
Definition at line 25 of file mavlink_msg_set_position_target_local_ned.h.
|
inlinestatic |
Decode a set_position_target_local_ned message into a struct.
msg | The message to decode |
set_position_target_local_ned | C-struct to decode the message contents into |
Definition at line 547 of file mavlink_msg_set_position_target_local_ned.h.
|
inlinestatic |
Encode a set_position_target_local_ned 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 |
set_position_target_local_ned | C-struct to read the message contents from |
Definition at line 219 of file mavlink_msg_set_position_target_local_ned.h.
|
inlinestatic |
Encode a set_position_target_local_ned 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 |
set_position_target_local_ned | C-struct to read the message contents from |
Definition at line 233 of file mavlink_msg_set_position_target_local_ned.h.
|
inlinestatic |
Get field afx from set_position_target_local_ned message.
Definition at line 496 of file mavlink_msg_set_position_target_local_ned.h.
|
inlinestatic |
Get field afy from set_position_target_local_ned message.
Definition at line 506 of file mavlink_msg_set_position_target_local_ned.h.
|
inlinestatic |
Get field afz from set_position_target_local_ned message.
Definition at line 516 of file mavlink_msg_set_position_target_local_ned.h.
|
inlinestatic |
Get field coordinate_frame from set_position_target_local_ned message.
Definition at line 416 of file mavlink_msg_set_position_target_local_ned.h.
|
inlinestatic |
Get field target_component from set_position_target_local_ned message.
Definition at line 406 of file mavlink_msg_set_position_target_local_ned.h.
|
inlinestatic |
Get field target_system from set_position_target_local_ned message.
Definition at line 396 of file mavlink_msg_set_position_target_local_ned.h.
|
inlinestatic |
Send a set_position_target_local_ned message.
chan | MAVLink channel to send the message |
time_boot_ms | Timestamp in milliseconds since system boot |
target_system | System ID |
target_component | Component ID |
coordinate_frame | 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 |
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 |
x | X Position in NED frame in meters |
y | Y Position in NED frame in meters |
z | Z Position in NED frame in meters (note, altitude is negative in NED) |
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 set_position_target_local_ned message |
Definition at line 386 of file mavlink_msg_set_position_target_local_ned.h.
|
inlinestatic |
Get field type_mask from set_position_target_local_ned message.
Definition at line 426 of file mavlink_msg_set_position_target_local_ned.h.
|
inlinestatic |
Get field vx from set_position_target_local_ned message.
Definition at line 466 of file mavlink_msg_set_position_target_local_ned.h.
|
inlinestatic |
Get field vy from set_position_target_local_ned message.
Definition at line 476 of file mavlink_msg_set_position_target_local_ned.h.
|
inlinestatic |
Get field vz from set_position_target_local_ned message.
Definition at line 486 of file mavlink_msg_set_position_target_local_ned.h.
|
inlinestatic |
Get field x from set_position_target_local_ned message.
Definition at line 436 of file mavlink_msg_set_position_target_local_ned.h.
|
inlinestatic |
Get field y from set_position_target_local_ned message.
Definition at line 446 of file mavlink_msg_set_position_target_local_ned.h.
|
inlinestatic |
Get field yaw from set_position_target_local_ned message.
Definition at line 526 of file mavlink_msg_set_position_target_local_ned.h.
|
inlinestatic |
Get field yaw_rate from set_position_target_local_ned message.
Definition at line 536 of file mavlink_msg_set_position_target_local_ned.h.
|
inlinestatic |
Get field z from set_position_target_local_ned message.
Definition at line 456 of file mavlink_msg_set_position_target_local_ned.h.
|
inlinestatic |
Pack a set_position_target_local_ned 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 |
target_system | System ID |
target_component | Component ID |
coordinate_frame | 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 |
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 |
x | X Position in NED frame in meters |
y | Y Position in NED frame in meters |
z | Z Position in NED frame in meters (note, altitude is negative in NED) |
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 80 of file mavlink_msg_set_position_target_local_ned.h.
|
inlinestatic |
Pack a set_position_target_local_ned 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 |
target_system | System ID |
target_component | Component ID |
coordinate_frame | 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 |
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 |
x | X Position in NED frame in meters |
y | Y Position in NED frame in meters |
z | Z Position in NED frame in meters (note, altitude is negative in NED) |
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 157 of file mavlink_msg_set_position_target_local_ned.h.