Classes | Macros | Typedefs | Functions
mavlink_msg_rosflight_gnss.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_rosflight_gnss_t
 

Macros

#define MAVLINK_MESSAGE_INFO_ROSFLIGHT_GNSS
 
#define MAVLINK_MSG_ID_197_CRC   9
 
#define MAVLINK_MSG_ID_197_LEN   93
 
#define MAVLINK_MSG_ID_ROSFLIGHT_GNSS   197
 
#define MAVLINK_MSG_ID_ROSFLIGHT_GNSS_CRC   9
 
#define MAVLINK_MSG_ID_ROSFLIGHT_GNSS_LEN   93
 

Typedefs

typedef struct __mavlink_rosflight_gnss_t mavlink_rosflight_gnss_t
 

Functions

static void mavlink_msg_rosflight_gnss_decode (const mavlink_message_t *msg, mavlink_rosflight_gnss_t *rosflight_gnss)
 Decode a rosflight_gnss message into a struct. More...
 
static uint16_t mavlink_msg_rosflight_gnss_encode (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_rosflight_gnss_t *rosflight_gnss)
 Encode a rosflight_gnss struct. More...
 
static uint16_t mavlink_msg_rosflight_gnss_encode_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_rosflight_gnss_t *rosflight_gnss)
 Encode a rosflight_gnss struct on a channel. More...
 
static int32_t mavlink_msg_rosflight_gnss_get_ecef_v_x (const mavlink_message_t *msg)
 Get field ecef_v_x from rosflight_gnss message. More...
 
static int32_t mavlink_msg_rosflight_gnss_get_ecef_v_y (const mavlink_message_t *msg)
 Get field ecef_v_y from rosflight_gnss message. More...
 
static int32_t mavlink_msg_rosflight_gnss_get_ecef_v_z (const mavlink_message_t *msg)
 Get field ecef_v_z from rosflight_gnss message. More...
 
static int32_t mavlink_msg_rosflight_gnss_get_ecef_x (const mavlink_message_t *msg)
 Get field ecef_x from rosflight_gnss message. More...
 
static int32_t mavlink_msg_rosflight_gnss_get_ecef_y (const mavlink_message_t *msg)
 Get field ecef_y from rosflight_gnss message. More...
 
static int32_t mavlink_msg_rosflight_gnss_get_ecef_z (const mavlink_message_t *msg)
 Get field ecef_z from rosflight_gnss message. More...
 
static uint8_t mavlink_msg_rosflight_gnss_get_fix_type (const mavlink_message_t *msg)
 Get field fix_type from rosflight_gnss message. More...
 
static uint32_t mavlink_msg_rosflight_gnss_get_h_acc (const mavlink_message_t *msg)
 Get field h_acc from rosflight_gnss message. More...
 
static int32_t mavlink_msg_rosflight_gnss_get_height (const mavlink_message_t *msg)
 Get field height from rosflight_gnss message. More...
 
static int32_t mavlink_msg_rosflight_gnss_get_lat (const mavlink_message_t *msg)
 Get field lat from rosflight_gnss message. More...
 
static int32_t mavlink_msg_rosflight_gnss_get_lon (const mavlink_message_t *msg)
 Get field lon from rosflight_gnss message. More...
 
static uint64_t mavlink_msg_rosflight_gnss_get_nanos (const mavlink_message_t *msg)
 Get field nanos from rosflight_gnss message. More...
 
static uint32_t mavlink_msg_rosflight_gnss_get_p_acc (const mavlink_message_t *msg)
 Get field p_acc from rosflight_gnss message. More...
 
static uint64_t mavlink_msg_rosflight_gnss_get_rosflight_timestamp (const mavlink_message_t *msg)
 Get field rosflight_timestamp from rosflight_gnss message. More...
 
static uint32_t mavlink_msg_rosflight_gnss_get_s_acc (const mavlink_message_t *msg)
 Get field s_acc from rosflight_gnss message. More...
 
