Classes | Macros | Typedefs | Functions
mavlink_msg_hil_optical_flow.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_hil_optical_flow_t
 

Macros

#define MAVLINK_MESSAGE_INFO_HIL_OPTICAL_FLOW
 
#define MAVLINK_MSG_ID_114_CRC   237
 
#define MAVLINK_MSG_ID_114_LEN   44
 
#define MAVLINK_MSG_ID_HIL_OPTICAL_FLOW   114
 
#define MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_CRC   237
 
#define MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN   44
 

Typedefs

typedef struct __mavlink_hil_optical_flow_t mavlink_hil_optical_flow_t
 

Functions

static void mavlink_msg_hil_optical_flow_decode (const mavlink_message_t *msg, mavlink_hil_optical_flow_t *hil_optical_flow)
 Decode a hil_optical_flow message into a struct. More...
 
static uint16_t mavlink_msg_hil_optical_flow_encode (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_hil_optical_flow_t *hil_optical_flow)
 Encode a hil_optical_flow struct. More...
 
static uint16_t mavlink_msg_hil_optical_flow_encode_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_hil_optical_flow_t *hil_optical_flow)
 Encode a hil_optical_flow struct on a channel. More...
 
static float mavlink_msg_hil_optical_flow_get_distance (const mavlink_message_t *msg)
 Get field distance from hil_optical_flow message. More...
 
static float mavlink_msg_hil_optical_flow_get_integrated_x (const mavlink_message_t *msg)
 Get field integrated_x from hil_optical_flow message. More...
 
static float mavlink_msg_hil_optical_flow_get_integrated_xgyro (const mavlink_message_t *msg)
 Get field integrated_xgyro from hil_optical_flow message. More...
 
static float mavlink_msg_hil_optical_flow_get_integrated_y (const mavlink_message_t *msg)
 Get field integrated_y from hil_optical_flow message. More...
 
static float mavlink_msg_hil_optical_flow_get_integrated_ygyro (const mavlink_message_t *msg)
 Get field integrated_ygyro from hil_optical_flow message. More...
 
static float mavlink_msg_hil_optical_flow_get_integrated_zgyro (const mavlink_message_t *msg)
 Get field integrated_zgyro from hil_optical_flow message. More...
 
static uint32_t mavlink_msg_hil_optical_flow_get_integration_time_us (const mavlink_message_t *msg)
 Get field integration_time_us from hil_optical_flow message. More...
 
static uint8_t mavlink_msg_hil_optical_flow_get_quality (const mavlink_message_t *msg)
 Get field quality from hil_optical_flow message. More...
 
static uint8_t mavlink_msg_hil_optical_flow_get_sensor_id (const mavlink_message_t *msg)
 Get field sensor_id from hil_optical_flow message. More...
 
static int16_t mavlink_msg_hil_optical_flow_get_temperature (const mavlink_message_t *msg)
 Get field temperature from hil_optical_flow message. More...
 
static uint32_t mavlink_msg_hil_optical_flow_get_time_delta_distance_us (const mavlink_message_t *msg)
 Get field time_delta_distance_us from hil_optical_flow message. More...
 
static uint64_t mavlink_msg_hil_optical_flow_get_time_usec (const mavlink_message_t *msg)
 Send a hil_optical_flow message. More...
 
static uint16_t mavlink_msg_hil_optical_flow_pack (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint64_t time_usec, uint8_t sensor_id, uint32_t integration_time_us, float integrated_x, float integrated_y, float integrated_xgyro, float integrated_ygyro, float integrated_zgyro, int16_t temperature, uint8_t quality, uint32_t time_delta_distance_us, float distance)
 Pack a hil_optical_flow message. More...
 
static uint16_t mavlink_msg_hil_optical_flow_pack_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, uint64_t time_usec, uint8_t sensor_id, uint32_t integration_time_us, float integrated_x, float integrated_y, float integrated_xgyro, float integrated_ygyro, float integrated_zgyro, int16_t temperature, uint8_t quality, uint32_t time_delta_distance_us, float distance)
 Pack a hil_optical_flow message on a channel. More...
 

Macro Definition Documentation

