mirror of https://github.com/ArduPilot/ardupilot
GCS_MAVLink: regenerate after merge
This commit is contained in:
parent
0dba1b370a
commit
682cf02770
File diff suppressed because one or more lines are too long
|
@ -5,7 +5,7 @@
|
|||
#ifndef MAVLINK_VERSION_H
|
||||
#define MAVLINK_VERSION_H
|
||||
|
||||
#define MAVLINK_BUILD_DATE "Sat Oct 18 12:05:51 2014"
|
||||
#define MAVLINK_BUILD_DATE "Fri Nov 14 15:24:39 2014"
|
||||
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
|
||||
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255
|
||||
|
||||
|
|
File diff suppressed because one or more lines are too long
|
@ -4,35 +4,43 @@
|
|||
|
||||
typedef struct __mavlink_hil_optical_flow_t
|
||||
{
|
||||
uint64_t time_usec; ///< Timestamp (UNIX)
|
||||
float flow_comp_m_x; ///< Flow in meters in x-sensor direction, angular-speed compensated
|
||||
float flow_comp_m_y; ///< Flow in meters in y-sensor direction, angular-speed compensated
|
||||
float ground_distance; ///< Ground distance in meters. Positive value: distance known. Negative value: Unknown distance
|
||||
int16_t flow_x; ///< Flow in pixels in x-sensor direction
|
||||
int16_t flow_y; ///< Flow in pixels in y-sensor direction
|
||||
uint64_t time_usec; ///< Timestamp (microseconds, synced to UNIX time or since system boot)
|
||||
uint32_t integration_time_us; ///< Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the.
|
||||
float integrated_x; ///< 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.)
|
||||
float integrated_y; ///< 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.)
|
||||
float integrated_xgyro; ///< RH rotation around X axis (rad)
|
||||
float integrated_ygyro; ///< RH rotation around Y axis (rad)
|
||||
float integrated_zgyro; ///< RH rotation around Z axis (rad)
|
||||
uint32_t time_delta_distance_us; ///< Time in microseconds since the distance was sampled.
|
||||
float distance; ///< Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance.
|
||||
int16_t temperature; ///< Temperature * 100 in centi-degrees Celsius
|
||||
uint8_t sensor_id; ///< Sensor ID
|
||||
uint8_t quality; ///< Optical flow quality / confidence. 0: bad, 255: maximum quality
|
||||
uint8_t quality; ///< Optical flow quality / confidence. 0: no valid flow, 255: maximum quality
|
||||
} mavlink_hil_optical_flow_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN 26
|
||||
#define MAVLINK_MSG_ID_114_LEN 26
|
||||
#define MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN 44
|
||||
#define MAVLINK_MSG_ID_114_LEN 44
|
||||
|
||||
#define MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_CRC 119
|
||||
#define MAVLINK_MSG_ID_114_CRC 119
|
||||
#define MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_CRC 237
|
||||
#define MAVLINK_MSG_ID_114_CRC 237
|
||||
|
||||
|
||||
|
||||
#define MAVLINK_MESSAGE_INFO_HIL_OPTICAL_FLOW { \
|
||||
"HIL_OPTICAL_FLOW", \
|
||||
8, \
|
||||
12, \
|
||||
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_optical_flow_t, time_usec) }, \
|
||||
{ "flow_comp_m_x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_hil_optical_flow_t, flow_comp_m_x) }, \
|
||||
{ "flow_comp_m_y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_hil_optical_flow_t, flow_comp_m_y) }, \
|
||||
{ "ground_distance", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_hil_optical_flow_t, ground_distance) }, \
|
||||
{ "flow_x", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_hil_optical_flow_t, flow_x) }, \
|
||||
{ "flow_y", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_hil_optical_flow_t, flow_y) }, \
|
||||
{ "sensor_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_hil_optical_flow_t, sensor_id) }, \
|
||||
{ "quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 25, offsetof(mavlink_hil_optical_flow_t, quality) }, \
|
||||
{ "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) }, \
|
||||
} \
|
||||
}
|
||||
|
||||
|
@ -43,39 +51,51 @@ typedef struct __mavlink_hil_optical_flow_t
|
|||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
*
|
||||
* @param time_usec Timestamp (UNIX)
|
||||
* @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot)
|
||||
* @param sensor_id Sensor ID
|
||||
* @param flow_x Flow in pixels in x-sensor direction
|
||||
* @param flow_y Flow in pixels in y-sensor direction
|
||||
* @param flow_comp_m_x Flow in meters in x-sensor direction, angular-speed compensated
|
||||
* @param flow_comp_m_y Flow in meters in y-sensor direction, angular-speed compensated
|
||||
* @param quality Optical flow quality / confidence. 0: bad, 255: maximum quality
|
||||
* @param ground_distance Ground distance in meters. Positive value: distance known. Negative value: Unknown distance
|
||||
* @param integration_time_us Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the.
|
||||
* @param integrated_x 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.)
|
||||
* @param integrated_y 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.)
|
||||
* @param integrated_xgyro RH rotation around X axis (rad)
|
||||
* @param integrated_ygyro RH rotation around Y axis (rad)
|
||||
* @param integrated_zgyro RH rotation around Z axis (rad)
|
||||
* @param temperature Temperature * 100 in centi-degrees Celsius
|
||||
* @param quality Optical flow quality / confidence. 0: no valid flow, 255: maximum quality
|
||||
* @param time_delta_distance_us Time in microseconds since the distance was sampled.
|
||||
* @param distance Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance.
|
||||
* @return length of the message in bytes (excluding serial stream start sign)
|
||||
*/
|
||||
static inline 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, int16_t flow_x, int16_t flow_y, float flow_comp_m_x, float flow_comp_m_y, uint8_t quality, float ground_distance)
|
||||
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)
|
||||
{
|
||||
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||
char buf[MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN];
|
||||
_mav_put_uint64_t(buf, 0, time_usec);
|
||||
_mav_put_float(buf, 8, flow_comp_m_x);
|
||||
_mav_put_float(buf, 12, flow_comp_m_y);
|
||||
_mav_put_float(buf, 16, ground_distance);
|
||||
_mav_put_int16_t(buf, 20, flow_x);
|
||||
_mav_put_int16_t(buf, 22, flow_y);
|
||||
_mav_put_uint8_t(buf, 24, sensor_id);
|
||||
_mav_put_uint8_t(buf, 25, quality);
|
||||
_mav_put_uint32_t(buf, 8, integration_time_us);
|
||||
_mav_put_float(buf, 12, integrated_x);
|
||||
_mav_put_float(buf, 16, integrated_y);
|
||||
_mav_put_float(buf, 20, integrated_xgyro);
|
||||
_mav_put_float(buf, 24, integrated_ygyro);
|
||||
_mav_put_float(buf, 28, integrated_zgyro);
|
||||
_mav_put_uint32_t(buf, 32, time_delta_distance_us);
|
||||
_mav_put_float(buf, 36, distance);
|
||||
_mav_put_int16_t(buf, 40, temperature);
|
||||
_mav_put_uint8_t(buf, 42, sensor_id);
|
||||
_mav_put_uint8_t(buf, 43, quality);
|
||||
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN);
|
||||
#else
|
||||
mavlink_hil_optical_flow_t packet;
|
||||
packet.time_usec = time_usec;
|
||||
packet.flow_comp_m_x = flow_comp_m_x;
|
||||
packet.flow_comp_m_y = flow_comp_m_y;
|
||||
packet.ground_distance = ground_distance;
|
||||
packet.flow_x = flow_x;
|
||||
packet.flow_y = flow_y;
|
||||
packet.integration_time_us = integration_time_us;
|
||||
packet.integrated_x = integrated_x;
|
||||
packet.integrated_y = integrated_y;
|
||||
packet.integrated_xgyro = integrated_xgyro;
|
||||
packet.integrated_ygyro = integrated_ygyro;
|
||||
packet.integrated_zgyro = integrated_zgyro;
|
||||
packet.time_delta_distance_us = time_delta_distance_us;
|
||||
packet.distance = distance;
|
||||
packet.temperature = temperature;
|
||||
packet.sensor_id = sensor_id;
|
||||
packet.quality = quality;
|
||||
|
||||
|
@ -96,40 +116,52 @@ static inline uint16_t mavlink_msg_hil_optical_flow_pack(uint8_t system_id, uint
|
|||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param chan The MAVLink channel this message will be sent over
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param time_usec Timestamp (UNIX)
|
||||
* @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot)
|
||||
* @param sensor_id Sensor ID
|
||||
* @param flow_x Flow in pixels in x-sensor direction
|
||||
* @param flow_y Flow in pixels in y-sensor direction
|
||||
* @param flow_comp_m_x Flow in meters in x-sensor direction, angular-speed compensated
|
||||
* @param flow_comp_m_y Flow in meters in y-sensor direction, angular-speed compensated
|
||||
* @param quality Optical flow quality / confidence. 0: bad, 255: maximum quality
|
||||
* @param ground_distance Ground distance in meters. Positive value: distance known. Negative value: Unknown distance
|
||||
* @param integration_time_us Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the.
|
||||
* @param integrated_x 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.)
|
||||
* @param integrated_y 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.)
|
||||
* @param integrated_xgyro RH rotation around X axis (rad)
|
||||
* @param integrated_ygyro RH rotation around Y axis (rad)
|
||||
* @param integrated_zgyro RH rotation around Z axis (rad)
|
||||
* @param temperature Temperature * 100 in centi-degrees Celsius
|
||||
* @param quality Optical flow quality / confidence. 0: no valid flow, 255: maximum quality
|
||||
* @param time_delta_distance_us Time in microseconds since the distance was sampled.
|
||||
* @param distance Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance.
|
||||
* @return length of the message in bytes (excluding serial stream start sign)
|
||||
*/
|
||||
static inline 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,int16_t flow_x,int16_t flow_y,float flow_comp_m_x,float flow_comp_m_y,uint8_t quality,float ground_distance)
|
||||
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)
|
||||
{
|
||||
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||
char buf[MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN];
|
||||
_mav_put_uint64_t(buf, 0, time_usec);
|
||||
_mav_put_float(buf, 8, flow_comp_m_x);
|
||||
_mav_put_float(buf, 12, flow_comp_m_y);
|
||||
_mav_put_float(buf, 16, ground_distance);
|
||||
_mav_put_int16_t(buf, 20, flow_x);
|
||||
_mav_put_int16_t(buf, 22, flow_y);
|
||||
_mav_put_uint8_t(buf, 24, sensor_id);
|
||||
_mav_put_uint8_t(buf, 25, quality);
|
||||
_mav_put_uint32_t(buf, 8, integration_time_us);
|
||||
_mav_put_float(buf, 12, integrated_x);
|
||||
_mav_put_float(buf, 16, integrated_y);
|
||||
_mav_put_float(buf, 20, integrated_xgyro);
|
||||
_mav_put_float(buf, 24, integrated_ygyro);
|
||||
_mav_put_float(buf, 28, integrated_zgyro);
|
||||
_mav_put_uint32_t(buf, 32, time_delta_distance_us);
|
||||
_mav_put_float(buf, 36, distance);
|
||||
_mav_put_int16_t(buf, 40, temperature);
|
||||
_mav_put_uint8_t(buf, 42, sensor_id);
|
||||
_mav_put_uint8_t(buf, 43, quality);
|
||||
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN);
|
||||
#else
|
||||
mavlink_hil_optical_flow_t packet;
|
||||
packet.time_usec = time_usec;
|
||||
packet.flow_comp_m_x = flow_comp_m_x;
|
||||
packet.flow_comp_m_y = flow_comp_m_y;
|
||||
packet.ground_distance = ground_distance;
|
||||
packet.flow_x = flow_x;
|
||||
packet.flow_y = flow_y;
|
||||
packet.integration_time_us = integration_time_us;
|
||||
packet.integrated_x = integrated_x;
|
||||
packet.integrated_y = integrated_y;
|
||||
packet.integrated_xgyro = integrated_xgyro;
|
||||
packet.integrated_ygyro = integrated_ygyro;
|
||||
packet.integrated_zgyro = integrated_zgyro;
|
||||
packet.time_delta_distance_us = time_delta_distance_us;
|
||||
packet.distance = distance;
|
||||
packet.temperature = temperature;
|
||||
packet.sensor_id = sensor_id;
|
||||
packet.quality = quality;
|
||||
|
||||
|
@ -154,7 +186,7 @@ static inline uint16_t mavlink_msg_hil_optical_flow_pack_chan(uint8_t system_id,
|
|||
*/
|
||||
static inline 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)
|
||||
{
|
||||
return mavlink_msg_hil_optical_flow_pack(system_id, component_id, msg, hil_optical_flow->time_usec, hil_optical_flow->sensor_id, hil_optical_flow->flow_x, hil_optical_flow->flow_y, hil_optical_flow->flow_comp_m_x, hil_optical_flow->flow_comp_m_y, hil_optical_flow->quality, hil_optical_flow->ground_distance);
|
||||
return mavlink_msg_hil_optical_flow_pack(system_id, component_id, msg, hil_optical_flow->time_usec, hil_optical_flow->sensor_id, hil_optical_flow->integration_time_us, hil_optical_flow->integrated_x, hil_optical_flow->integrated_y, hil_optical_flow->integrated_xgyro, hil_optical_flow->integrated_ygyro, hil_optical_flow->integrated_zgyro, hil_optical_flow->temperature, hil_optical_flow->quality, hil_optical_flow->time_delta_distance_us, hil_optical_flow->distance);
|
||||
}
|
||||
|
||||
/**
|
||||
|
@ -168,36 +200,44 @@ static inline uint16_t mavlink_msg_hil_optical_flow_encode(uint8_t system_id, ui
|
|||
*/
|
||||
static inline 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)
|
||||
{
|
||||
return mavlink_msg_hil_optical_flow_pack_chan(system_id, component_id, chan, msg, hil_optical_flow->time_usec, hil_optical_flow->sensor_id, hil_optical_flow->flow_x, hil_optical_flow->flow_y, hil_optical_flow->flow_comp_m_x, hil_optical_flow->flow_comp_m_y, hil_optical_flow->quality, hil_optical_flow->ground_distance);
|
||||
return mavlink_msg_hil_optical_flow_pack_chan(system_id, component_id, chan, msg, hil_optical_flow->time_usec, hil_optical_flow->sensor_id, hil_optical_flow->integration_time_us, hil_optical_flow->integrated_x, hil_optical_flow->integrated_y, hil_optical_flow->integrated_xgyro, hil_optical_flow->integrated_ygyro, hil_optical_flow->integrated_zgyro, hil_optical_flow->temperature, hil_optical_flow->quality, hil_optical_flow->time_delta_distance_us, hil_optical_flow->distance);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Send a hil_optical_flow message
|
||||
* @param chan MAVLink channel to send the message
|
||||
*
|
||||
* @param time_usec Timestamp (UNIX)
|
||||
* @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot)
|
||||
* @param sensor_id Sensor ID
|
||||
* @param flow_x Flow in pixels in x-sensor direction
|
||||
* @param flow_y Flow in pixels in y-sensor direction
|
||||
* @param flow_comp_m_x Flow in meters in x-sensor direction, angular-speed compensated
|
||||
* @param flow_comp_m_y Flow in meters in y-sensor direction, angular-speed compensated
|
||||
* @param quality Optical flow quality / confidence. 0: bad, 255: maximum quality
|
||||
* @param ground_distance Ground distance in meters. Positive value: distance known. Negative value: Unknown distance
|
||||
* @param integration_time_us Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the.
|
||||
* @param integrated_x 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.)
|
||||
* @param integrated_y 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.)
|
||||
* @param integrated_xgyro RH rotation around X axis (rad)
|
||||
* @param integrated_ygyro RH rotation around Y axis (rad)
|
||||
* @param integrated_zgyro RH rotation around Z axis (rad)
|
||||
* @param temperature Temperature * 100 in centi-degrees Celsius
|
||||
* @param quality Optical flow quality / confidence. 0: no valid flow, 255: maximum quality
|
||||
* @param time_delta_distance_us Time in microseconds since the distance was sampled.
|
||||
* @param distance Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance.
|
||||
*/
|
||||
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
|
||||
|
||||
static inline void mavlink_msg_hil_optical_flow_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t sensor_id, int16_t flow_x, int16_t flow_y, float flow_comp_m_x, float flow_comp_m_y, uint8_t quality, float ground_distance)
|
||||
static inline void mavlink_msg_hil_optical_flow_send(mavlink_channel_t chan, 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)
|
||||
{
|
||||
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||
char buf[MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN];
|
||||
_mav_put_uint64_t(buf, 0, time_usec);
|
||||
_mav_put_float(buf, 8, flow_comp_m_x);
|
||||
_mav_put_float(buf, 12, flow_comp_m_y);
|
||||
_mav_put_float(buf, 16, ground_distance);
|
||||
_mav_put_int16_t(buf, 20, flow_x);
|
||||
_mav_put_int16_t(buf, 22, flow_y);
|
||||
_mav_put_uint8_t(buf, 24, sensor_id);
|
||||
_mav_put_uint8_t(buf, 25, quality);
|
||||
_mav_put_uint32_t(buf, 8, integration_time_us);
|
||||
_mav_put_float(buf, 12, integrated_x);
|
||||
_mav_put_float(buf, 16, integrated_y);
|
||||
_mav_put_float(buf, 20, integrated_xgyro);
|
||||
_mav_put_float(buf, 24, integrated_ygyro);
|
||||
_mav_put_float(buf, 28, integrated_zgyro);
|
||||
_mav_put_uint32_t(buf, 32, time_delta_distance_us);
|
||||
_mav_put_float(buf, 36, distance);
|
||||
_mav_put_int16_t(buf, 40, temperature);
|
||||
_mav_put_uint8_t(buf, 42, sensor_id);
|
||||
_mav_put_uint8_t(buf, 43, quality);
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW, buf, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_CRC);
|
||||
|
@ -207,11 +247,15 @@ static inline void mavlink_msg_hil_optical_flow_send(mavlink_channel_t chan, uin
|
|||
#else
|
||||
mavlink_hil_optical_flow_t packet;
|
||||
packet.time_usec = time_usec;
|
||||
packet.flow_comp_m_x = flow_comp_m_x;
|
||||
packet.flow_comp_m_y = flow_comp_m_y;
|
||||
packet.ground_distance = ground_distance;
|
||||
packet.flow_x = flow_x;
|
||||
packet.flow_y = flow_y;
|
||||
packet.integration_time_us = integration_time_us;
|
||||
packet.integrated_x = integrated_x;
|
||||
packet.integrated_y = integrated_y;
|
||||
packet.integrated_xgyro = integrated_xgyro;
|
||||
packet.integrated_ygyro = integrated_ygyro;
|
||||
packet.integrated_zgyro = integrated_zgyro;
|
||||
packet.time_delta_distance_us = time_delta_distance_us;
|
||||
packet.distance = distance;
|
||||
packet.temperature = temperature;
|
||||
packet.sensor_id = sensor_id;
|
||||
packet.quality = quality;
|
||||
|
||||
|
@ -231,18 +275,22 @@ static inline void mavlink_msg_hil_optical_flow_send(mavlink_channel_t chan, uin
|
|||
is usually the receive buffer for the channel, and allows a reply to an
|
||||
incoming message with minimum stack space usage.
|
||||
*/
|
||||
static inline void mavlink_msg_hil_optical_flow_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint8_t sensor_id, int16_t flow_x, int16_t flow_y, float flow_comp_m_x, float flow_comp_m_y, uint8_t quality, float ground_distance)
|
||||
static inline void mavlink_msg_hil_optical_flow_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, 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)
|
||||
{
|
||||
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||
char *buf = (char *)msgbuf;
|
||||
_mav_put_uint64_t(buf, 0, time_usec);
|
||||
_mav_put_float(buf, 8, flow_comp_m_x);
|
||||
_mav_put_float(buf, 12, flow_comp_m_y);
|
||||
_mav_put_float(buf, 16, ground_distance);
|
||||
_mav_put_int16_t(buf, 20, flow_x);
|
||||
_mav_put_int16_t(buf, 22, flow_y);
|
||||
_mav_put_uint8_t(buf, 24, sensor_id);
|
||||
_mav_put_uint8_t(buf, 25, quality);
|
||||
_mav_put_uint32_t(buf, 8, integration_time_us);
|
||||
_mav_put_float(buf, 12, integrated_x);
|
||||
_mav_put_float(buf, 16, integrated_y);
|
||||
_mav_put_float(buf, 20, integrated_xgyro);
|
||||
_mav_put_float(buf, 24, integrated_ygyro);
|
||||
_mav_put_float(buf, 28, integrated_zgyro);
|
||||
_mav_put_uint32_t(buf, 32, time_delta_distance_us);
|
||||
_mav_put_float(buf, 36, distance);
|
||||
_mav_put_int16_t(buf, 40, temperature);
|
||||
_mav_put_uint8_t(buf, 42, sensor_id);
|
||||
_mav_put_uint8_t(buf, 43, quality);
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW, buf, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_CRC);
|
||||
|
@ -252,11 +300,15 @@ static inline void mavlink_msg_hil_optical_flow_send_buf(mavlink_message_t *msgb
|
|||
#else
|
||||
mavlink_hil_optical_flow_t *packet = (mavlink_hil_optical_flow_t *)msgbuf;
|
||||
packet->time_usec = time_usec;
|
||||
packet->flow_comp_m_x = flow_comp_m_x;
|
||||
packet->flow_comp_m_y = flow_comp_m_y;
|
||||
packet->ground_distance = ground_distance;
|
||||
packet->flow_x = flow_x;
|
||||
packet->flow_y = flow_y;
|
||||
packet->integration_time_us = integration_time_us;
|
||||
packet->integrated_x = integrated_x;
|
||||
packet->integrated_y = integrated_y;
|
||||
packet->integrated_xgyro = integrated_xgyro;
|
||||
packet->integrated_ygyro = integrated_ygyro;
|
||||
packet->integrated_zgyro = integrated_zgyro;
|
||||
packet->time_delta_distance_us = time_delta_distance_us;
|
||||
packet->distance = distance;
|
||||
packet->temperature = temperature;
|
||||
packet->sensor_id = sensor_id;
|
||||
packet->quality = quality;
|
||||
|
||||
|
@ -277,7 +329,7 @@ static inline void mavlink_msg_hil_optical_flow_send_buf(mavlink_message_t *msgb
|
|||
/**
|
||||
* @brief Get field time_usec from hil_optical_flow message
|
||||
*
|
||||
* @return Timestamp (UNIX)
|
||||
* @return Timestamp (microseconds, synced to UNIX time or since system boot)
|
||||
*/
|
||||
static inline uint64_t mavlink_msg_hil_optical_flow_get_time_usec(const mavlink_message_t* msg)
|
||||
{
|
||||
|
@ -291,67 +343,107 @@ static inline uint64_t mavlink_msg_hil_optical_flow_get_time_usec(const mavlink_
|
|||
*/
|
||||
static inline uint8_t mavlink_msg_hil_optical_flow_get_sensor_id(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_uint8_t(msg, 24);
|
||||
return _MAV_RETURN_uint8_t(msg, 42);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field flow_x from hil_optical_flow message
|
||||
* @brief Get field integration_time_us from hil_optical_flow message
|
||||
*
|
||||
* @return Flow in pixels in x-sensor direction
|
||||
* @return Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the.
|
||||
*/
|
||||
static inline int16_t mavlink_msg_hil_optical_flow_get_flow_x(const mavlink_message_t* msg)
|
||||
static inline uint32_t mavlink_msg_hil_optical_flow_get_integration_time_us(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_int16_t(msg, 20);
|
||||
return _MAV_RETURN_uint32_t(msg, 8);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field flow_y from hil_optical_flow message
|
||||
* @brief Get field integrated_x from hil_optical_flow message
|
||||
*
|
||||
* @return Flow in pixels in y-sensor direction
|
||||
* @return 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.)
|
||||
*/
|
||||
static inline int16_t mavlink_msg_hil_optical_flow_get_flow_y(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_int16_t(msg, 22);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field flow_comp_m_x from hil_optical_flow message
|
||||
*
|
||||
* @return Flow in meters in x-sensor direction, angular-speed compensated
|
||||
*/
|
||||
static inline float mavlink_msg_hil_optical_flow_get_flow_comp_m_x(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_float(msg, 8);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field flow_comp_m_y from hil_optical_flow message
|
||||
*
|
||||
* @return Flow in meters in y-sensor direction, angular-speed compensated
|
||||
*/
|
||||
static inline float mavlink_msg_hil_optical_flow_get_flow_comp_m_y(const mavlink_message_t* msg)
|
||||
static inline float mavlink_msg_hil_optical_flow_get_integrated_x(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_float(msg, 12);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field quality from hil_optical_flow message
|
||||
* @brief Get field integrated_y from hil_optical_flow message
|
||||
*
|
||||
* @return Optical flow quality / confidence. 0: bad, 255: maximum quality
|
||||
* @return 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.)
|
||||
*/
|
||||
static inline uint8_t mavlink_msg_hil_optical_flow_get_quality(const mavlink_message_t* msg)
|
||||
static inline float mavlink_msg_hil_optical_flow_get_integrated_y(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_uint8_t(msg, 25);
|
||||
return _MAV_RETURN_float(msg, 16);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field ground_distance from hil_optical_flow message
|
||||
* @brief Get field integrated_xgyro from hil_optical_flow message
|
||||
*
|
||||
* @return Ground distance in meters. Positive value: distance known. Negative value: Unknown distance
|
||||
* @return RH rotation around X axis (rad)
|
||||
*/
|
||||
static inline float mavlink_msg_hil_optical_flow_get_ground_distance(const mavlink_message_t* msg)
|
||||
static inline float mavlink_msg_hil_optical_flow_get_integrated_xgyro(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_float(msg, 16);
|
||||
return _MAV_RETURN_float(msg, 20);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field integrated_ygyro from hil_optical_flow message
|
||||
*
|
||||
* @return RH rotation around Y axis (rad)
|
||||
*/
|
||||
static inline float mavlink_msg_hil_optical_flow_get_integrated_ygyro(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_float(msg, 24);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field integrated_zgyro from hil_optical_flow message
|
||||
*
|
||||
* @return RH rotation around Z axis (rad)
|
||||
*/
|
||||
static inline float mavlink_msg_hil_optical_flow_get_integrated_zgyro(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_float(msg, 28);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field temperature from hil_optical_flow message
|
||||
*
|
||||
* @return Temperature * 100 in centi-degrees Celsius
|
||||
*/
|
||||
static inline int16_t mavlink_msg_hil_optical_flow_get_temperature(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_int16_t(msg, 40);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field quality from hil_optical_flow message
|
||||
*
|
||||
* @return Optical flow quality / confidence. 0: no valid flow, 255: maximum quality
|
||||
*/
|
||||
static inline uint8_t mavlink_msg_hil_optical_flow_get_quality(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_uint8_t(msg, 43);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field time_delta_distance_us from hil_optical_flow message
|
||||
*
|
||||
* @return Time in microseconds since the distance was sampled.
|
||||
*/
|
||||
static inline uint32_t mavlink_msg_hil_optical_flow_get_time_delta_distance_us(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_uint32_t(msg, 32);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field distance from hil_optical_flow message
|
||||
*
|
||||
* @return Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance.
|
||||
*/
|
||||
static inline float mavlink_msg_hil_optical_flow_get_distance(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_float(msg, 36);
|
||||
}
|
||||
|
||||
/**
|
||||
|
@ -364,11 +456,15 @@ static inline void mavlink_msg_hil_optical_flow_decode(const mavlink_message_t*
|
|||
{
|
||||
#if MAVLINK_NEED_BYTE_SWAP
|
||||
hil_optical_flow->time_usec = mavlink_msg_hil_optical_flow_get_time_usec(msg);
|
||||
hil_optical_flow->flow_comp_m_x = mavlink_msg_hil_optical_flow_get_flow_comp_m_x(msg);
|
||||
hil_optical_flow->flow_comp_m_y = mavlink_msg_hil_optical_flow_get_flow_comp_m_y(msg);
|
||||
hil_optical_flow->ground_distance = mavlink_msg_hil_optical_flow_get_ground_distance(msg);
|
||||
hil_optical_flow->flow_x = mavlink_msg_hil_optical_flow_get_flow_x(msg);
|
||||
hil_optical_flow->flow_y = mavlink_msg_hil_optical_flow_get_flow_y(msg);
|
||||
hil_optical_flow->integration_time_us = mavlink_msg_hil_optical_flow_get_integration_time_us(msg);
|
||||
hil_optical_flow->integrated_x = mavlink_msg_hil_optical_flow_get_integrated_x(msg);
|
||||
hil_optical_flow->integrated_y = mavlink_msg_hil_optical_flow_get_integrated_y(msg);
|
||||
hil_optical_flow->integrated_xgyro = mavlink_msg_hil_optical_flow_get_integrated_xgyro(msg);
|
||||
hil_optical_flow->integrated_ygyro = mavlink_msg_hil_optical_flow_get_integrated_ygyro(msg);
|
||||
hil_optical_flow->integrated_zgyro = mavlink_msg_hil_optical_flow_get_integrated_zgyro(msg);
|
||||
hil_optical_flow->time_delta_distance_us = mavlink_msg_hil_optical_flow_get_time_delta_distance_us(msg);
|
||||
hil_optical_flow->distance = mavlink_msg_hil_optical_flow_get_distance(msg);
|
||||
hil_optical_flow->temperature = mavlink_msg_hil_optical_flow_get_temperature(msg);
|
||||
hil_optical_flow->sensor_id = mavlink_msg_hil_optical_flow_get_sensor_id(msg);
|
||||
hil_optical_flow->quality = mavlink_msg_hil_optical_flow_get_quality(msg);
|
||||
#else
|
||||
|
|
|
@ -0,0 +1,473 @@
|
|||
// MESSAGE OPTICAL_FLOW_RAD PACKING
|
||||
|
||||
#define MAVLINK_MSG_ID_OPTICAL_FLOW_RAD 106
|
||||
|
||||
typedef struct __mavlink_optical_flow_rad_t
|
||||
{
|
||||
uint64_t time_usec; ///< Timestamp (microseconds, synced to UNIX time or since system boot)
|
||||
uint32_t integration_time_us; ///< Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the.
|
||||
float integrated_x; ///< 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.)
|
||||
float integrated_y; ///< 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.)
|
||||
float integrated_xgyro; ///< RH rotation around X axis (rad)
|
||||
float integrated_ygyro; ///< RH rotation around Y axis (rad)
|
||||
float integrated_zgyro; ///< RH rotation around Z axis (rad)
|
||||
uint32_t time_delta_distance_us; ///< Time in microseconds since the distance was sampled.
|
||||
float distance; ///< Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance.
|
||||
int16_t temperature; ///< Temperature * 100 in centi-degrees Celsius
|
||||
uint8_t sensor_id; ///< Sensor ID
|
||||
uint8_t quality; ///< Optical flow quality / confidence. 0: no valid flow, 255: maximum quality
|
||||
} mavlink_optical_flow_rad_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN 44
|
||||
#define MAVLINK_MSG_ID_106_LEN 44
|
||||
|
||||
#define MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_CRC 138
|
||||
#define MAVLINK_MSG_ID_106_CRC 138
|
||||
|
||||
|
||||
|
||||
#define MAVLINK_MESSAGE_INFO_OPTICAL_FLOW_RAD { \
|
||||
"OPTICAL_FLOW_RAD", \
|
||||
12, \
|
||||
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_optical_flow_rad_t, time_usec) }, \
|
||||
{ "integration_time_us", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_optical_flow_rad_t, integration_time_us) }, \
|
||||
{ "integrated_x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_optical_flow_rad_t, integrated_x) }, \
|
||||
{ "integrated_y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_optical_flow_rad_t, integrated_y) }, \
|
||||
{ "integrated_xgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_optical_flow_rad_t, integrated_xgyro) }, \
|
||||
{ "integrated_ygyro", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_optical_flow_rad_t, integrated_ygyro) }, \
|
||||
{ "integrated_zgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_optical_flow_rad_t, integrated_zgyro) }, \
|
||||
{ "time_delta_distance_us", NULL, MAVLINK_TYPE_UINT32_T, 0, 32, offsetof(mavlink_optical_flow_rad_t, time_delta_distance_us) }, \
|
||||
{ "distance", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_optical_flow_rad_t, distance) }, \
|
||||
{ "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 40, offsetof(mavlink_optical_flow_rad_t, temperature) }, \
|
||||
{ "sensor_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_optical_flow_rad_t, sensor_id) }, \
|
||||
{ "quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 43, offsetof(mavlink_optical_flow_rad_t, quality) }, \
|
||||
} \
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @brief Pack a optical_flow_rad message
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
*
|
||||
* @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot)
|
||||
* @param sensor_id Sensor ID
|
||||
* @param integration_time_us Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the.
|
||||
* @param integrated_x 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.)
|
||||
* @param integrated_y 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.)
|
||||
* @param integrated_xgyro RH rotation around X axis (rad)
|
||||
* @param integrated_ygyro RH rotation around Y axis (rad)
|
||||
* @param integrated_zgyro RH rotation around Z axis (rad)
|
||||
* @param temperature Temperature * 100 in centi-degrees Celsius
|
||||
* @param quality Optical flow quality / confidence. 0: no valid flow, 255: maximum quality
|
||||
* @param time_delta_distance_us Time in microseconds since the distance was sampled.
|
||||
* @param distance Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance.
|
||||
* @return length of the message in bytes (excluding serial stream start sign)
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_optical_flow_rad_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)
|
||||
{
|
||||
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||
char buf[MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN];
|
||||
_mav_put_uint64_t(buf, 0, time_usec);
|
||||
_mav_put_uint32_t(buf, 8, integration_time_us);
|
||||
_mav_put_float(buf, 12, integrated_x);
|
||||
_mav_put_float(buf, 16, integrated_y);
|
||||
_mav_put_float(buf, 20, integrated_xgyro);
|
||||
_mav_put_float(buf, 24, integrated_ygyro);
|
||||
_mav_put_float(buf, 28, integrated_zgyro);
|
||||
_mav_put_uint32_t(buf, 32, time_delta_distance_us);
|
||||
_mav_put_float(buf, 36, distance);
|
||||
_mav_put_int16_t(buf, 40, temperature);
|
||||
_mav_put_uint8_t(buf, 42, sensor_id);
|
||||
_mav_put_uint8_t(buf, 43, quality);
|
||||
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN);
|
||||
#else
|
||||
mavlink_optical_flow_rad_t packet;
|
||||
packet.time_usec = time_usec;
|
||||
packet.integration_time_us = integration_time_us;
|
||||
packet.integrated_x = integrated_x;
|
||||
packet.integrated_y = integrated_y;
|
||||
packet.integrated_xgyro = integrated_xgyro;
|
||||
packet.integrated_ygyro = integrated_ygyro;
|
||||
packet.integrated_zgyro = integrated_zgyro;
|
||||
packet.time_delta_distance_us = time_delta_distance_us;
|
||||
packet.distance = distance;
|
||||
packet.temperature = temperature;
|
||||
packet.sensor_id = sensor_id;
|
||||
packet.quality = quality;
|
||||
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN);
|
||||
#endif
|
||||
|
||||
msg->msgid = MAVLINK_MSG_ID_OPTICAL_FLOW_RAD;
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_CRC);
|
||||
#else
|
||||
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN);
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Pack a optical_flow_rad message on a channel
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param chan The MAVLink channel this message will be sent over
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot)
|
||||
* @param sensor_id Sensor ID
|
||||
* @param integration_time_us Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the.
|
||||
* @param integrated_x 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.)
|
||||
* @param integrated_y 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.)
|
||||
* @param integrated_xgyro RH rotation around X axis (rad)
|
||||
* @param integrated_ygyro RH rotation around Y axis (rad)
|
||||
* @param integrated_zgyro RH rotation around Z axis (rad)
|
||||
* @param temperature Temperature * 100 in centi-degrees Celsius
|
||||
* @param quality Optical flow quality / confidence. 0: no valid flow, 255: maximum quality
|
||||
* @param time_delta_distance_us Time in microseconds since the distance was sampled.
|
||||
* @param distance Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance.
|
||||
* @return length of the message in bytes (excluding serial stream start sign)
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_optical_flow_rad_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)
|
||||
{
|
||||
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||
char buf[MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN];
|
||||
_mav_put_uint64_t(buf, 0, time_usec);
|
||||
_mav_put_uint32_t(buf, 8, integration_time_us);
|
||||
_mav_put_float(buf, 12, integrated_x);
|
||||
_mav_put_float(buf, 16, integrated_y);
|
||||
_mav_put_float(buf, 20, integrated_xgyro);
|
||||
_mav_put_float(buf, 24, integrated_ygyro);
|
||||
_mav_put_float(buf, 28, integrated_zgyro);
|
||||
_mav_put_uint32_t(buf, 32, time_delta_distance_us);
|
||||
_mav_put_float(buf, 36, distance);
|
||||
_mav_put_int16_t(buf, 40, temperature);
|
||||
_mav_put_uint8_t(buf, 42, sensor_id);
|
||||
_mav_put_uint8_t(buf, 43, quality);
|
||||
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN);
|
||||
#else
|
||||
mavlink_optical_flow_rad_t packet;
|
||||
packet.time_usec = time_usec;
|
||||
packet.integration_time_us = integration_time_us;
|
||||
packet.integrated_x = integrated_x;
|
||||
packet.integrated_y = integrated_y;
|
||||
packet.integrated_xgyro = integrated_xgyro;
|
||||
packet.integrated_ygyro = integrated_ygyro;
|
||||
packet.integrated_zgyro = integrated_zgyro;
|
||||
packet.time_delta_distance_us = time_delta_distance_us;
|
||||
packet.distance = distance;
|
||||
packet.temperature = temperature;
|
||||
packet.sensor_id = sensor_id;
|
||||
packet.quality = quality;
|
||||
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN);
|
||||
#endif
|
||||
|
||||
msg->msgid = MAVLINK_MSG_ID_OPTICAL_FLOW_RAD;
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_CRC);
|
||||
#else
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN);
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a optical_flow_rad struct
|
||||
*
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param optical_flow_rad C-struct to read the message contents from
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_optical_flow_rad_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_optical_flow_rad_t* optical_flow_rad)
|
||||
{
|
||||
return mavlink_msg_optical_flow_rad_pack(system_id, component_id, msg, optical_flow_rad->time_usec, optical_flow_rad->sensor_id, optical_flow_rad->integration_time_us, optical_flow_rad->integrated_x, optical_flow_rad->integrated_y, optical_flow_rad->integrated_xgyro, optical_flow_rad->integrated_ygyro, optical_flow_rad->integrated_zgyro, optical_flow_rad->temperature, optical_flow_rad->quality, optical_flow_rad->time_delta_distance_us, optical_flow_rad->distance);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a optical_flow_rad struct on a channel
|
||||
*
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param chan The MAVLink channel this message will be sent over
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param optical_flow_rad C-struct to read the message contents from
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_optical_flow_rad_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_optical_flow_rad_t* optical_flow_rad)
|
||||
{
|
||||
return mavlink_msg_optical_flow_rad_pack_chan(system_id, component_id, chan, msg, optical_flow_rad->time_usec, optical_flow_rad->sensor_id, optical_flow_rad->integration_time_us, optical_flow_rad->integrated_x, optical_flow_rad->integrated_y, optical_flow_rad->integrated_xgyro, optical_flow_rad->integrated_ygyro, optical_flow_rad->integrated_zgyro, optical_flow_rad->temperature, optical_flow_rad->quality, optical_flow_rad->time_delta_distance_us, optical_flow_rad->distance);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Send a optical_flow_rad message
|
||||
* @param chan MAVLink channel to send the message
|
||||
*
|
||||
* @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot)
|
||||
* @param sensor_id Sensor ID
|
||||
* @param integration_time_us Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the.
|
||||
* @param integrated_x 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.)
|
||||
* @param integrated_y 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.)
|
||||
* @param integrated_xgyro RH rotation around X axis (rad)
|
||||
* @param integrated_ygyro RH rotation around Y axis (rad)
|
||||
* @param integrated_zgyro RH rotation around Z axis (rad)
|
||||
* @param temperature Temperature * 100 in centi-degrees Celsius
|
||||
* @param quality Optical flow quality / confidence. 0: no valid flow, 255: maximum quality
|
||||
* @param time_delta_distance_us Time in microseconds since the distance was sampled.
|
||||
* @param distance Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance.
|
||||
*/
|
||||
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
|
||||
|
||||
static inline void mavlink_msg_optical_flow_rad_send(mavlink_channel_t chan, 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)
|
||||
{
|
||||
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||
char buf[MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN];
|
||||
_mav_put_uint64_t(buf, 0, time_usec);
|
||||
_mav_put_uint32_t(buf, 8, integration_time_us);
|
||||
_mav_put_float(buf, 12, integrated_x);
|
||||
_mav_put_float(buf, 16, integrated_y);
|
||||
_mav_put_float(buf, 20, integrated_xgyro);
|
||||
_mav_put_float(buf, 24, integrated_ygyro);
|
||||
_mav_put_float(buf, 28, integrated_zgyro);
|
||||
_mav_put_uint32_t(buf, 32, time_delta_distance_us);
|
||||
_mav_put_float(buf, 36, distance);
|
||||
_mav_put_int16_t(buf, 40, temperature);
|
||||
_mav_put_uint8_t(buf, 42, sensor_id);
|
||||
_mav_put_uint8_t(buf, 43, quality);
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD, buf, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD, buf, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN);
|
||||
#endif
|
||||
#else
|
||||
mavlink_optical_flow_rad_t packet;
|
||||
packet.time_usec = time_usec;
|
||||
packet.integration_time_us = integration_time_us;
|
||||
packet.integrated_x = integrated_x;
|
||||
packet.integrated_y = integrated_y;
|
||||
packet.integrated_xgyro = integrated_xgyro;
|
||||
packet.integrated_ygyro = integrated_ygyro;
|
||||
packet.integrated_zgyro = integrated_zgyro;
|
||||
packet.time_delta_distance_us = time_delta_distance_us;
|
||||
packet.distance = distance;
|
||||
packet.temperature = temperature;
|
||||
packet.sensor_id = sensor_id;
|
||||
packet.quality = quality;
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD, (const char *)&packet, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD, (const char *)&packet, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN);
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
|
||||
#if MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN <= MAVLINK_MAX_PAYLOAD_LEN
|
||||
/*
|
||||
This varient of _send() can be used to save stack space by re-using
|
||||
memory from the receive buffer. The caller provides a
|
||||
mavlink_message_t which is the size of a full mavlink message. This
|
||||
is usually the receive buffer for the channel, and allows a reply to an
|
||||
incoming message with minimum stack space usage.
|
||||
*/
|
||||
static inline void mavlink_msg_optical_flow_rad_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, 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)
|
||||
{
|
||||
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||
char *buf = (char *)msgbuf;
|
||||
_mav_put_uint64_t(buf, 0, time_usec);
|
||||
_mav_put_uint32_t(buf, 8, integration_time_us);
|
||||
_mav_put_float(buf, 12, integrated_x);
|
||||
_mav_put_float(buf, 16, integrated_y);
|
||||
_mav_put_float(buf, 20, integrated_xgyro);
|
||||
_mav_put_float(buf, 24, integrated_ygyro);
|
||||
_mav_put_float(buf, 28, integrated_zgyro);
|
||||
_mav_put_uint32_t(buf, 32, time_delta_distance_us);
|
||||
_mav_put_float(buf, 36, distance);
|
||||
_mav_put_int16_t(buf, 40, temperature);
|
||||
_mav_put_uint8_t(buf, 42, sensor_id);
|
||||
_mav_put_uint8_t(buf, 43, quality);
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD, buf, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD, buf, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN);
|
||||
#endif
|
||||
#else
|
||||
mavlink_optical_flow_rad_t *packet = (mavlink_optical_flow_rad_t *)msgbuf;
|
||||
packet->time_usec = time_usec;
|
||||
packet->integration_time_us = integration_time_us;
|
||||
packet->integrated_x = integrated_x;
|
||||
packet->integrated_y = integrated_y;
|
||||
packet->integrated_xgyro = integrated_xgyro;
|
||||
packet->integrated_ygyro = integrated_ygyro;
|
||||
packet->integrated_zgyro = integrated_zgyro;
|
||||
packet->time_delta_distance_us = time_delta_distance_us;
|
||||
packet->distance = distance;
|
||||
packet->temperature = temperature;
|
||||
packet->sensor_id = sensor_id;
|
||||
packet->quality = quality;
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD, (const char *)packet, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD, (const char *)packet, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN);
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif
|
||||
|
||||
// MESSAGE OPTICAL_FLOW_RAD UNPACKING
|
||||
|
||||
|
||||
/**
|
||||
* @brief Get field time_usec from optical_flow_rad message
|
||||
*
|
||||
* @return Timestamp (microseconds, synced to UNIX time or since system boot)
|
||||
*/
|
||||
static inline uint64_t mavlink_msg_optical_flow_rad_get_time_usec(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_uint64_t(msg, 0);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field sensor_id from optical_flow_rad message
|
||||
*
|
||||
* @return Sensor ID
|
||||
*/
|
||||
static inline uint8_t mavlink_msg_optical_flow_rad_get_sensor_id(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_uint8_t(msg, 42);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field integration_time_us from optical_flow_rad message
|
||||
*
|
||||
* @return Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the.
|
||||
*/
|
||||
static inline uint32_t mavlink_msg_optical_flow_rad_get_integration_time_us(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_uint32_t(msg, 8);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field integrated_x from optical_flow_rad message
|
||||
*
|
||||
* @return 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.)
|
||||
*/
|
||||
static inline float mavlink_msg_optical_flow_rad_get_integrated_x(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_float(msg, 12);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field integrated_y from optical_flow_rad message
|
||||
*
|
||||
* @return 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.)
|
||||
*/
|
||||
static inline float mavlink_msg_optical_flow_rad_get_integrated_y(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_float(msg, 16);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field integrated_xgyro from optical_flow_rad message
|
||||
*
|
||||
* @return RH rotation around X axis (rad)
|
||||
*/
|
||||
static inline float mavlink_msg_optical_flow_rad_get_integrated_xgyro(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_float(msg, 20);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field integrated_ygyro from optical_flow_rad message
|
||||
*
|
||||
* @return RH rotation around Y axis (rad)
|
||||
*/
|
||||
static inline float mavlink_msg_optical_flow_rad_get_integrated_ygyro(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_float(msg, 24);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field integrated_zgyro from optical_flow_rad message
|
||||
*
|
||||
* @return RH rotation around Z axis (rad)
|
||||
*/
|
||||
static inline float mavlink_msg_optical_flow_rad_get_integrated_zgyro(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_float(msg, 28);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field temperature from optical_flow_rad message
|
||||
*
|
||||
* @return Temperature * 100 in centi-degrees Celsius
|
||||
*/
|
||||
static inline int16_t mavlink_msg_optical_flow_rad_get_temperature(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_int16_t(msg, 40);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field quality from optical_flow_rad message
|
||||
*
|
||||
* @return Optical flow quality / confidence. 0: no valid flow, 255: maximum quality
|
||||
*/
|
||||
static inline uint8_t mavlink_msg_optical_flow_rad_get_quality(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_uint8_t(msg, 43);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field time_delta_distance_us from optical_flow_rad message
|
||||
*
|
||||
* @return Time in microseconds since the distance was sampled.
|
||||
*/
|
||||
static inline uint32_t mavlink_msg_optical_flow_rad_get_time_delta_distance_us(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_uint32_t(msg, 32);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field distance from optical_flow_rad message
|
||||
*
|
||||
* @return Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance.
|
||||
*/
|
||||
static inline float mavlink_msg_optical_flow_rad_get_distance(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_float(msg, 36);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Decode a optical_flow_rad message into a struct
|
||||
*
|
||||
* @param msg The message to decode
|
||||
* @param optical_flow_rad C-struct to decode the message contents into
|
||||
*/
|
||||
static inline void mavlink_msg_optical_flow_rad_decode(const mavlink_message_t* msg, mavlink_optical_flow_rad_t* optical_flow_rad)
|
||||
{
|
||||
#if MAVLINK_NEED_BYTE_SWAP
|
||||
optical_flow_rad->time_usec = mavlink_msg_optical_flow_rad_get_time_usec(msg);
|
||||
optical_flow_rad->integration_time_us = mavlink_msg_optical_flow_rad_get_integration_time_us(msg);
|
||||
optical_flow_rad->integrated_x = mavlink_msg_optical_flow_rad_get_integrated_x(msg);
|
||||
optical_flow_rad->integrated_y = mavlink_msg_optical_flow_rad_get_integrated_y(msg);
|
||||
optical_flow_rad->integrated_xgyro = mavlink_msg_optical_flow_rad_get_integrated_xgyro(msg);
|
||||
optical_flow_rad->integrated_ygyro = mavlink_msg_optical_flow_rad_get_integrated_ygyro(msg);
|
||||
optical_flow_rad->integrated_zgyro = mavlink_msg_optical_flow_rad_get_integrated_zgyro(msg);
|
||||
optical_flow_rad->time_delta_distance_us = mavlink_msg_optical_flow_rad_get_time_delta_distance_us(msg);
|
||||
optical_flow_rad->distance = mavlink_msg_optical_flow_rad_get_distance(msg);
|
||||
optical_flow_rad->temperature = mavlink_msg_optical_flow_rad_get_temperature(msg);
|
||||
optical_flow_rad->sensor_id = mavlink_msg_optical_flow_rad_get_sensor_id(msg);
|
||||
optical_flow_rad->quality = mavlink_msg_optical_flow_rad_get_quality(msg);
|
||||
#else
|
||||
memcpy(optical_flow_rad, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN);
|
||||
#endif
|
||||
}
|
|
@ -4,7 +4,7 @@
|
|||
|
||||
typedef struct __mavlink_ping_t
|
||||
{
|
||||
uint64_t time_usec; ///< Unix timestamp in microseconds
|
||||
uint64_t time_usec; ///< Unix timestamp in microseconds or since system boot if smaller than MAVLink epoch (1.1.2009)
|
||||
uint32_t seq; ///< PING sequence
|
||||
uint8_t target_system; ///< 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
|
||||
uint8_t target_component; ///< 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
|
||||
|
@ -35,7 +35,7 @@ typedef struct __mavlink_ping_t
|
|||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
*
|
||||
* @param time_usec Unix timestamp in microseconds
|
||||
* @param time_usec Unix timestamp in microseconds or since system boot if smaller than MAVLink epoch (1.1.2009)
|
||||
* @param seq PING sequence
|
||||
* @param target_system 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
|
||||
* @param target_component 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
|
||||
|
@ -76,7 +76,7 @@ static inline uint16_t mavlink_msg_ping_pack(uint8_t system_id, uint8_t componen
|
|||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param chan The MAVLink channel this message will be sent over
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param time_usec Unix timestamp in microseconds
|
||||
* @param time_usec Unix timestamp in microseconds or since system boot if smaller than MAVLink epoch (1.1.2009)
|
||||
* @param seq PING sequence
|
||||
* @param target_system 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
|
||||
* @param target_component 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
|
||||
|
@ -143,7 +143,7 @@ static inline uint16_t mavlink_msg_ping_encode_chan(uint8_t system_id, uint8_t c
|
|||
* @brief Send a ping message
|
||||
* @param chan MAVLink channel to send the message
|
||||
*
|
||||
* @param time_usec Unix timestamp in microseconds
|
||||
* @param time_usec Unix timestamp in microseconds or since system boot if smaller than MAVLink epoch (1.1.2009)
|
||||
* @param seq PING sequence
|
||||
* @param target_system 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
|
||||
* @param target_component 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
|
||||
|
@ -225,7 +225,7 @@ static inline void mavlink_msg_ping_send_buf(mavlink_message_t *msgbuf, mavlink_
|
|||
/**
|
||||
* @brief Get field time_usec from ping message
|
||||
*
|
||||
* @return Unix timestamp in microseconds
|
||||
* @return Unix timestamp in microseconds or since system boot if smaller than MAVLink epoch (1.1.2009)
|
||||
*/
|
||||
static inline uint64_t mavlink_msg_ping_get_time_usec(const mavlink_message_t* msg)
|
||||
{
|
||||
|
|
|
@ -0,0 +1,233 @@
|
|||
// MESSAGE TIMESYNC PACKING
|
||||
|
||||
#define MAVLINK_MSG_ID_TIMESYNC 111
|
||||
|
||||
typedef struct __mavlink_timesync_t
|
||||
{
|
||||
int64_t tc1; ///< Time sync timestamp 1
|
||||
int64_t ts1; ///< Time sync timestamp 2
|
||||
} mavlink_timesync_t;
|
||||
|
||||
#define MAVLINK_MSG_ID_TIMESYNC_LEN 16
|
||||
#define MAVLINK_MSG_ID_111_LEN 16
|
||||
|
||||
#define MAVLINK_MSG_ID_TIMESYNC_CRC 34
|
||||
#define MAVLINK_MSG_ID_111_CRC 34
|
||||
|
||||
|
||||
|
||||
#define MAVLINK_MESSAGE_INFO_TIMESYNC { \
|
||||
"TIMESYNC", \
|
||||
2, \
|
||||
{ { "tc1", NULL, MAVLINK_TYPE_INT64_T, 0, 0, offsetof(mavlink_timesync_t, tc1) }, \
|
||||
{ "ts1", NULL, MAVLINK_TYPE_INT64_T, 0, 8, offsetof(mavlink_timesync_t, ts1) }, \
|
||||
} \
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @brief Pack a timesync message
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
*
|
||||
* @param tc1 Time sync timestamp 1
|
||||
* @param ts1 Time sync timestamp 2
|
||||
* @return length of the message in bytes (excluding serial stream start sign)
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_timesync_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
|
||||
int64_t tc1, int64_t ts1)
|
||||
{
|
||||
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||
char buf[MAVLINK_MSG_ID_TIMESYNC_LEN];
|
||||
_mav_put_int64_t(buf, 0, tc1);
|
||||
_mav_put_int64_t(buf, 8, ts1);
|
||||
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TIMESYNC_LEN);
|
||||
#else
|
||||
mavlink_timesync_t packet;
|
||||
packet.tc1 = tc1;
|
||||
packet.ts1 = ts1;
|
||||
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TIMESYNC_LEN);
|
||||
#endif
|
||||
|
||||
msg->msgid = MAVLINK_MSG_ID_TIMESYNC;
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_TIMESYNC_LEN, MAVLINK_MSG_ID_TIMESYNC_CRC);
|
||||
#else
|
||||
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_TIMESYNC_LEN);
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Pack a timesync message on a channel
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param chan The MAVLink channel this message will be sent over
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param tc1 Time sync timestamp 1
|
||||
* @param ts1 Time sync timestamp 2
|
||||
* @return length of the message in bytes (excluding serial stream start sign)
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_timesync_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
|
||||
mavlink_message_t* msg,
|
||||
int64_t tc1,int64_t ts1)
|
||||
{
|
||||
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||
char buf[MAVLINK_MSG_ID_TIMESYNC_LEN];
|
||||
_mav_put_int64_t(buf, 0, tc1);
|
||||
_mav_put_int64_t(buf, 8, ts1);
|
||||
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TIMESYNC_LEN);
|
||||
#else
|
||||
mavlink_timesync_t packet;
|
||||
packet.tc1 = tc1;
|
||||
packet.ts1 = ts1;
|
||||
|
||||
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TIMESYNC_LEN);
|
||||
#endif
|
||||
|
||||
msg->msgid = MAVLINK_MSG_ID_TIMESYNC;
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_TIMESYNC_LEN, MAVLINK_MSG_ID_TIMESYNC_CRC);
|
||||
#else
|
||||
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_TIMESYNC_LEN);
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a timesync struct
|
||||
*
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param timesync C-struct to read the message contents from
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_timesync_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_timesync_t* timesync)
|
||||
{
|
||||
return mavlink_msg_timesync_pack(system_id, component_id, msg, timesync->tc1, timesync->ts1);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Encode a timesync struct on a channel
|
||||
*
|
||||
* @param system_id ID of this system
|
||||
* @param component_id ID of this component (e.g. 200 for IMU)
|
||||
* @param chan The MAVLink channel this message will be sent over
|
||||
* @param msg The MAVLink message to compress the data into
|
||||
* @param timesync C-struct to read the message contents from
|
||||
*/
|
||||
static inline uint16_t mavlink_msg_timesync_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_timesync_t* timesync)
|
||||
{
|
||||
return mavlink_msg_timesync_pack_chan(system_id, component_id, chan, msg, timesync->tc1, timesync->ts1);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Send a timesync message
|
||||
* @param chan MAVLink channel to send the message
|
||||
*
|
||||
* @param tc1 Time sync timestamp 1
|
||||
* @param ts1 Time sync timestamp 2
|
||||
*/
|
||||
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
|
||||
|
||||
static inline void mavlink_msg_timesync_send(mavlink_channel_t chan, int64_t tc1, int64_t ts1)
|
||||
{
|
||||
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||
char buf[MAVLINK_MSG_ID_TIMESYNC_LEN];
|
||||
_mav_put_int64_t(buf, 0, tc1);
|
||||
_mav_put_int64_t(buf, 8, ts1);
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TIMESYNC, buf, MAVLINK_MSG_ID_TIMESYNC_LEN, MAVLINK_MSG_ID_TIMESYNC_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TIMESYNC, buf, MAVLINK_MSG_ID_TIMESYNC_LEN);
|
||||
#endif
|
||||
#else
|
||||
mavlink_timesync_t packet;
|
||||
packet.tc1 = tc1;
|
||||
packet.ts1 = ts1;
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TIMESYNC, (const char *)&packet, MAVLINK_MSG_ID_TIMESYNC_LEN, MAVLINK_MSG_ID_TIMESYNC_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TIMESYNC, (const char *)&packet, MAVLINK_MSG_ID_TIMESYNC_LEN);
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
|
||||
#if MAVLINK_MSG_ID_TIMESYNC_LEN <= MAVLINK_MAX_PAYLOAD_LEN
|
||||
/*
|
||||
This varient of _send() can be used to save stack space by re-using
|
||||
memory from the receive buffer. The caller provides a
|
||||
mavlink_message_t which is the size of a full mavlink message. This
|
||||
is usually the receive buffer for the channel, and allows a reply to an
|
||||
incoming message with minimum stack space usage.
|
||||
*/
|
||||
static inline void mavlink_msg_timesync_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, int64_t tc1, int64_t ts1)
|
||||
{
|
||||
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
||||
char *buf = (char *)msgbuf;
|
||||
_mav_put_int64_t(buf, 0, tc1);
|
||||
_mav_put_int64_t(buf, 8, ts1);
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TIMESYNC, buf, MAVLINK_MSG_ID_TIMESYNC_LEN, MAVLINK_MSG_ID_TIMESYNC_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TIMESYNC, buf, MAVLINK_MSG_ID_TIMESYNC_LEN);
|
||||
#endif
|
||||
#else
|
||||
mavlink_timesync_t *packet = (mavlink_timesync_t *)msgbuf;
|
||||
packet->tc1 = tc1;
|
||||
packet->ts1 = ts1;
|
||||
|
||||
#if MAVLINK_CRC_EXTRA
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TIMESYNC, (const char *)packet, MAVLINK_MSG_ID_TIMESYNC_LEN, MAVLINK_MSG_ID_TIMESYNC_CRC);
|
||||
#else
|
||||
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TIMESYNC, (const char *)packet, MAVLINK_MSG_ID_TIMESYNC_LEN);
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif
|
||||
|
||||
// MESSAGE TIMESYNC UNPACKING
|
||||
|
||||
|
||||
/**
|
||||
* @brief Get field tc1 from timesync message
|
||||
*
|
||||
* @return Time sync timestamp 1
|
||||
*/
|
||||
static inline int64_t mavlink_msg_timesync_get_tc1(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_int64_t(msg, 0);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get field ts1 from timesync message
|
||||
*
|
||||
* @return Time sync timestamp 2
|
||||
*/
|
||||
static inline int64_t mavlink_msg_timesync_get_ts1(const mavlink_message_t* msg)
|
||||
{
|
||||
return _MAV_RETURN_int64_t(msg, 8);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Decode a timesync message into a struct
|
||||
*
|
||||
* @param msg The message to decode
|
||||
* @param timesync C-struct to decode the message contents into
|
||||
*/
|
||||
static inline void mavlink_msg_timesync_decode(const mavlink_message_t* msg, mavlink_timesync_t* timesync)
|
||||
{
|
||||
#if MAVLINK_NEED_BYTE_SWAP
|
||||
timesync->tc1 = mavlink_msg_timesync_get_tc1(msg);
|
||||
timesync->ts1 = mavlink_msg_timesync_get_ts1(msg);
|
||||
#else
|
||||
memcpy(timesync, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_TIMESYNC_LEN);
|
||||
#endif
|
||||
}
|
|
@ -3534,38 +3534,44 @@ static void mavlink_test_highres_imu(uint8_t system_id, uint8_t component_id, ma
|
|||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
}
|
||||
|
||||
static void mavlink_test_omnidirectional_flow(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
|
||||
static void mavlink_test_optical_flow_rad(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
|
||||
uint16_t i;
|
||||
mavlink_omnidirectional_flow_t packet_in = {
|
||||
93372036854775807ULL,73.0,{ 17859, 17860, 17861, 17862, 17863, 17864, 17865, 17866, 17867, 17868 },{ 18899, 18900, 18901, 18902, 18903, 18904, 18905, 18906, 18907, 18908 },161,228
|
||||
mavlink_optical_flow_rad_t packet_in = {
|
||||
93372036854775807ULL,963497880,101.0,129.0,157.0,185.0,213.0,963499128,269.0,19315,3,70
|
||||
};
|
||||
mavlink_omnidirectional_flow_t packet1, packet2;
|
||||
mavlink_optical_flow_rad_t packet1, packet2;
|
||||
memset(&packet1, 0, sizeof(packet1));
|
||||
packet1.time_usec = packet_in.time_usec;
|
||||
packet1.front_distance_m = packet_in.front_distance_m;
|
||||
packet1.integration_time_us = packet_in.integration_time_us;
|
||||
packet1.integrated_x = packet_in.integrated_x;
|
||||
packet1.integrated_y = packet_in.integrated_y;
|
||||
packet1.integrated_xgyro = packet_in.integrated_xgyro;
|
||||
packet1.integrated_ygyro = packet_in.integrated_ygyro;
|
||||
packet1.integrated_zgyro = packet_in.integrated_zgyro;
|
||||
packet1.time_delta_distance_us = packet_in.time_delta_distance_us;
|
||||
packet1.distance = packet_in.distance;
|
||||
packet1.temperature = packet_in.temperature;
|
||||
packet1.sensor_id = packet_in.sensor_id;
|
||||
packet1.quality = packet_in.quality;
|
||||
|
||||
mav_array_memcpy(packet1.left, packet_in.left, sizeof(int16_t)*10);
|
||||
mav_array_memcpy(packet1.right, packet_in.right, sizeof(int16_t)*10);
|
||||
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_omnidirectional_flow_encode(system_id, component_id, &msg, &packet1);
|
||||
mavlink_msg_omnidirectional_flow_decode(&msg, &packet2);
|
||||
mavlink_msg_optical_flow_rad_encode(system_id, component_id, &msg, &packet1);
|
||||
mavlink_msg_optical_flow_rad_decode(&msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_omnidirectional_flow_pack(system_id, component_id, &msg , packet1.time_usec , packet1.sensor_id , packet1.left , packet1.right , packet1.quality , packet1.front_distance_m );
|
||||
mavlink_msg_omnidirectional_flow_decode(&msg, &packet2);
|
||||
mavlink_msg_optical_flow_rad_pack(system_id, component_id, &msg , packet1.time_usec , packet1.sensor_id , packet1.integration_time_us , packet1.integrated_x , packet1.integrated_y , packet1.integrated_xgyro , packet1.integrated_ygyro , packet1.integrated_zgyro , packet1.temperature , packet1.quality , packet1.time_delta_distance_us , packet1.distance );
|
||||
mavlink_msg_optical_flow_rad_decode(&msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_omnidirectional_flow_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.sensor_id , packet1.left , packet1.right , packet1.quality , packet1.front_distance_m );
|
||||
mavlink_msg_omnidirectional_flow_decode(&msg, &packet2);
|
||||
mavlink_msg_optical_flow_rad_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.sensor_id , packet1.integration_time_us , packet1.integrated_x , packet1.integrated_y , packet1.integrated_xgyro , packet1.integrated_ygyro , packet1.integrated_zgyro , packet1.temperature , packet1.quality , packet1.time_delta_distance_us , packet1.distance );
|
||||
mavlink_msg_optical_flow_rad_decode(&msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
|
@ -3573,12 +3579,12 @@ static void mavlink_test_omnidirectional_flow(uint8_t system_id, uint8_t compone
|
|||
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
|
||||
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
|
||||
}
|
||||
mavlink_msg_omnidirectional_flow_decode(last_msg, &packet2);
|
||||
mavlink_msg_optical_flow_rad_decode(last_msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_omnidirectional_flow_send(MAVLINK_COMM_1 , packet1.time_usec , packet1.sensor_id , packet1.left , packet1.right , packet1.quality , packet1.front_distance_m );
|
||||
mavlink_msg_omnidirectional_flow_decode(last_msg, &packet2);
|
||||
mavlink_msg_optical_flow_rad_send(MAVLINK_COMM_1 , packet1.time_usec , packet1.sensor_id , packet1.integration_time_us , packet1.integrated_x , packet1.integrated_y , packet1.integrated_xgyro , packet1.integrated_ygyro , packet1.integrated_zgyro , packet1.temperature , packet1.quality , packet1.time_delta_distance_us , packet1.distance );
|
||||
mavlink_msg_optical_flow_rad_decode(last_msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
}
|
||||
|
||||
|
@ -3797,6 +3803,50 @@ static void mavlink_test_file_transfer_protocol(uint8_t system_id, uint8_t compo
|
|||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
}
|
||||
|
||||
static void mavlink_test_timesync(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
|
||||
uint16_t i;
|
||||
mavlink_timesync_t packet_in = {
|
||||
93372036854775807LL,93372036854776311LL
|
||||
};
|
||||
mavlink_timesync_t packet1, packet2;
|
||||
memset(&packet1, 0, sizeof(packet1));
|
||||
packet1.tc1 = packet_in.tc1;
|
||||
packet1.ts1 = packet_in.ts1;
|
||||
|
||||
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_timesync_encode(system_id, component_id, &msg, &packet1);
|
||||
mavlink_msg_timesync_decode(&msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_timesync_pack(system_id, component_id, &msg , packet1.tc1 , packet1.ts1 );
|
||||
mavlink_msg_timesync_decode(&msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_timesync_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.tc1 , packet1.ts1 );
|
||||
mavlink_msg_timesync_decode(&msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_to_send_buffer(buffer, &msg);
|
||||
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
|
||||
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
|
||||
}
|
||||
mavlink_msg_timesync_decode(last_msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_timesync_send(MAVLINK_COMM_1 , packet1.tc1 , packet1.ts1 );
|
||||
mavlink_msg_timesync_decode(last_msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
}
|
||||
|
||||
static void mavlink_test_hil_gps(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
|
||||
{
|
||||
mavlink_message_t msg;
|
||||
|
@ -3858,16 +3908,20 @@ static void mavlink_test_hil_optical_flow(uint8_t system_id, uint8_t component_i
|
|||
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
|
||||
uint16_t i;
|
||||
mavlink_hil_optical_flow_t packet_in = {
|
||||
93372036854775807ULL,73.0,101.0,129.0,18275,18379,77,144
|
||||
93372036854775807ULL,963497880,101.0,129.0,157.0,185.0,213.0,963499128,269.0,19315,3,70
|
||||
};
|
||||
mavlink_hil_optical_flow_t packet1, packet2;
|
||||
memset(&packet1, 0, sizeof(packet1));
|
||||
packet1.time_usec = packet_in.time_usec;
|
||||
packet1.flow_comp_m_x = packet_in.flow_comp_m_x;
|
||||
packet1.flow_comp_m_y = packet_in.flow_comp_m_y;
|
||||
packet1.ground_distance = packet_in.ground_distance;
|
||||
packet1.flow_x = packet_in.flow_x;
|
||||
packet1.flow_y = packet_in.flow_y;
|
||||
packet1.integration_time_us = packet_in.integration_time_us;
|
||||
packet1.integrated_x = packet_in.integrated_x;
|
||||
packet1.integrated_y = packet_in.integrated_y;
|
||||
packet1.integrated_xgyro = packet_in.integrated_xgyro;
|
||||
packet1.integrated_ygyro = packet_in.integrated_ygyro;
|
||||
packet1.integrated_zgyro = packet_in.integrated_zgyro;
|
||||
packet1.time_delta_distance_us = packet_in.time_delta_distance_us;
|
||||
packet1.distance = packet_in.distance;
|
||||
packet1.temperature = packet_in.temperature;
|
||||
packet1.sensor_id = packet_in.sensor_id;
|
||||
packet1.quality = packet_in.quality;
|
||||
|
||||
|
@ -3879,12 +3933,12 @@ static void mavlink_test_hil_optical_flow(uint8_t system_id, uint8_t component_i
|
|||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_hil_optical_flow_pack(system_id, component_id, &msg , packet1.time_usec , packet1.sensor_id , packet1.flow_x , packet1.flow_y , packet1.flow_comp_m_x , packet1.flow_comp_m_y , packet1.quality , packet1.ground_distance );
|
||||
mavlink_msg_hil_optical_flow_pack(system_id, component_id, &msg , packet1.time_usec , packet1.sensor_id , packet1.integration_time_us , packet1.integrated_x , packet1.integrated_y , packet1.integrated_xgyro , packet1.integrated_ygyro , packet1.integrated_zgyro , packet1.temperature , packet1.quality , packet1.time_delta_distance_us , packet1.distance );
|
||||
mavlink_msg_hil_optical_flow_decode(&msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_hil_optical_flow_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.sensor_id , packet1.flow_x , packet1.flow_y , packet1.flow_comp_m_x , packet1.flow_comp_m_y , packet1.quality , packet1.ground_distance );
|
||||
mavlink_msg_hil_optical_flow_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.sensor_id , packet1.integration_time_us , packet1.integrated_x , packet1.integrated_y , packet1.integrated_xgyro , packet1.integrated_ygyro , packet1.integrated_zgyro , packet1.temperature , packet1.quality , packet1.time_delta_distance_us , packet1.distance );
|
||||
mavlink_msg_hil_optical_flow_decode(&msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
|
@ -3897,7 +3951,7 @@ static void mavlink_test_hil_optical_flow(uint8_t system_id, uint8_t component_i
|
|||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
|
||||
memset(&packet2, 0, sizeof(packet2));
|
||||
mavlink_msg_hil_optical_flow_send(MAVLINK_COMM_1 , packet1.time_usec , packet1.sensor_id , packet1.flow_x , packet1.flow_y , packet1.flow_comp_m_x , packet1.flow_comp_m_y , packet1.quality , packet1.ground_distance );
|
||||
mavlink_msg_hil_optical_flow_send(MAVLINK_COMM_1 , packet1.time_usec , packet1.sensor_id , packet1.integration_time_us , packet1.integrated_x , packet1.integrated_y , packet1.integrated_xgyro , packet1.integrated_ygyro , packet1.integrated_zgyro , packet1.temperature , packet1.quality , packet1.time_delta_distance_us , packet1.distance );
|
||||
mavlink_msg_hil_optical_flow_decode(last_msg, &packet2);
|
||||
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
|
||||
}
|
||||
|
@ -5406,11 +5460,12 @@ static void mavlink_test_common(uint8_t system_id, uint8_t component_id, mavlink
|
|||
mavlink_test_vision_speed_estimate(system_id, component_id, last_msg);
|
||||
mavlink_test_vicon_position_estimate(system_id, component_id, last_msg);
|
||||
mavlink_test_highres_imu(system_id, component_id, last_msg);
|
||||
mavlink_test_omnidirectional_flow(system_id, component_id, last_msg);
|
||||
mavlink_test_optical_flow_rad(system_id, component_id, last_msg);
|
||||
mavlink_test_hil_sensor(system_id, component_id, last_msg);
|
||||
mavlink_test_sim_state(system_id, component_id, last_msg);
|
||||
mavlink_test_radio_status(system_id, component_id, last_msg);
|
||||
mavlink_test_file_transfer_protocol(system_id, component_id, last_msg);
|
||||
mavlink_test_timesync(system_id, component_id, last_msg);
|
||||
mavlink_test_hil_gps(system_id, component_id, last_msg);
|
||||
mavlink_test_hil_optical_flow(system_id, component_id, last_msg);
|
||||
mavlink_test_hil_state_quaternion(system_id, component_id, last_msg);
|
||||
|
|
|
@ -5,7 +5,7 @@
|
|||
#ifndef MAVLINK_VERSION_H
|
||||
#define MAVLINK_VERSION_H
|
||||
|
||||
#define MAVLINK_BUILD_DATE "Sat Oct 18 12:05:51 2014"
|
||||
#define MAVLINK_BUILD_DATE "Fri Nov 14 15:24:39 2014"
|
||||
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
|
||||
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255
|
||||
|
||||
|
|
Loading…
Reference in New Issue