static uint64_t mavlink_msg_rosflight_gnss_get_time (const mavlink_message_t *msg)
 Get field time from rosflight_gnss message. More...
 
static uint32_t mavlink_msg_rosflight_gnss_get_time_of_week (const mavlink_message_t *msg)
 Send a rosflight_gnss message. More...
 
static uint32_t mavlink_msg_rosflight_gnss_get_v_acc (const mavlink_message_t *msg)
 Get field v_acc from rosflight_gnss message. More...
 
static int32_t mavlink_msg_rosflight_gnss_get_vel_d (const mavlink_message_t *msg)
 Get field vel_d from rosflight_gnss message. More...
 
static int32_t mavlink_msg_rosflight_gnss_get_vel_e (const mavlink_message_t *msg)
 Get field vel_e from rosflight_gnss message. More...
 
static int32_t mavlink_msg_rosflight_gnss_get_vel_n (const mavlink_message_t *msg)
 Get field vel_n from rosflight_gnss message. More...
 
static uint16_t mavlink_msg_rosflight_gnss_pack (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint32_t time_of_week, uint8_t fix_type, uint64_t time, uint64_t nanos, int32_t lat, int32_t lon, int32_t height, int32_t vel_n, int32_t vel_e, int32_t vel_d, uint32_t h_acc, uint32_t v_acc, int32_t ecef_x, int32_t ecef_y, int32_t ecef_z, uint32_t p_acc, int32_t ecef_v_x, int32_t ecef_v_y, int32_t ecef_v_z, uint32_t s_acc, uint64_t rosflight_timestamp)
 Pack a rosflight_gnss message. More...
 
static uint16_t mavlink_msg_rosflight_gnss_pack_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, uint32_t time_of_week, uint8_t fix_type, uint64_t time, uint64_t nanos, int32_t lat, int32_t lon, int32_t height, int32_t vel_n, int32_t vel_e, int32_t vel_d, uint32_t h_acc, uint32_t v_acc, int32_t ecef_x, int32_t ecef_y, int32_t ecef_z, uint32_t p_acc, int32_t ecef_v_x, int32_t ecef_v_y, int32_t ecef_v_z, uint32_t s_acc, uint64_t rosflight_timestamp)
 Pack a rosflight_gnss message on a channel. More...
 

Macro Definition Documentation

#define MAVLINK_MESSAGE_INFO_ROSFLIGHT_GNSS
Value:
{ \
"ROSFLIGHT_GNSS", \
21, \
{ { "time", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_rosflight_gnss_t, time) }, \
{ "nanos", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_rosflight_gnss_t, nanos) }, \
{ "rosflight_timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 16, offsetof(mavlink_rosflight_gnss_t, rosflight_timestamp) }, \
{ "time_of_week", NULL, MAVLINK_TYPE_UINT32_T, 0, 24, offsetof(mavlink_rosflight_gnss_t, time_of_week) }, \
{ "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 28, offsetof(mavlink_rosflight_gnss_t, lat) }, \
{ "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 32, offsetof(mavlink_rosflight_gnss_t, lon) }, \
{ "height", NULL, MAVLINK_TYPE_INT32_T, 0, 36, offsetof(mavlink_rosflight_gnss_t, height) }, \
{ "vel_n", NULL, MAVLINK_TYPE_INT32_T, 0, 40, offsetof(mavlink_rosflight_gnss_t, vel_n) }, \
{ "vel_e", NULL, MAVLINK_TYPE_INT32_T, 0, 44, offsetof(mavlink_rosflight_gnss_t, vel_e) }, \
{ "vel_d", NULL, MAVLINK_TYPE_INT32_T, 0, 48, offsetof(mavlink_rosflight_gnss_t, vel_d) }, \
{ "h_acc", NULL, MAVLINK_TYPE_UINT32_T, 0, 52, offsetof(mavlink_rosflight_gnss_t, h_acc) }, \
{ "v_acc", NULL, MAVLINK_TYPE_UINT32_T, 0, 56, offsetof(mavlink_rosflight_gnss_t, v_acc) }, \
{ "ecef_x", NULL, MAVLINK_TYPE_INT32_T, 0, 60, offsetof(mavlink_rosflight_gnss_t, ecef_x) }, \
{ "ecef_y", NULL, MAVLINK_TYPE_INT32_T, 0, 64, offsetof(mavlink_rosflight_gnss_t, ecef_y) }, \
{ "ecef_z", NULL, MAVLINK_TYPE_INT32_T, 0, 68, offsetof(mavlink_rosflight_gnss_t, ecef_z) }, \
{ "p_acc", NULL, MAVLINK_TYPE_UINT32_T, 0, 72, offsetof(mavlink_rosflight_gnss_t, p_acc) }, \
{ "ecef_v_x", NULL, MAVLINK_TYPE_INT32_T, 0, 76, offsetof(mavlink_rosflight_gnss_t, ecef_v_x) }, \
{ "ecef_v_y", NULL, MAVLINK_TYPE_INT32_T, 0, 80, offsetof(mavlink_rosflight_gnss_t, ecef_v_y) }, \
{ "ecef_v_z", NULL, MAVLINK_TYPE_INT32_T, 0, 84, offsetof(mavlink_rosflight_gnss_t, ecef_v_z) }, \
{ "s_acc", NULL, MAVLINK_TYPE_UINT32_T, 0, 88, offsetof(mavlink_rosflight_gnss_t, s_acc) }, \
{ "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 92, offsetof(mavlink_rosflight_gnss_t, fix_type) }, \
} \
}
#define NULL
Definition: usbd_def.h:50