#define MAVLINK_MESSAGE_INFO_HIL_OPTICAL_FLOW
Value:
{ \
"HIL_OPTICAL_FLOW", \
12, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_optical_flow_t, time_usec) }, \
{ "integration_time_us", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_hil_optical_flow_t, integration_time_us) }, \
{ "integrated_x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_hil_optical_flow_t, integrated_x) }, \
{ "integrated_y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_hil_optical_flow_t, integrated_y) }, \
{ "integrated_xgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_hil_optical_flow_t, integrated_xgyro) }, \
{ "integrated_ygyro", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_hil_optical_flow_t, integrated_ygyro) }, \
{ "integrated_zgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_hil_optical_flow_t, integrated_zgyro) }, \
{ "time_delta_distance_us", NULL, MAVLINK_TYPE_UINT32_T, 0, 32, offsetof(mavlink_hil_optical_flow_t, time_delta_distance_us) }, \
{ "distance", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_hil_optical_flow_t, distance) }, \
{ "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 40, offsetof(mavlink_hil_optical_flow_t, temperature) }, \
{ "sensor_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_hil_optical_flow_t, sensor_id) }, \
{ "quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 43, offsetof(mavlink_hil_optical_flow_t, quality) }, \
} \
}
float temperature
Definition: ms4525.c:41
static float distance
Definition: drv_sen13680.c:34
#define NULL
Definition: usbd_def.h:50

Definition at line 29 of file mavlink_msg_hil_optical_flow.h.

#define MAVLINK_MSG_ID_114_CRC   237

Definition at line 25 of file mavlink_msg_hil_optical_flow.h.

#define MAVLINK_MSG_ID_114_LEN   44

Definition at line 22 of file mavlink_msg_hil_optical_flow.h.

#define MAVLINK_MSG_ID_HIL_OPTICAL_FLOW   114

Definition at line 3 of file mavlink_msg_hil_optical_flow.h.

#define MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_CRC   237

Definition at line 24 of file mavlink_msg_hil_optical_flow.h.

#define MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN   44

Definition at line 21 of file mavlink_msg_hil_optical_flow.h.

Typedef Documentation

Function Documentation

static void mavlink_msg_hil_optical_flow_decode ( const mavlink_message_t *  msg,
mavlink_hil_optical_flow_t hil_optical_flow 
)
inlinestatic

Decode a hil_optical_flow message into a struct.

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

Definition at line 455 of file mavlink_msg_hil_optical_flow.h.

static uint16_t mavlink_msg_hil_optical_flow_encode ( uint8_t  system_id,
uint8_t  component_id,
mavlink_message_t *  msg,
const mavlink_hil_optical_flow_t hil_optical_flow 
)
inlinestatic

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

Definition at line 187 of file mavlink_msg_hil_optical_flow.h.

static uint16_t mavlink_msg_hil_optical_flow_encode_chan ( uint8_t  system_id,
uint8_t  component_id,
uint8_t  chan,
mavlink_message_t *  msg,
const mavlink_hil_optical_flow_t hil_optical_flow 
)
inlinestatic

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

Definition at line 201 of file mavlink_msg_hil_optical_flow.h.

static float mavlink_msg_hil_optical_flow_get_distance ( const mavlink_message_t *  msg)
inlinestatic

Get field distance from hil_optical_flow message.

Returns
Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance.

Definition at line 444 of file mavlink_msg_hil_optical_flow.h.

static float mavlink_msg_hil_optical_flow_get_integrated_x ( const mavlink_message_t *  msg)
inlinestatic

Get field integrated_x from hil_optical_flow message.

Returns
Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.)

Definition at line 364 of file mavlink_msg_hil_optical_flow.h.

static float mavlink_msg_hil_optical_flow_get_integrated_xgyro ( const mavlink_message_t *  msg)
inlinestatic

Get field integrated_xgyro from hil_optical_flow message.

Returns
RH rotation around X axis (rad)

Definition at line 384 of file mavlink_msg_hil_optical_flow.h.

static float mavlink_msg_hil_optical_flow_get_integrated_y ( const mavlink_message_t *  msg)
inlinestatic

Get field integrated_y from hil_optical_flow message.

Returns
Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.)

Definition at line 374 of file mavlink_msg_hil_optical_flow.h.

static float mavlink_msg_hil_optical_flow_get_integrated_ygyro ( const mavlink_message_t *  msg)
inlinestatic

Get field integrated_ygyro from hil_optical_flow message.

Returns
RH rotation around Y axis (rad)

Definition at line 394 of file mavlink_msg_hil_optical_flow.h.

static float mavlink_msg_hil_optical_flow_get_integrated_zgyro ( const mavlink_message_t *  msg)
inlinestatic

Get field integrated_zgyro from hil_optical_flow message.

Returns
RH rotation around Z axis (rad)

Definition at line 404 of file mavlink_msg_hil_optical_flow.h.

static uint32_t mavlink_msg_hil_optical_flow_get_integration_time_us ( const mavlink_message_t *  msg)
inlinestatic

Get field integration_time_us from hil_optical_flow message.

Returns
Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the.

Definition at line 354 of file mavlink_msg_hil_optical_flow.h.

static uint8_t mavlink_msg_hil_optical_flow_get_quality ( const mavlink_message_t *  msg)
inlinestatic

Get field quality from hil_optical_flow message.

