Classes | Macros | Typedefs | Functions
mavlink_msg_small_range.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_small_range_t
 

Macros

#define MAVLINK_MESSAGE_INFO_SMALL_RANGE
 
#define MAVLINK_MSG_ID_187_CRC   60
 
#define MAVLINK_MSG_ID_187_LEN   13
 
#define MAVLINK_MSG_ID_SMALL_RANGE   187
 
#define MAVLINK_MSG_ID_SMALL_RANGE_CRC   60
 
#define MAVLINK_MSG_ID_SMALL_RANGE_LEN   13
 

Typedefs

typedef struct __mavlink_small_range_t mavlink_small_range_t
 

Functions

static void mavlink_msg_small_range_decode (const mavlink_message_t *msg, mavlink_small_range_t *small_range)
 Decode a small_range message into a struct. More...
 
static uint16_t mavlink_msg_small_range_encode (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_small_range_t *small_range)
 Encode a small_range struct. More...
 
static uint16_t mavlink_msg_small_range_encode_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_small_range_t *small_range)
 Encode a small_range struct on a channel. More...
 
static float mavlink_msg_small_range_get_max_range (const mavlink_message_t *msg)
 Get field max_range from small_range message. More...
 
static float mavlink_msg_small_range_get_min_range (const mavlink_message_t *msg)
 Get field min_range from small_range message. More...
 
static float mavlink_msg_small_range_get_range (const mavlink_message_t *msg)
 Get field range from small_range message. More...
 
static uint8_t mavlink_msg_small_range_get_type (const mavlink_message_t *msg)
 Send a small_range message. More...
 
static uint16_t mavlink_msg_small_range_pack (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint8_t type, float range, float max_range, float min_range)
 Pack a small_range message. More...
 
static uint16_t mavlink_msg_small_range_pack_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, uint8_t type, float range, float max_range, float min_range)
 Pack a small_range message on a channel. More...
 

Macro Definition Documentation

#define MAVLINK_MESSAGE_INFO_SMALL_RANGE
Value:
{ \
"SMALL_RANGE", \
4, \
{ { "range", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_small_range_t, range) }, \
{ "max_range", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_small_range_t, max_range) }, \
{ "min_range", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_small_range_t, min_range) }, \
{ "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_small_range_t, type) }, \
} \
}
#define NULL
Definition: usbd_def.h:50

Definition at line 21 of file mavlink_msg_small_range.h.

#define MAVLINK_MSG_ID_187_CRC   60

Definition at line 17 of file mavlink_msg_small_range.h.

#define MAVLINK_MSG_ID_187_LEN   13

Definition at line 14 of file mavlink_msg_small_range.h.

#define MAVLINK_MSG_ID_SMALL_RANGE   187

Definition at line 3 of file mavlink_msg_small_range.h.

#define MAVLINK_MSG_ID_SMALL_RANGE_CRC   60

Definition at line 16 of file mavlink_msg_small_range.h.

#define MAVLINK_MSG_ID_SMALL_RANGE_LEN   13

Definition at line 13 of file mavlink_msg_small_range.h.

Typedef Documentation

Function Documentation

static void mavlink_msg_small_range_decode ( const mavlink_message_t *  msg,
mavlink_small_range_t small_range 
)
inlinestatic

Decode a small_range message into a struct.

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

Definition at line 271 of file mavlink_msg_small_range.h.

static uint16_t mavlink_msg_small_range_encode ( uint8_t  system_id,
uint8_t  component_id,
mavlink_message_t *  msg,
const mavlink_small_range_t small_range 
)
inlinestatic

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

Definition at line 123 of file mavlink_msg_small_range.h.

static uint16_t mavlink_msg_small_range_encode_chan ( uint8_t  system_id,
uint8_t  component_id,
uint8_t  chan,
mavlink_message_t *  msg,
const mavlink_small_range_t small_range 
)
inlinestatic

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

Definition at line 137 of file mavlink_msg_small_range.h.

static float mavlink_msg_small_range_get_max_range ( const mavlink_message_t *  msg)
inlinestatic

Get field max_range from small_range message.

Returns
Max Range (m)

Definition at line 250 of file mavlink_msg_small_range.h.

static float mavlink_msg_small_range_get_min_range ( const mavlink_message_t *  msg)
inlinestatic

Get field min_range from small_range message.

Returns
Min Range (m)

Definition at line 260 of file mavlink_msg_small_range.h.

static float mavlink_msg_small_range_get_range ( const mavlink_message_t *  msg)
inlinestatic

Get field range from small_range message.

Returns
Range Measurement (m)

Definition at line 240 of file mavlink_msg_small_range.h.

static uint8_t mavlink_msg_small_range_get_type ( const mavlink_message_t *  msg)
inlinestatic

Send a small_range message.

Parameters
chanMAVLink channel to send the message
typeSensor type
rangeRange Measurement (m)
max_rangeMax Range (m)
min_rangeMin Range (m) Get field type from small_range message
Returns
Sensor type

Definition at line 230 of file mavlink_msg_small_range.h.

static uint16_t mavlink_msg_small_range_pack ( uint8_t  system_id,
uint8_t  component_id,
mavlink_message_t *  msg,
uint8_t  type,
float  range,
float  max_range,
float  min_range 
)
inlinestatic

Pack a small_range 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
typeSensor type
rangeRange Measurement (m)
max_rangeMax Range (m)
min_rangeMin Range (m)
Returns
length of the message in bytes (excluding serial stream start sign)

Definition at line 44 of file mavlink_msg_small_range.h.

static uint16_t mavlink_msg_small_range_pack_chan ( uint8_t  system_id,
uint8_t  component_id,
uint8_t  chan,
mavlink_message_t *  msg,
uint8_t  type,
float  range,
float  max_range,
float  min_range 
)
inlinestatic

Pack a small_range 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
typeSensor type
rangeRange Measurement (m)
max_rangeMax Range (m)
min_rangeMin Range (m)
Returns
length of the message in bytes (excluding serial stream start sign)

Definition at line 85 of file mavlink_msg_small_range.h.



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