Classes | Macros | Typedefs | Functions
mavlink_msg_param_request_read.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_param_request_read_t
 

Macros

#define MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ
 
#define MAVLINK_MSG_ID_20_CRC   214
 
#define MAVLINK_MSG_ID_20_LEN   20
 
#define MAVLINK_MSG_ID_PARAM_REQUEST_READ   20
 
#define MAVLINK_MSG_ID_PARAM_REQUEST_READ_CRC   214
 
#define MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN   20
 
#define MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN   16
 

Typedefs

typedef struct __mavlink_param_request_read_t mavlink_param_request_read_t
 

Functions

static void mavlink_msg_param_request_read_decode (const mavlink_message_t *msg, mavlink_param_request_read_t *param_request_read)
 Decode a param_request_read message into a struct. More...
 
static uint16_t mavlink_msg_param_request_read_encode (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_param_request_read_t *param_request_read)
 Encode a param_request_read struct. More...
 
static uint16_t mavlink_msg_param_request_read_encode_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_param_request_read_t *param_request_read)
 Encode a param_request_read struct on a channel. More...
 
static uint16_t mavlink_msg_param_request_read_get_param_id (const mavlink_message_t *msg, char *param_id)
 Get field param_id from param_request_read message. More...
 
static int16_t mavlink_msg_param_request_read_get_param_index (const mavlink_message_t *msg)
 Get field param_index from param_request_read message. More...
 
static uint8_t mavlink_msg_param_request_read_get_target_component (const mavlink_message_t *msg)
 Get field target_component from param_request_read message. More...
 
static uint8_t mavlink_msg_param_request_read_get_target_system (const mavlink_message_t *msg)
 Send a param_request_read message. More...
 
static uint16_t mavlink_msg_param_request_read_pack (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint8_t target_system, uint8_t target_component, const char *param_id, int16_t param_index)
 Pack a param_request_read message. More...
 
static uint16_t mavlink_msg_param_request_read_pack_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, uint8_t target_system, uint8_t target_component, const char *param_id, int16_t param_index)
 Pack a param_request_read message on a channel. More...
 

Macro Definition Documentation

#define MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ
Value:
{ \
"PARAM_REQUEST_READ", \
4, \
{ { "param_index", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_param_request_read_t, param_index) }, \
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_param_request_read_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_param_request_read_t, target_component) }, \
{ "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 4, offsetof(mavlink_param_request_read_t, param_id) }, \
} \
}
#define NULL
Definition: usbd_def.h:50

Definition at line 21 of file mavlink_msg_param_request_read.h.

#define MAVLINK_MSG_ID_20_CRC   214

Definition at line 17 of file mavlink_msg_param_request_read.h.

#define MAVLINK_MSG_ID_20_LEN   20

Definition at line 14 of file mavlink_msg_param_request_read.h.

#define MAVLINK_MSG_ID_PARAM_REQUEST_READ   20

Definition at line 3 of file mavlink_msg_param_request_read.h.

#define MAVLINK_MSG_ID_PARAM_REQUEST_READ_CRC   214

Definition at line 16 of file mavlink_msg_param_request_read.h.

#define MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN   20

Definition at line 13 of file mavlink_msg_param_request_read.h.

#define MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN   16

Definition at line 19 of file mavlink_msg_param_request_read.h.

Typedef Documentation

Function Documentation

static void mavlink_msg_param_request_read_decode ( const mavlink_message_t *  msg,
mavlink_param_request_read_t param_request_read 
)
inlinestatic

Decode a param_request_read message into a struct.

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

Definition at line 263 of file mavlink_msg_param_request_read.h.

static uint16_t mavlink_msg_param_request_read_encode ( uint8_t  system_id,
uint8_t  component_id,
mavlink_message_t *  msg,
const mavlink_param_request_read_t param_request_read 
)
inlinestatic

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

Definition at line 119 of file mavlink_msg_param_request_read.h.

static uint16_t mavlink_msg_param_request_read_encode_chan ( uint8_t  system_id,
uint8_t  component_id,
uint8_t  chan,
mavlink_message_t *  msg,
const mavlink_param_request_read_t param_request_read 
)
inlinestatic

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

Definition at line 133 of file mavlink_msg_param_request_read.h.

static uint16_t mavlink_msg_param_request_read_get_param_id ( const mavlink_message_t *  msg,
char *  param_id 
)
inlinestatic

Get field param_id from param_request_read message.

Returns
Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string

Definition at line 242 of file mavlink_msg_param_request_read.h.

static int16_t mavlink_msg_param_request_read_get_param_index ( const mavlink_message_t *  msg)
inlinestatic

Get field param_index from param_request_read message.

Returns
Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored)

Definition at line 252 of file mavlink_msg_param_request_read.h.

static uint8_t mavlink_msg_param_request_read_get_target_component ( const mavlink_message_t *  msg)
inlinestatic

Get field target_component from param_request_read message.

Returns
Component ID

Definition at line 232 of file mavlink_msg_param_request_read.h.

static uint8_t mavlink_msg_param_request_read_get_target_system ( const mavlink_message_t *  msg)
inlinestatic

Send a param_request_read message.

Parameters
chanMAVLink channel to send the message
target_systemSystem ID
target_componentComponent ID
param_idOnboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string
param_indexParameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored) Get field target_system from param_request_read message
Returns
System ID

Definition at line 222 of file mavlink_msg_param_request_read.h.

static uint16_t mavlink_msg_param_request_read_pack ( uint8_t  system_id,
uint8_t  component_id,
mavlink_message_t *  msg,
uint8_t  target_system,
uint8_t  target_component,
const char *  param_id,
int16_t  param_index 
)
inlinestatic

Pack a param_request_read 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
target_systemSystem ID
target_componentComponent ID
param_idOnboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string
param_indexParameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored)
Returns
length of the message in bytes (excluding serial stream start sign)

Definition at line 44 of file mavlink_msg_param_request_read.h.

static uint16_t mavlink_msg_param_request_read_pack_chan ( uint8_t  system_id,
uint8_t  component_id,
uint8_t  chan,
mavlink_message_t *  msg,
uint8_t  target_system,
uint8_t  target_component,
const char *  param_id,
int16_t  param_index 
)
inlinestatic

Pack a param_request_read 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
target_systemSystem ID
target_componentComponent ID
param_idOnboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string
param_indexParameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored)
Returns
length of the message in bytes (excluding serial stream start sign)

Definition at line 83 of file mavlink_msg_param_request_read.h.



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