Classes | Macros | Typedefs | Functions
mavlink_msg_distance_sensor.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_distance_sensor_t
 

Macros

#define MAVLINK_MESSAGE_INFO_DISTANCE_SENSOR
 
#define MAVLINK_MSG_ID_132_CRC   85
 
#define MAVLINK_MSG_ID_132_LEN   14
 
#define MAVLINK_MSG_ID_DISTANCE_SENSOR   132
 
#define MAVLINK_MSG_ID_DISTANCE_SENSOR_CRC   85
 
#define MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN   14
 

Typedefs

typedef struct __mavlink_distance_sensor_t mavlink_distance_sensor_t
 

Functions

static void mavlink_msg_distance_sensor_decode (const mavlink_message_t *msg, mavlink_distance_sensor_t *distance_sensor)
 Decode a distance_sensor message into a struct. More...
 
static uint16_t mavlink_msg_distance_sensor_encode (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_distance_sensor_t *distance_sensor)
 Encode a distance_sensor struct. More...
 
static uint16_t mavlink_msg_distance_sensor_encode_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_distance_sensor_t *distance_sensor)
 Encode a distance_sensor struct on a channel. More...
 
static uint8_t mavlink_msg_distance_sensor_get_covariance (const mavlink_message_t *msg)
 Get field covariance from distance_sensor message. More...
 
static uint16_t mavlink_msg_distance_sensor_get_current_distance (const mavlink_message_t *msg)
 Get field current_distance from distance_sensor message. More...
 
static uint8_t mavlink_msg_distance_sensor_get_id (const mavlink_message_t *msg)
 Get field id from distance_sensor message. More...
 
static uint16_t mavlink_msg_distance_sensor_get_max_distance (const mavlink_message_t *msg)
 Get field max_distance from distance_sensor message. More...
 
static uint16_t mavlink_msg_distance_sensor_get_min_distance (const mavlink_message_t *msg)
 Get field min_distance from distance_sensor message. More...
 
static uint8_t mavlink_msg_distance_sensor_get_orientation (const mavlink_message_t *msg)
 Get field orientation from distance_sensor message. More...
 
static uint32_t mavlink_msg_distance_sensor_get_time_boot_ms (const mavlink_message_t *msg)
 Send a distance_sensor message. More...
 
static uint8_t mavlink_msg_distance_sensor_get_type (const mavlink_message_t *msg)
 Get field type from distance_sensor message. More...
 
static uint16_t mavlink_msg_distance_sensor_pack (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint32_t time_boot_ms, uint16_t min_distance, uint16_t max_distance, uint16_t current_distance, uint8_t type, uint8_t id, uint8_t orientation, uint8_t covariance)
 Pack a distance_sensor message. More...
 
static uint16_t mavlink_msg_distance_sensor_pack_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, uint32_t time_boot_ms, uint16_t min_distance, uint16_t max_distance, uint16_t current_distance, uint8_t type, uint8_t id, uint8_t orientation, uint8_t covariance)
 Pack a distance_sensor message on a channel. More...
 

Macro Definition Documentation

