Go to the source code of this file.
Classes | |
struct | __mavlink_rosflight_ins_t |
Macros | |
#define | MAVLINK_MESSAGE_INFO_ROSFLIGHT_INS |
#define | MAVLINK_MSG_ID_194_CRC 125 |
#define | MAVLINK_MSG_ID_194_LEN 52 |
#define | MAVLINK_MSG_ID_ROSFLIGHT_INS 194 |
#define | MAVLINK_MSG_ID_ROSFLIGHT_INS_CRC 125 |
#define | MAVLINK_MSG_ID_ROSFLIGHT_INS_LEN 52 |
Typedefs | |
typedef struct __mavlink_rosflight_ins_t | mavlink_rosflight_ins_t |
Functions | |
static void | mavlink_msg_rosflight_ins_decode (const mavlink_message_t *msg, mavlink_rosflight_ins_t *rosflight_ins) |
Decode a rosflight_ins message into a struct. More... | |
static uint16_t | mavlink_msg_rosflight_ins_encode (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_rosflight_ins_t *rosflight_ins) |
Encode a rosflight_ins struct. More... | |
static uint16_t | mavlink_msg_rosflight_ins_encode_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_rosflight_ins_t *rosflight_ins) |
Encode a rosflight_ins struct on a channel. More... | |
static float | mavlink_msg_rosflight_ins_get_p (const mavlink_message_t *msg) |
Get field p from rosflight_ins message. More... | |
static float | mavlink_msg_rosflight_ins_get_pos_down (const mavlink_message_t *msg) |
Get field pos_down from rosflight_ins message. More... | |
static float | mavlink_msg_rosflight_ins_get_pos_east (const mavlink_message_t *msg) |
Get field pos_east from rosflight_ins message. More... | |
static float | mavlink_msg_rosflight_ins_get_pos_north (const mavlink_message_t *msg) |
Send a rosflight_ins message. More... | |
static float | mavlink_msg_rosflight_ins_get_q (const mavlink_message_t *msg) |
Get field q from rosflight_ins message. More... | |
static float | mavlink_msg_rosflight_ins_get_qw (const mavlink_message_t *msg) |
Get field qw from rosflight_ins message. More... | |
static float | mavlink_msg_rosflight_ins_get_qx (const mavlink_message_t *msg) |
Get field qx from rosflight_ins message. More... | |
static float | mavlink_msg_rosflight_ins_get_qy (const mavlink_message_t *msg) |
Get field qy from rosflight_ins message. More... | |
static float | mavlink_msg_rosflight_ins_get_qz (const mavlink_message_t *msg) |
Get field qz from rosflight_ins message. More... | |
static float | mavlink_msg_rosflight_ins_get_r (const mavlink_message_t *msg) |
Get field r from rosflight_ins message. More... | |
static float | mavlink_msg_rosflight_ins_get_u (const mavlink_message_t *msg) |
Get field u from rosflight_ins message. More... | |
static float | mavlink_msg_rosflight_ins_get_v (const mavlink_message_t *msg) |
Get field v from rosflight_ins message. More... | |
static float | mavlink_msg_rosflight_ins_get_w (const mavlink_message_t *msg) |
Get field w from rosflight_ins message. More... | |
static uint16_t | mavlink_msg_rosflight_ins_pack (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, float pos_north, float pos_east, float pos_down, float qw, float qx, float qy, float qz, float u, float v, float w, float p, float q, float r) |
Pack a rosflight_ins message. More... | |
static uint16_t | mavlink_msg_rosflight_ins_pack_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, float pos_north, float pos_east, float pos_down, float qw, float qx, float qy, float qz, float u, float v, float w, float p, float q, float r) |
Pack a rosflight_ins message on a channel. More... | |
#define MAVLINK_MESSAGE_INFO_ROSFLIGHT_INS |
Definition at line 30 of file mavlink_msg_rosflight_ins.h.
#define MAVLINK_MSG_ID_194_CRC 125 |
Definition at line 26 of file mavlink_msg_rosflight_ins.h.
#define MAVLINK_MSG_ID_194_LEN 52 |
Definition at line 23 of file mavlink_msg_rosflight_ins.h.
#define MAVLINK_MSG_ID_ROSFLIGHT_INS 194 |
Definition at line 3 of file mavlink_msg_rosflight_ins.h.
#define MAVLINK_MSG_ID_ROSFLIGHT_INS_CRC 125 |
Definition at line 25 of file mavlink_msg_rosflight_ins.h.
#define MAVLINK_MSG_ID_ROSFLIGHT_INS_LEN 52 |
Definition at line 22 of file mavlink_msg_rosflight_ins.h.
typedef struct __mavlink_rosflight_ins_t mavlink_rosflight_ins_t |
|
inlinestatic |
Decode a rosflight_ins message into a struct.
msg | The message to decode |
rosflight_ins | C-struct to decode the message contents into |
Definition at line 478 of file mavlink_msg_rosflight_ins.h.
|
inlinestatic |
Encode a rosflight_ins 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 |
rosflight_ins | C-struct to read the message contents from |
Definition at line 195 of file mavlink_msg_rosflight_ins.h.
|
inlinestatic |
Encode a rosflight_ins 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 |
rosflight_ins | C-struct to read the message contents from |
Definition at line 209 of file mavlink_msg_rosflight_ins.h.
|
inlinestatic |
Get field p from rosflight_ins message.
Definition at line 447 of file mavlink_msg_rosflight_ins.h.
|
inlinestatic |
Get field pos_down from rosflight_ins message.
Definition at line 367 of file mavlink_msg_rosflight_ins.h.
|
inlinestatic |
Get field pos_east from rosflight_ins message.
Definition at line 357 of file mavlink_msg_rosflight_ins.h.
|
inlinestatic |
Send a rosflight_ins message.
chan | MAVLink channel to send the message |
pos_north | |
pos_east | |
pos_down | |
qw | |
qx | |
qy | |
qz | |
u | |
v | |
w | |
p | |
q | |
r | Get field pos_north from rosflight_ins message |
Definition at line 347 of file mavlink_msg_rosflight_ins.h.
|
inlinestatic |
Get field q from rosflight_ins message.
Definition at line 457 of file mavlink_msg_rosflight_ins.h.
|
inlinestatic |
Get field qw from rosflight_ins message.
Definition at line 377 of file mavlink_msg_rosflight_ins.h.
|
inlinestatic |
Get field qx from rosflight_ins message.
Definition at line 387 of file mavlink_msg_rosflight_ins.h.
|
inlinestatic |
Get field qy from rosflight_ins message.
Definition at line 397 of file mavlink_msg_rosflight_ins.h.
|
inlinestatic |
Get field qz from rosflight_ins message.
Definition at line 407 of file mavlink_msg_rosflight_ins.h.
|
inlinestatic |
Get field r from rosflight_ins message.
Definition at line 467 of file mavlink_msg_rosflight_ins.h.
|
inlinestatic |
Get field u from rosflight_ins message.
Definition at line 417 of file mavlink_msg_rosflight_ins.h.
|
inlinestatic |
Get field v from rosflight_ins message.
Definition at line 427 of file mavlink_msg_rosflight_ins.h.
|
inlinestatic |
Get field w from rosflight_ins message.
Definition at line 437 of file mavlink_msg_rosflight_ins.h.
|
inlinestatic |
Pack a rosflight_ins 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 |
pos_north | |
pos_east | |
pos_down | |
qw | |
qx | |
qy | |
qz | |
u | |
v | |
w | |
p | |
q | |
r |
Definition at line 71 of file mavlink_msg_rosflight_ins.h.
|
inlinestatic |
Pack a rosflight_ins 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 |
pos_north | |
pos_east | |
pos_down | |
qw | |
qx | |
qy | |
qz | |
u | |
v | |
w | |
p | |
q | |
r |
Definition at line 139 of file mavlink_msg_rosflight_ins.h.