Definition at line 38 of file mavlink_msg_rosflight_gnss.h.

#define MAVLINK_MSG_ID_197_CRC   9

Definition at line 34 of file mavlink_msg_rosflight_gnss.h.

#define MAVLINK_MSG_ID_197_LEN   93

Definition at line 31 of file mavlink_msg_rosflight_gnss.h.

#define MAVLINK_MSG_ID_ROSFLIGHT_GNSS   197

Definition at line 3 of file mavlink_msg_rosflight_gnss.h.

#define MAVLINK_MSG_ID_ROSFLIGHT_GNSS_CRC   9

Definition at line 33 of file mavlink_msg_rosflight_gnss.h.

#define MAVLINK_MSG_ID_ROSFLIGHT_GNSS_LEN   93

Definition at line 30 of file mavlink_msg_rosflight_gnss.h.

Typedef Documentation

Function Documentation

static void mavlink_msg_rosflight_gnss_decode ( const mavlink_message_t *  msg,
mavlink_rosflight_gnss_t rosflight_gnss 
)
inlinestatic

Decode a rosflight_gnss message into a struct.

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

Definition at line 662 of file mavlink_msg_rosflight_gnss.h.

static uint16_t mavlink_msg_rosflight_gnss_encode ( uint8_t  system_id,
uint8_t  component_id,
mavlink_message_t *  msg,
const mavlink_rosflight_gnss_t rosflight_gnss 
)
inlinestatic

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

Definition at line 259 of file mavlink_msg_rosflight_gnss.h.

static uint16_t mavlink_msg_rosflight_gnss_encode_chan ( uint8_t  system_id,
uint8_t  component_id,
uint8_t  chan,
mavlink_message_t *  msg,
const mavlink_rosflight_gnss_t rosflight_gnss 
)
inlinestatic

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

Definition at line 273 of file mavlink_msg_rosflight_gnss.h.

static int32_t mavlink_msg_rosflight_gnss_get_ecef_v_x ( const mavlink_message_t *  msg)
inlinestatic

Get field ecef_v_x from rosflight_gnss message.

Returns

Definition at line 611 of file mavlink_msg_rosflight_gnss.h.

static int32_t mavlink_msg_rosflight_gnss_get_ecef_v_y ( const mavlink_message_t *  msg)
inlinestatic

Get field ecef_v_y from rosflight_gnss message.

Returns

Definition at line 621 of file mavlink_msg_rosflight_gnss.h.