#define MAVLINK_MESSAGE_INFO_DISTANCE_SENSOR
Value:
{ \
"DISTANCE_SENSOR", \
8, \
{ { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_distance_sensor_t, time_boot_ms) }, \
{ "min_distance", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_distance_sensor_t, min_distance) }, \
{ "max_distance", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_distance_sensor_t, max_distance) }, \
{ "current_distance", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_distance_sensor_t, current_distance) }, \
{ "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_distance_sensor_t, type) }, \
{ "id", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_distance_sensor_t, id) }, \
{ "orientation", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_distance_sensor_t, orientation) }, \
{ "covariance", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_distance_sensor_t, covariance) }, \
} \
}
#define NULL
Definition: usbd_def.h:50

Definition at line 25 of file mavlink_msg_distance_sensor.h.

#define MAVLINK_MSG_ID_132_CRC   85

Definition at line 21 of file mavlink_msg_distance_sensor.h.

#define MAVLINK_MSG_ID_132_LEN   14

Definition at line 18 of file mavlink_msg_distance_sensor.h.

#define MAVLINK_MSG_ID_DISTANCE_SENSOR   132

Definition at line 3 of file mavlink_msg_distance_sensor.h.

#define MAVLINK_MSG_ID_DISTANCE_SENSOR_CRC   85

Definition at line 20 of file mavlink_msg_distance_sensor.h.

#define MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN   14

Definition at line 17 of file mavlink_msg_distance_sensor.h.

Typedef Documentation

Function Documentation

static void mavlink_msg_distance_sensor_decode ( const mavlink_message_t *  msg,
mavlink_distance_sensor_t distance_sensor 
)
inlinestatic

Decode a distance_sensor message into a struct.

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

Definition at line 363 of file mavlink_msg_distance_sensor.h.

static uint16_t mavlink_msg_distance_sensor_encode ( uint8_t  system_id,
uint8_t  component_id,
mavlink_message_t *  msg,
const mavlink_distance_sensor_t distance_sensor 
)
inlinestatic

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

Definition at line 155 of file mavlink_msg_distance_sensor.h.

static uint16_t mavlink_msg_distance_sensor_encode_chan ( uint8_t  system_id,
uint8_t  component_id,
uint8_t  chan,
mavlink_message_t *  msg,
const mavlink_distance_sensor_t distance_sensor 
)
inlinestatic

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

Definition at line 169 of file mavlink_msg_distance_sensor.h.

static uint8_t mavlink_msg_distance_sensor_get_covariance ( const mavlink_message_t *  msg)
inlinestatic

Get field covariance from distance_sensor message.

Returns
Measurement covariance in centimeters, 0 for unknown / invalid readings

Definition at line 352 of file mavlink_msg_distance_sensor.h.

static uint16_t mavlink_msg_distance_sensor_get_current_distance ( const mavlink_message_t *  msg)
inlinestatic

Get field current_distance from distance_sensor message.

Returns
Current distance reading

Definition at line 312 of file mavlink_msg_distance_sensor.h.

static uint8_t mavlink_msg_distance_sensor_get_id ( const mavlink_message_t *  msg)
inlinestatic

Get field id from distance_sensor message.

Returns
Onboard ID of the sensor

Definition at line 332 of file mavlink_msg_distance_sensor.h.

static uint16_t mavlink_msg_distance_sensor_get_max_distance ( const mavlink_message_t *  msg)
inlinestatic

Get field max_distance from distance_sensor message.

Returns
Maximum distance the sensor can measure in centimeters

Definition at line 302 of file mavlink_msg_distance_sensor.h.

static uint16_t mavlink_msg_distance_sensor_get_min_distance ( const mavlink_message_t *  msg)
inlinestatic

Get field min_distance from distance_sensor message.

Returns
Minimum distance the sensor can measure in centimeters

Definition at line 292 of file mavlink_msg_distance_sensor.h.

static uint8_t mavlink_msg_distance_sensor_get_orientation ( const mavlink_message_t *  msg)
inlinestatic

Get field orientation from distance_sensor message.

Returns
Direction the sensor faces from MAV_SENSOR_ORIENTATION enum.

Definition at line 342 of file mavlink_msg_distance_sensor.h.

static uint32_t mavlink_msg_distance_sensor_get_time_boot_ms ( const mavlink_message_t *  msg)
inlinestatic

Send a distance_sensor message.

Parameters
chanMAVLink channel to send the message
time_boot_msTime since system boot
min_distanceMinimum distance the sensor can measure in centimeters
max_distanceMaximum distance the sensor can measure in centimeters
current_distanceCurrent distance reading
typeType from MAV_DISTANCE_SENSOR enum.
idOnboard ID of the sensor
orientationDirection the sensor faces from MAV_SENSOR_ORIENTATION enum.
covarianceMeasurement covariance in centimeters, 0 for unknown / invalid readings Get field time_boot_ms from distance_sensor message
Returns
Time since system boot

Definition at line 282 of file mavlink_msg_distance_sensor.h.

static uint8_t mavlink_msg_distance_sensor_get_type ( const mavlink_message_t *  msg)
inlinestatic

Get field type from distance_sensor message.

Returns
Type from MAV_DISTANCE_SENSOR enum.

Definition at line 322 of file mavlink_msg_distance_sensor.h.

static uint16_t mavlink_msg_distance_sensor_pack ( uint8_t  system_id,
uint8_t  component_id,
mavlink_message_t *  msg,
uint32_t  time_boot_ms,
uint16_t  min_distance,
uint16_t  max_distance,
uint16_t  current_distance,
uint8_t  type,
uint8_t  id,
uint8_t  orientation,
uint8_t  covariance 
)
inlinestatic

Pack a distance_sensor 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_boot_msTime since system boot
min_distanceMinimum distance the sensor can measure in centimeters
max_distanceMaximum distance the sensor can measure in centimeters
current_distanceCurrent distance reading
typeType from MAV_DISTANCE_SENSOR enum.
idOnboard ID of the sensor
orientationDirection the sensor faces from MAV_SENSOR_ORIENTATION enum.
covarianceMeasurement covariance in centimeters, 0 for unknown / invalid readings
Returns
length of the message in bytes (excluding serial stream start sign)

Definition at line 56 of file mavlink_msg_distance_sensor.h.

static uint16_t mavlink_msg_distance_sensor_pack_chan ( uint8_t  system_id,
uint8_t  component_id,
uint8_t  chan,
mavlink_message_t *  msg,
uint32_t  time_boot_ms,
uint16_t  min_distance,
uint16_t  max_distance,
uint16_t  current_distance,
uint8_t  type,
uint8_t  id,
uint8_t  orientation,
uint8_t  covariance 
)
inlinestatic

Pack a distance_sensor 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_boot_msTime since system boot
min_distanceMinimum distance the sensor can measure in centimeters
max_distanceMaximum distance the sensor can measure in centimeters
current_distanceCurrent distance reading
typeType from MAV_DISTANCE_SENSOR enum.
idOnboard ID of the sensor
orientationDirection the sensor faces from MAV_SENSOR_ORIENTATION enum.
covarianceMeasurement covariance in centimeters, 0 for unknown / invalid readings
Returns
length of the message in bytes (excluding serial stream start sign)

Definition at line 109 of file mavlink_msg_distance_sensor.h.



rosflight_firmware
Author(s): Daniel Koch , James Jackson
autogenerated on Wed Jul 3 2019 19:59:26