Returns
Optical flow quality / confidence. 0: no valid flow, 255: maximum quality

Definition at line 424 of file mavlink_msg_hil_optical_flow.h.

static uint8_t mavlink_msg_hil_optical_flow_get_sensor_id ( const mavlink_message_t *  msg)
inlinestatic

Get field sensor_id from hil_optical_flow message.

Returns
Sensor ID

Definition at line 344 of file mavlink_msg_hil_optical_flow.h.

static int16_t mavlink_msg_hil_optical_flow_get_temperature ( const mavlink_message_t *  msg)
inlinestatic

Get field temperature from hil_optical_flow message.

Returns
Temperature * 100 in centi-degrees Celsius

Definition at line 414 of file mavlink_msg_hil_optical_flow.h.

static uint32_t mavlink_msg_hil_optical_flow_get_time_delta_distance_us ( const mavlink_message_t *  msg)
inlinestatic

Get field time_delta_distance_us from hil_optical_flow message.

Returns
Time in microseconds since the distance was sampled.

Definition at line 434 of file mavlink_msg_hil_optical_flow.h.

static uint64_t mavlink_msg_hil_optical_flow_get_time_usec ( const mavlink_message_t *  msg)
inlinestatic

Send a hil_optical_flow message.

Parameters
chanMAVLink channel to send the message
time_usecTimestamp (microseconds, synced to UNIX time or since system boot)
sensor_idSensor ID
integration_time_usIntegration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the.
integrated_xFlow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.)
integrated_yFlow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.)
integrated_xgyroRH rotation around X axis (rad)
integrated_ygyroRH rotation around Y axis (rad)
integrated_zgyroRH rotation around Z axis (rad)
temperatureTemperature * 100 in centi-degrees Celsius
qualityOptical flow quality / confidence. 0: no valid flow, 255: maximum quality
time_delta_distance_usTime in microseconds since the distance was sampled.
distanceDistance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance. Get field time_usec from hil_optical_flow message
Returns
Timestamp (microseconds, synced to UNIX time or since system boot)

Definition at line 334 of file mavlink_msg_hil_optical_flow.h.

static uint16_t mavlink_msg_hil_optical_flow_pack ( uint8_t  system_id,
uint8_t  component_id,
mavlink_message_t *  msg,
uint64_t  time_usec,
uint8_t  sensor_id,
uint32_t  integration_time_us,
float  integrated_x,
float  integrated_y,
float  integrated_xgyro,
float  integrated_ygyro,
float  integrated_zgyro,
int16_t  temperature,
uint8_t  quality,
uint32_t  time_delta_distance_us,
float  distance 
)
inlinestatic

Pack a hil_optical_flow 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_usecTimestamp (microseconds, synced to UNIX time or since system boot)
sensor_idSensor ID
integration_time_usIntegration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the.
integrated_xFlow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.)
integrated_yFlow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.)
integrated_xgyroRH rotation around X axis (rad)
integrated_ygyroRH rotation around Y axis (rad)
integrated_zgyroRH rotation around Z axis (rad)
temperatureTemperature * 100 in centi-degrees Celsius
qualityOptical flow quality / confidence. 0: no valid flow, 255: maximum quality
time_delta_distance_usTime in microseconds since the distance was sampled.
distanceDistance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance.
Returns
length of the message in bytes (excluding serial stream start sign)

Definition at line 68 of file mavlink_msg_hil_optical_flow.h.

static uint16_t mavlink_msg_hil_optical_flow_pack_chan ( uint8_t  system_id,
uint8_t  component_id,
uint8_t  chan,
mavlink_message_t *  msg,
uint64_t  time_usec,
uint8_t  sensor_id,
uint32_t  integration_time_us,
float  integrated_x,
float  integrated_y,
float  integrated_xgyro,
float  integrated_ygyro,
float  integrated_zgyro,
int16_t  temperature,
uint8_t  quality,
uint32_t  time_delta_distance_us,
float  distance 
)
inlinestatic

Pack a hil_optical_flow 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_usecTimestamp (microseconds, synced to UNIX time or since system boot)
sensor_idSensor ID
integration_time_usIntegration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the.
integrated_xFlow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.)
integrated_yFlow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.)
integrated_xgyroRH rotation around X axis (rad)
integrated_ygyroRH rotation around Y axis (rad)
integrated_zgyroRH rotation around Z axis (rad)
temperatureTemperature * 100 in centi-degrees Celsius
qualityOptical flow quality / confidence. 0: no valid flow, 255: maximum quality
time_delta_distance_usTime in microseconds since the distance was sampled.
distanceDistance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance.
Returns
length of the message in bytes (excluding serial stream start sign)

Definition at line 133 of file mavlink_msg_hil_optical_flow.h.



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