static int32_t mavlink_msg_rosflight_gnss_get_ecef_v_z ( const mavlink_message_t *  msg)
inlinestatic

Get field ecef_v_z from rosflight_gnss message.

Returns

Definition at line 631 of file mavlink_msg_rosflight_gnss.h.

static int32_t mavlink_msg_rosflight_gnss_get_ecef_x ( const mavlink_message_t *  msg)
inlinestatic

Get field ecef_x from rosflight_gnss message.

Returns

Definition at line 571 of file mavlink_msg_rosflight_gnss.h.

static int32_t mavlink_msg_rosflight_gnss_get_ecef_y ( const mavlink_message_t *  msg)
inlinestatic

Get field ecef_y from rosflight_gnss message.

Returns

Definition at line 581 of file mavlink_msg_rosflight_gnss.h.

static int32_t mavlink_msg_rosflight_gnss_get_ecef_z ( const mavlink_message_t *  msg)
inlinestatic

Get field ecef_z from rosflight_gnss message.

Returns

Definition at line 591 of file mavlink_msg_rosflight_gnss.h.

static uint8_t mavlink_msg_rosflight_gnss_get_fix_type ( const mavlink_message_t *  msg)
inlinestatic

Get field fix_type from rosflight_gnss message.

Returns

Definition at line 461 of file mavlink_msg_rosflight_gnss.h.

static uint32_t mavlink_msg_rosflight_gnss_get_h_acc ( const mavlink_message_t *  msg)
inlinestatic

Get field h_acc from rosflight_gnss message.

Returns

Definition at line 551 of file mavlink_msg_rosflight_gnss.h.

static int32_t mavlink_msg_rosflight_gnss_get_height ( const mavlink_message_t *  msg)
inlinestatic

Get field height from rosflight_gnss message.

Returns

Definition at line 511 of file mavlink_msg_rosflight_gnss.h.

static int32_t mavlink_msg_rosflight_gnss_get_lat ( const mavlink_message_t *  msg)
inlinestatic

Get field lat from rosflight_gnss message.

Returns

Definition at line 491 of file mavlink_msg_rosflight_gnss.h.

static int32_t mavlink_msg_rosflight_gnss_get_lon ( const mavlink_message_t *  msg)
inlinestatic

Get field lon from rosflight_gnss message.

Returns

Definition at line 501 of file mavlink_msg_rosflight_gnss.h.

static uint64_t mavlink_msg_rosflight_gnss_get_nanos ( const mavlink_message_t *  msg)
inlinestatic

Get field nanos from rosflight_gnss message.

Returns

Definition at line 481 of file mavlink_msg_rosflight_gnss.h.

static uint32_t mavlink_msg_rosflight_gnss_get_p_acc ( const mavlink_message_t *  msg)
inlinestatic

Get field p_acc from rosflight_gnss message.

Returns

Definition at line 601 of file mavlink_msg_rosflight_gnss.h.

static uint64_t mavlink_msg_rosflight_gnss_get_rosflight_timestamp ( const mavlink_message_t *  msg)
inlinestatic

Get field rosflight_timestamp from rosflight_gnss message.

Returns

Definition at line 651 of file mavlink_msg_rosflight_gnss.h.

static uint32_t mavlink_msg_rosflight_gnss_get_s_acc ( const mavlink_message_t *  msg)
inlinestatic

Get field s_acc from rosflight_gnss message.

Returns

Definition at line 641 of file mavlink_msg_rosflight_gnss.h.

static uint64_t mavlink_msg_rosflight_gnss_get_time ( const mavlink_message_t *  msg)
inlinestatic

Get field time from rosflight_gnss message.

Returns

Definition at line 471 of file mavlink_msg_rosflight_gnss.h.

static uint32_t mavlink_msg_rosflight_gnss_get_time_of_week ( const mavlink_message_t *  msg)
inlinestatic

Send a rosflight_gnss message.

