Classes | Macros | Typedefs | Functions
mavlink_msg_ping.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_ping_t
 

Macros

#define MAVLINK_MESSAGE_INFO_PING
 
#define MAVLINK_MSG_ID_4_CRC   237
 
#define MAVLINK_MSG_ID_4_LEN   14
 
#define MAVLINK_MSG_ID_PING   4
 
#define MAVLINK_MSG_ID_PING_CRC   237
 
#define MAVLINK_MSG_ID_PING_LEN   14
 

Typedefs

typedef struct __mavlink_ping_t mavlink_ping_t
 

Functions

static void mavlink_msg_ping_decode (const mavlink_message_t *msg, mavlink_ping_t *ping)
 Decode a ping message into a struct. More...
 
static uint16_t mavlink_msg_ping_encode (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_ping_t *ping)
 Encode a ping struct. More...
 
static uint16_t mavlink_msg_ping_encode_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_ping_t *ping)
 Encode a ping struct on a channel. More...
 
static uint32_t mavlink_msg_ping_get_seq (const mavlink_message_t *msg)
 Get field seq from ping message. More...
 
static uint8_t mavlink_msg_ping_get_target_component (const mavlink_message_t *msg)
 Get field target_component from ping message. More...
 
static uint8_t mavlink_msg_ping_get_target_system (const mavlink_message_t *msg)
 Get field target_system from ping message. More...
 
static uint64_t mavlink_msg_ping_get_time_usec (const mavlink_message_t *msg)
 Send a ping message. More...
 
static uint16_t mavlink_msg_ping_pack (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint64_t time_usec, uint32_t seq, uint8_t target_system, uint8_t target_component)
 Pack a ping message. More...
 
static uint16_t mavlink_msg_ping_pack_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, uint64_t time_usec, uint32_t seq, uint8_t target_system, uint8_t target_component)
 Pack a ping message on a channel. More...
 

Macro Definition Documentation

#define MAVLINK_MESSAGE_INFO_PING
Value:
{ \
"PING", \
4, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_ping_t, time_usec) }, \
{ "seq", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_ping_t, seq) }, \
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_ping_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_ping_t, target_component) }, \
} \
}
#define NULL
Definition: usbd_def.h:50

Definition at line 21 of file mavlink_msg_ping.h.

#define MAVLINK_MSG_ID_4_CRC   237

Definition at line 17 of file mavlink_msg_ping.h.

#define MAVLINK_MSG_ID_4_LEN   14

Definition at line 14 of file mavlink_msg_ping.h.

#define MAVLINK_MSG_ID_PING   4

Definition at line 3 of file mavlink_msg_ping.h.

#define MAVLINK_MSG_ID_PING_CRC   237

Definition at line 16 of file mavlink_msg_ping.h.

#define MAVLINK_MSG_ID_PING_LEN   14

Definition at line 13 of file mavlink_msg_ping.h.

Typedef Documentation

Function Documentation

static void mavlink_msg_ping_decode ( const mavlink_message_t *  msg,
mavlink_ping_t ping 
)
inlinestatic

Decode a ping message into a struct.

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

Definition at line 271 of file mavlink_msg_ping.h.

static uint16_t mavlink_msg_ping_encode ( uint8_t  system_id,
uint8_t  component_id,
mavlink_message_t *  msg,
const mavlink_ping_t ping 
)
inlinestatic

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

Definition at line 123 of file mavlink_msg_ping.h.

static uint16_t mavlink_msg_ping_encode_chan ( uint8_t  system_id,
uint8_t  component_id,
uint8_t  chan,
mavlink_message_t *  msg,
const mavlink_ping_t ping 
)
inlinestatic

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

Definition at line 137 of file mavlink_msg_ping.h.

static uint32_t mavlink_msg_ping_get_seq ( const mavlink_message_t *  msg)
inlinestatic

Get field seq from ping message.

Returns
PING sequence

Definition at line 240 of file mavlink_msg_ping.h.

static uint8_t mavlink_msg_ping_get_target_component ( const mavlink_message_t *  msg)
inlinestatic

Get field target_component from ping message.

Returns
0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system

Definition at line 260 of file mavlink_msg_ping.h.

static uint8_t mavlink_msg_ping_get_target_system ( const mavlink_message_t *  msg)
inlinestatic

Get field target_system from ping message.

Returns
0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system

Definition at line 250 of file mavlink_msg_ping.h.

static uint64_t mavlink_msg_ping_get_time_usec ( const mavlink_message_t *  msg)
inlinestatic

Send a ping message.

Parameters
chanMAVLink channel to send the message
time_usecUnix timestamp in microseconds or since system boot if smaller than MAVLink epoch (1.1.2009)
seqPING sequence
target_system0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system
target_component0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system Get field time_usec from ping message
Returns
Unix timestamp in microseconds or since system boot if smaller than MAVLink epoch (1.1.2009)

Definition at line 230 of file mavlink_msg_ping.h.

static uint16_t mavlink_msg_ping_pack ( uint8_t  system_id,
uint8_t  component_id,
mavlink_message_t *  msg,
uint64_t  time_usec,
uint32_t  seq,
uint8_t  target_system,
uint8_t  target_component 
)
inlinestatic

Pack a ping 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_usecUnix timestamp in microseconds or since system boot if smaller than MAVLink epoch (1.1.2009)
seqPING sequence
target_system0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system
target_component0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system
Returns
length of the message in bytes (excluding serial stream start sign)

Definition at line 44 of file mavlink_msg_ping.h.

static uint16_t mavlink_msg_ping_pack_chan ( uint8_t  system_id,
uint8_t  component_id,
uint8_t  chan,
mavlink_message_t *  msg,
uint64_t  time_usec,
uint32_t  seq,
uint8_t  target_system,
uint8_t  target_component 
)
inlinestatic

Pack a ping 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_usecUnix timestamp in microseconds or since system boot if smaller than MAVLink epoch (1.1.2009)
seqPING sequence
target_system0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system
target_component0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system
Returns
length of the message in bytes (excluding serial stream start sign)

Definition at line 85 of file mavlink_msg_ping.h.



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