Go to the source code of this file.
Classes | |
struct | __mavlink_distance_sensor_t |
Defines | |
#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. | |
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. | |
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. | |
static uint8_t | mavlink_msg_distance_sensor_get_covariance (const mavlink_message_t *msg) |
Get field covariance from distance_sensor message. | |
static uint16_t | mavlink_msg_distance_sensor_get_current_distance (const mavlink_message_t *msg) |
Get field current_distance from distance_sensor message. | |
static uint8_t | mavlink_msg_distance_sensor_get_id (const mavlink_message_t *msg) |
Get field id from distance_sensor message. | |
static uint16_t | mavlink_msg_distance_sensor_get_max_distance (const mavlink_message_t *msg) |
Get field max_distance from distance_sensor message. | |
static uint16_t | mavlink_msg_distance_sensor_get_min_distance (const mavlink_message_t *msg) |
Get field min_distance from distance_sensor message. | |
static uint8_t | mavlink_msg_distance_sensor_get_orientation (const mavlink_message_t *msg) |
Get field orientation from distance_sensor message. | |
static uint32_t | mavlink_msg_distance_sensor_get_time_boot_ms (const mavlink_message_t *msg) |
Send a distance_sensor message. | |
static uint8_t | mavlink_msg_distance_sensor_get_type (const mavlink_message_t *msg) |
Get field type from distance_sensor message. | |
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. | |
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. |
{ \ "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) }, \ } \ }
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 struct __mavlink_distance_sensor_t mavlink_distance_sensor_t |
static void mavlink_msg_distance_sensor_decode | ( | const mavlink_message_t * | msg, |
mavlink_distance_sensor_t * | distance_sensor | ||
) | [inline, static] |
Decode a distance_sensor message into a struct.
msg | The message to decode |
distance_sensor | C-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 | ||
) | [inline, static] |
Encode a distance_sensor struct.
system_id | ID of this system |
component_id | ID of this component (e.g. 200 for IMU) |
msg | The MAVLink message to compress the data into |
distance_sensor | C-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 | ||
) | [inline, static] |
Encode a distance_sensor struct on a channel.
system_id | ID of this system |
component_id | ID of this component (e.g. 200 for IMU) |
chan | The MAVLink channel this message will be sent over |
msg | The MAVLink message to compress the data into |
distance_sensor | C-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 | ) | [inline, static] |
Get field covariance from distance_sensor message.
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 | ) | [inline, static] |
Get field current_distance from distance_sensor message.
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 | ) | [inline, static] |
Get field id from distance_sensor message.
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 | ) | [inline, static] |
Get field max_distance from distance_sensor message.
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 | ) | [inline, static] |
Get field min_distance from distance_sensor message.
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 | ) | [inline, static] |
Get field orientation from distance_sensor message.
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 | ) | [inline, static] |
Send a distance_sensor message.
chan | MAVLink channel to send the message |
time_boot_ms | Time since system boot |
min_distance | Minimum distance the sensor can measure in centimeters |
max_distance | Maximum distance the sensor can measure in centimeters |
current_distance | Current distance reading |
type | Type from MAV_DISTANCE_SENSOR enum. |
id | Onboard ID of the sensor |
orientation | Direction the sensor faces from MAV_SENSOR_ORIENTATION enum. |
covariance | Measurement covariance in centimeters, 0 for unknown / invalid readings Get field time_boot_ms from distance_sensor message |
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 | ) | [inline, static] |
Get field type from distance_sensor message.
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 | ||
) | [inline, static] |
Pack a distance_sensor message.
system_id | ID of this system |
component_id | ID of this component (e.g. 200 for IMU) |
msg | The MAVLink message to compress the data into |
time_boot_ms | Time since system boot |
min_distance | Minimum distance the sensor can measure in centimeters |
max_distance | Maximum distance the sensor can measure in centimeters |
current_distance | Current distance reading |
type | Type from MAV_DISTANCE_SENSOR enum. |
id | Onboard ID of the sensor |
orientation | Direction the sensor faces from MAV_SENSOR_ORIENTATION enum. |
covariance | Measurement covariance in centimeters, 0 for unknown / invalid readings |
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 | ||
) | [inline, static] |
Pack a distance_sensor message on a channel.
system_id | ID of this system |
component_id | ID of this component (e.g. 200 for IMU) |
chan | The MAVLink channel this message will be sent over |
msg | The MAVLink message to compress the data into |
time_boot_ms | Time since system boot |
min_distance | Minimum distance the sensor can measure in centimeters |
max_distance | Maximum distance the sensor can measure in centimeters |
current_distance | Current distance reading |
type | Type from MAV_DISTANCE_SENSOR enum. |
id | Onboard ID of the sensor |
orientation | Direction the sensor faces from MAV_SENSOR_ORIENTATION enum. |
covariance | Measurement covariance in centimeters, 0 for unknown / invalid readings |
Definition at line 109 of file mavlink_msg_distance_sensor.h.