Parameters
chanMAVLink channel to send the message
time_of_week
fix_type
time
nanos
lat
lon
height
vel_n
vel_e
vel_d
h_acc
v_acc
ecef_x
ecef_y
ecef_z
p_acc
ecef_v_x
ecef_v_y
ecef_v_z
s_acc
rosflight_timestampGet field time_of_week from rosflight_gnss message
Returns

Definition at line 451 of file mavlink_msg_rosflight_gnss.h.

static uint32_t mavlink_msg_rosflight_gnss_get_v_acc ( const mavlink_message_t *  msg)
inlinestatic

Get field v_acc from rosflight_gnss message.

Returns

Definition at line 561 of file mavlink_msg_rosflight_gnss.h.

static int32_t mavlink_msg_rosflight_gnss_get_vel_d ( const mavlink_message_t *  msg)
inlinestatic

Get field vel_d from rosflight_gnss message.

Returns

Definition at line 541 of file mavlink_msg_rosflight_gnss.h.

static int32_t mavlink_msg_rosflight_gnss_get_vel_e ( const mavlink_message_t *  msg)
inlinestatic

Get field vel_e from rosflight_gnss message.

Returns

Definition at line 531 of file mavlink_msg_rosflight_gnss.h.

static int32_t mavlink_msg_rosflight_gnss_get_vel_n ( const mavlink_message_t *  msg)
inlinestatic

Get field vel_n from rosflight_gnss message.

Returns

Definition at line 521 of file mavlink_msg_rosflight_gnss.h.

static uint16_t mavlink_msg_rosflight_gnss_pack ( uint8_t  system_id,
uint8_t  component_id,
mavlink_message_t *  msg,
uint32_t  time_of_week,
uint8_t  fix_type,
uint64_t  time,
uint64_t  nanos,
int32_t  lat,
int32_t  lon,
int32_t  height,
int32_t  vel_n,
int32_t  vel_e,
int32_t  vel_d,
uint32_t  h_acc,
uint32_t  v_acc,
int32_t  ecef_x,
int32_t  ecef_y,
int32_t  ecef_z,
uint32_t  p_acc,
int32_t  ecef_v_x,
int32_t  ecef_v_y,
int32_t  ecef_v_z,
uint32_t  s_acc,
uint64_t  rosflight_timestamp 
)
inlinestatic

Pack a rosflight_gnss 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_of_week
fix_type
time
nanos
lat
lon
height
vel_n
vel_e
vel_d
h_acc
v_acc
ecef_x
ecef_y
ecef_z
p_acc
ecef_v_x
ecef_v_y
ecef_v_z
s_acc
rosflight_timestamp
Returns
length of the message in bytes (excluding serial stream start sign)

Definition at line 95 of file mavlink_msg_rosflight_gnss.h.

static uint16_t mavlink_msg_rosflight_gnss_pack_chan ( uint8_t  system_id,
uint8_t  component_id,
uint8_t  chan,
mavlink_message_t *  msg,
uint32_t  time_of_week,
uint8_t  fix_type,
uint64_t  time,
uint64_t  nanos,
int32_t  lat,
int32_t  lon,
int32_t  height,
int32_t  vel_n,
int32_t  vel_e,
int32_t  vel_d,
uint32_t  h_acc,
uint32_t  v_acc,
int32_t  ecef_x,
int32_t  ecef_y,
int32_t  ecef_z,
uint32_t  p_acc,
int32_t  ecef_v_x,
int32_t  ecef_v_y,
int32_t  ecef_v_z,
uint32_t  s_acc,
uint64_t  rosflight_timestamp 
)
inlinestatic

Pack a rosflight_gnss 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_of_week
fix_type
time
nanos
lat
lon
height
vel_n
vel_e
vel_d
h_acc
v_acc
ecef_x
ecef_y
ecef_z
p_acc
ecef_v_x
ecef_v_y
ecef_v_z
s_acc
rosflight_timestamp
Returns
length of the message in bytes (excluding serial stream start sign)

Definition at line 187 of file mavlink_msg_rosflight_gnss.h.



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