Commit c6f04883 authored by PX4BuildBot's avatar PX4BuildBot

autogenerated headers for rev...

autogenerated headers for rev https://github.com/mavlink/mavlink/tree/4ed72b0cfa22576436ec69cb670a01be08262103
parent d54436d4
...@@ -6,8 +6,8 @@ ...@@ -6,8 +6,8 @@
MAVPACKED( MAVPACKED(
typedef struct __mavlink_optical_flow_t { typedef struct __mavlink_optical_flow_t {
uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude the number.*/ uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude the number.*/
float flow_comp_m_x; /*< [m] Flow in x-sensor direction, angular-speed compensated*/ float flow_comp_m_x; /*< [m/s] Flow in x-sensor direction, angular-speed compensated*/
float flow_comp_m_y; /*< [m] Flow in y-sensor direction, angular-speed compensated*/ float flow_comp_m_y; /*< [m/s] Flow in y-sensor direction, angular-speed compensated*/
float ground_distance; /*< [m] Ground distance. Positive value: distance known. Negative value: Unknown distance*/ float ground_distance; /*< [m] Ground distance. Positive value: distance known. Negative value: Unknown distance*/
int16_t flow_x; /*< [dpix] Flow in x-sensor direction*/ int16_t flow_x; /*< [dpix] Flow in x-sensor direction*/
int16_t flow_y; /*< [dpix] Flow in y-sensor direction*/ int16_t flow_y; /*< [dpix] Flow in y-sensor direction*/
...@@ -72,8 +72,8 @@ typedef struct __mavlink_optical_flow_t { ...@@ -72,8 +72,8 @@ typedef struct __mavlink_optical_flow_t {
* @param sensor_id Sensor ID * @param sensor_id Sensor ID
* @param flow_x [dpix] Flow in x-sensor direction * @param flow_x [dpix] Flow in x-sensor direction
* @param flow_y [dpix] Flow in y-sensor direction * @param flow_y [dpix] Flow in y-sensor direction
* @param flow_comp_m_x [m] Flow in x-sensor direction, angular-speed compensated * @param flow_comp_m_x [m/s] Flow in x-sensor direction, angular-speed compensated
* @param flow_comp_m_y [m] Flow in y-sensor direction, angular-speed compensated * @param flow_comp_m_y [m/s] Flow in y-sensor direction, angular-speed compensated
* @param quality Optical flow quality / confidence. 0: bad, 255: maximum quality * @param quality Optical flow quality / confidence. 0: bad, 255: maximum quality
* @param ground_distance [m] Ground distance. Positive value: distance known. Negative value: Unknown distance * @param ground_distance [m] Ground distance. Positive value: distance known. Negative value: Unknown distance
* @param flow_rate_x [rad/s] Flow rate about X axis * @param flow_rate_x [rad/s] Flow rate about X axis
...@@ -127,8 +127,8 @@ static inline uint16_t mavlink_msg_optical_flow_pack(uint8_t system_id, uint8_t ...@@ -127,8 +127,8 @@ static inline uint16_t mavlink_msg_optical_flow_pack(uint8_t system_id, uint8_t
* @param sensor_id Sensor ID * @param sensor_id Sensor ID
* @param flow_x [dpix] Flow in x-sensor direction * @param flow_x [dpix] Flow in x-sensor direction
* @param flow_y [dpix] Flow in y-sensor direction * @param flow_y [dpix] Flow in y-sensor direction
* @param flow_comp_m_x [m] Flow in x-sensor direction, angular-speed compensated * @param flow_comp_m_x [m/s] Flow in x-sensor direction, angular-speed compensated
* @param flow_comp_m_y [m] Flow in y-sensor direction, angular-speed compensated * @param flow_comp_m_y [m/s] Flow in y-sensor direction, angular-speed compensated
* @param quality Optical flow quality / confidence. 0: bad, 255: maximum quality * @param quality Optical flow quality / confidence. 0: bad, 255: maximum quality
* @param ground_distance [m] Ground distance. Positive value: distance known. Negative value: Unknown distance * @param ground_distance [m] Ground distance. Positive value: distance known. Negative value: Unknown distance
* @param flow_rate_x [rad/s] Flow rate about X axis * @param flow_rate_x [rad/s] Flow rate about X axis
...@@ -208,8 +208,8 @@ static inline uint16_t mavlink_msg_optical_flow_encode_chan(uint8_t system_id, u ...@@ -208,8 +208,8 @@ static inline uint16_t mavlink_msg_optical_flow_encode_chan(uint8_t system_id, u
* @param sensor_id Sensor ID * @param sensor_id Sensor ID
* @param flow_x [dpix] Flow in x-sensor direction * @param flow_x [dpix] Flow in x-sensor direction
* @param flow_y [dpix] Flow in y-sensor direction * @param flow_y [dpix] Flow in y-sensor direction
* @param flow_comp_m_x [m] Flow in x-sensor direction, angular-speed compensated * @param flow_comp_m_x [m/s] Flow in x-sensor direction, angular-speed compensated
* @param flow_comp_m_y [m] Flow in y-sensor direction, angular-speed compensated * @param flow_comp_m_y [m/s] Flow in y-sensor direction, angular-speed compensated
* @param quality Optical flow quality / confidence. 0: bad, 255: maximum quality * @param quality Optical flow quality / confidence. 0: bad, 255: maximum quality
* @param ground_distance [m] Ground distance. Positive value: distance known. Negative value: Unknown distance * @param ground_distance [m] Ground distance. Positive value: distance known. Negative value: Unknown distance
* @param flow_rate_x [rad/s] Flow rate about X axis * @param flow_rate_x [rad/s] Flow rate about X axis
...@@ -354,7 +354,7 @@ static inline int16_t mavlink_msg_optical_flow_get_flow_y(const mavlink_message_ ...@@ -354,7 +354,7 @@ static inline int16_t mavlink_msg_optical_flow_get_flow_y(const mavlink_message_
/** /**
* @brief Get field flow_comp_m_x from optical_flow message * @brief Get field flow_comp_m_x from optical_flow message
* *
* @return [m] Flow in x-sensor direction, angular-speed compensated * @return [m/s] Flow in x-sensor direction, angular-speed compensated
*/ */
static inline float mavlink_msg_optical_flow_get_flow_comp_m_x(const mavlink_message_t* msg) static inline float mavlink_msg_optical_flow_get_flow_comp_m_x(const mavlink_message_t* msg)
{ {
...@@ -364,7 +364,7 @@ static inline float mavlink_msg_optical_flow_get_flow_comp_m_x(const mavlink_mes ...@@ -364,7 +364,7 @@ static inline float mavlink_msg_optical_flow_get_flow_comp_m_x(const mavlink_mes
/** /**
* @brief Get field flow_comp_m_y from optical_flow message * @brief Get field flow_comp_m_y from optical_flow message
* *
* @return [m] Flow in y-sensor direction, angular-speed compensated * @return [m/s] Flow in y-sensor direction, angular-speed compensated
*/ */
static inline float mavlink_msg_optical_flow_get_flow_comp_m_y(const mavlink_message_t* msg) static inline float mavlink_msg_optical_flow_get_flow_comp_m_y(const mavlink_message_t* msg)
{ {
......
...@@ -4498,8 +4498,8 @@ ...@@ -4498,8 +4498,8 @@
<field type="uint8_t" name="sensor_id">Sensor ID</field> <field type="uint8_t" name="sensor_id">Sensor ID</field>
<field type="int16_t" name="flow_x" units="dpix">Flow in x-sensor direction</field> <field type="int16_t" name="flow_x" units="dpix">Flow in x-sensor direction</field>
<field type="int16_t" name="flow_y" units="dpix">Flow in y-sensor direction</field> <field type="int16_t" name="flow_y" units="dpix">Flow in y-sensor direction</field>
<field type="float" name="flow_comp_m_x" units="m">Flow in x-sensor direction, angular-speed compensated</field> <field type="float" name="flow_comp_m_x" units="m/s">Flow in x-sensor direction, angular-speed compensated</field>
<field type="float" name="flow_comp_m_y" units="m">Flow in y-sensor direction, angular-speed compensated</field> <field type="float" name="flow_comp_m_y" units="m/s">Flow in y-sensor direction, angular-speed compensated</field>
<field type="uint8_t" name="quality">Optical flow quality / confidence. 0: bad, 255: maximum quality</field> <field type="uint8_t" name="quality">Optical flow quality / confidence. 0: bad, 255: maximum quality</field>
<field type="float" name="ground_distance" units="m">Ground distance. Positive value: distance known. Negative value: Unknown distance</field> <field type="float" name="ground_distance" units="m">Ground distance. Positive value: distance known. Negative value: Unknown distance</field>
<extensions/> <extensions/>
...@@ -5689,7 +5689,7 @@ ...@@ -5689,7 +5689,7 @@
<message id="385" name="TUNNEL"> <message id="385" name="TUNNEL">
<wip/> <wip/>
<!-- This message is work-in-progress it can therefore change, and should NOT be used in stable production environments --> <!-- This message is work-in-progress it can therefore change, and should NOT be used in stable production environments -->
<description>Message for transporting "arbitrary" variable-length data from one component to another (broadcast is not forbidden, but discouraged). The encoding of the data is usually extension specific, i.e. determined by the source, and is usually not documented as part of the mavlink specification.</description> <description>Message for transporting "arbitrary" variable-length data from one component to another (broadcast is not forbidden, but discouraged). The encoding of the data is usually extension specific, i.e. determined by the source, and is usually not documented as part of the MAVLink specification.</description>
<field type="uint8_t" name="target_system">System ID (can be 0 for broadcast, but this is discouraged)</field> <field type="uint8_t" name="target_system">System ID (can be 0 for broadcast, but this is discouraged)</field>
<field type="uint8_t" name="target_component">Component ID (can be 0 for broadcast, but this is discouraged)</field> <field type="uint8_t" name="target_component">Component ID (can be 0 for broadcast, but this is discouraged)</field>
<field type="uint16_t" name="payload_type" enum="MAV_TUNNEL_PAYLOAD_TYPE">A code that identifies the content of the payload (0 for unknown, which is the default). If this code is less than 32768, it is a 'registered' payload type and the corresponding code should be added to the MAV_TUNNEL_PAYLOAD_TYPE enum, and the entry possibly to https://github.com/mavlink/mavlink/tunnel-message-payload-types.xml. Software creators can register blocks of types as needed. Codes greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase.</field> <field type="uint16_t" name="payload_type" enum="MAV_TUNNEL_PAYLOAD_TYPE">A code that identifies the content of the payload (0 for unknown, which is the default). If this code is less than 32768, it is a 'registered' payload type and the corresponding code should be added to the MAV_TUNNEL_PAYLOAD_TYPE enum, and the entry possibly to https://github.com/mavlink/mavlink/tunnel-message-payload-types.xml. Software creators can register blocks of types as needed. Codes greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase.</field>
......
Markdown is supported
0%
or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment