Classes | Macros | Typedefs | Functions
mavlink_msg_rosflight_output_raw.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_output_raw_t
 

Macros

#define MAVLINK_MESSAGE_INFO_ROSFLIGHT_OUTPUT_RAW
 
#define MAVLINK_MSG_ID_190_CRC   181
 
#define MAVLINK_MSG_ID_190_LEN   64
 
#define MAVLINK_MSG_ID_ROSFLIGHT_OUTPUT_RAW   190
 
#define MAVLINK_MSG_ID_ROSFLIGHT_OUTPUT_RAW_CRC   181
 
#define MAVLINK_MSG_ID_ROSFLIGHT_OUTPUT_RAW_LEN   64
 
#define MAVLINK_MSG_ROSFLIGHT_OUTPUT_RAW_FIELD_VALUES_LEN   14
 

Typedefs

typedef struct __mavlink_rosflight_output_raw_t mavlink_rosflight_output_raw_t
 

Functions

static void mavlink_msg_rosflight_output_raw_decode (const mavlink_message_t *msg, mavlink_rosflight_output_raw_t *rosflight_output_raw)
 Decode a rosflight_output_raw message into a struct. More...
 
static uint16_t mavlink_msg_rosflight_output_raw_encode (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_rosflight_output_raw_t *rosflight_output_raw)
 Encode a rosflight_output_raw struct. More...
 
static uint16_t mavlink_msg_rosflight_output_raw_encode_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_rosflight_output_raw_t *rosflight_output_raw)
 Encode a rosflight_output_raw struct on a channel. More...
 
static uint64_t mavlink_msg_rosflight_output_raw_get_stamp (const mavlink_message_t *msg)
 Send a rosflight_output_raw message. More...
 
static uint16_t mavlink_msg_rosflight_output_raw_get_values (const mavlink_message_t *msg, float *values)
 Get field values from rosflight_output_raw message. More...
 
static uint16_t mavlink_msg_rosflight_output_raw_pack (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint64_t stamp, const float *values)
 Pack a rosflight_output_raw message. More...
 
static uint16_t mavlink_msg_rosflight_output_raw_pack_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, uint64_t stamp, const float *values)
 Pack a rosflight_output_raw message on a channel. More...
 

Macro Definition Documentation

#define MAVLINK_MESSAGE_INFO_ROSFLIGHT_OUTPUT_RAW
Value:
{ \
"ROSFLIGHT_OUTPUT_RAW", \
2, \
{ { "stamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_rosflight_output_raw_t, stamp) }, \
{ "values", NULL, MAVLINK_TYPE_FLOAT, 14, 8, offsetof(mavlink_rosflight_output_raw_t, values) }, \
} \
}
#define NULL
Definition: usbd_def.h:50

Definition at line 19 of file mavlink_msg_rosflight_output_raw.h.

#define MAVLINK_MSG_ID_190_CRC   181

Definition at line 15 of file mavlink_msg_rosflight_output_raw.h.

#define MAVLINK_MSG_ID_190_LEN   64

Definition at line 12 of file mavlink_msg_rosflight_output_raw.h.

#define MAVLINK_MSG_ID_ROSFLIGHT_OUTPUT_RAW   190

Definition at line 3 of file mavlink_msg_rosflight_output_raw.h.

#define MAVLINK_MSG_ID_ROSFLIGHT_OUTPUT_RAW_CRC   181

Definition at line 14 of file mavlink_msg_rosflight_output_raw.h.

#define MAVLINK_MSG_ID_ROSFLIGHT_OUTPUT_RAW_LEN   64

Definition at line 11 of file mavlink_msg_rosflight_output_raw.h.

#define MAVLINK_MSG_ROSFLIGHT_OUTPUT_RAW_FIELD_VALUES_LEN   14

Definition at line 17 of file mavlink_msg_rosflight_output_raw.h.

Typedef Documentation

Function Documentation

static void mavlink_msg_rosflight_output_raw_decode ( const mavlink_message_t *  msg,
mavlink_rosflight_output_raw_t rosflight_output_raw 
)
inlinestatic

Decode a rosflight_output_raw message into a struct.

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

Definition at line 217 of file mavlink_msg_rosflight_output_raw.h.

static uint16_t mavlink_msg_rosflight_output_raw_encode ( uint8_t  system_id,
uint8_t  component_id,
mavlink_message_t *  msg,
const mavlink_rosflight_output_raw_t rosflight_output_raw 
)
inlinestatic

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

Definition at line 103 of file mavlink_msg_rosflight_output_raw.h.

static uint16_t mavlink_msg_rosflight_output_raw_encode_chan ( uint8_t  system_id,
uint8_t  component_id,
uint8_t  chan,
mavlink_message_t *  msg,
const mavlink_rosflight_output_raw_t rosflight_output_raw 
)
inlinestatic

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

Definition at line 117 of file mavlink_msg_rosflight_output_raw.h.

static uint64_t mavlink_msg_rosflight_output_raw_get_stamp ( const mavlink_message_t *  msg)
inlinestatic

Send a rosflight_output_raw message.

Parameters
chanMAVLink channel to send the message
stamp
valuesGet field stamp from rosflight_output_raw message
Returns

Definition at line 196 of file mavlink_msg_rosflight_output_raw.h.

static uint16_t mavlink_msg_rosflight_output_raw_get_values ( const mavlink_message_t *  msg,
float *  values 
)
inlinestatic

Get field values from rosflight_output_raw message.

Returns

Definition at line 206 of file mavlink_msg_rosflight_output_raw.h.

static uint16_t mavlink_msg_rosflight_output_raw_pack ( uint8_t  system_id,
uint8_t  component_id,
mavlink_message_t *  msg,
uint64_t  stamp,
const float *  values 
)
inlinestatic

Pack a rosflight_output_raw 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
stamp
values
Returns
length of the message in bytes (excluding serial stream start sign)

Definition at line 38 of file mavlink_msg_rosflight_output_raw.h.

static uint16_t mavlink_msg_rosflight_output_raw_pack_chan ( uint8_t  system_id,
uint8_t  component_id,
uint8_t  chan,
mavlink_message_t *  msg,
uint64_t  stamp,
const float *  values 
)
inlinestatic

Pack a rosflight_output_raw 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
stamp
values
Returns
length of the message in bytes (excluding serial stream start sign)

Definition at line 71 of file mavlink_msg_rosflight_output_raw.h.



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