diff --git a/src/drivers/px4flow/i2c_frame.h b/src/drivers/px4flow/i2c_frame.h index ec8a5e1fda..2db240e35e 100644 --- a/src/drivers/px4flow/i2c_frame.h +++ b/src/drivers/px4flow/i2c_frame.h @@ -34,47 +34,48 @@ /** * @file i2c_frame.h * Definition of i2c frames. + * There are different I2C readouts available: i2c_frame and i2c_integral_frame. + * The ic2_frame can be requested via the register 0x0, the i2c_integral_frame via 0x16. + * * @author Thomas Boehm * @author James Goppert */ -#ifndef I2C_FRAME_H_ -#define I2C_FRAME_H_ +#pragma once #include typedef struct i2c_frame { - uint16_t frame_count; - int16_t pixel_flow_x_sum; - int16_t pixel_flow_y_sum; - int16_t flow_comp_m_x; - int16_t flow_comp_m_y; - int16_t qual; - int16_t gyro_x_rate; - int16_t gyro_y_rate; - int16_t gyro_z_rate; - uint8_t gyro_range; - uint8_t sonar_timestamp; - int16_t ground_distance; + uint16_t frame_count; /**< counts created I2C frames [#frames] */ + int16_t pixel_flow_x_sum; /**< latest x flow measurement in pixels*10 [pixels] */ + int16_t pixel_flow_y_sum; /**< latest y flow measurement in pixels*10 [pixels] */ + int16_t flow_comp_m_x; /**< x velocity*1000 [meters/sec] */ + int16_t flow_comp_m_y; /**< y velocity*1000 [meters/sec] */ + int16_t qual; /**< Optical flow quality / confidence [0: bad, 255: maximum quality] */ + int16_t gyro_x_rate; /**< latest gyro x rate [rad/sec] */ + int16_t gyro_y_rate; /**< latest gyro y rate [rad/sec] */ + int16_t gyro_z_rate; /**< latest gyro z rate [rad/sec] */ + uint8_t gyro_range; /**< gyro range [0 .. 7] equals [50 deg/sec .. 2000 deg/sec] */ + uint8_t sonar_timestamp; /**< time since last sonar update [milliseconds] */ + int16_t ground_distance; /**< Ground distance in meters*1000 [meters]. Positive value: distance known. Negative value: Unknown distance */ } i2c_frame; #define I2C_FRAME_SIZE (sizeof(i2c_frame)) typedef struct i2c_integral_frame { - uint16_t frame_count_since_last_readout; - int16_t pixel_flow_x_integral; - int16_t pixel_flow_y_integral; - int16_t gyro_x_rate_integral; - int16_t gyro_y_rate_integral; - int16_t gyro_z_rate_integral; - uint32_t integration_timespan; - uint32_t sonar_timestamp; - uint16_t ground_distance; - int16_t gyro_temperature; - uint8_t qual; + uint16_t frame_count_since_last_readout; /**< number of flow measurements since last I2C readout [#frames] */ + int16_t pixel_flow_x_integral; /**< accumulated flow in radians*10000 around x axis since last I2C readout [rad*10000] */ + int16_t pixel_flow_y_integral; /**< accumulated flow in radians*10000 around y axis since last I2C readout [rad*10000] */ + int16_t gyro_x_rate_integral; /**< accumulated gyro x rates in radians*10000 since last I2C readout [rad*10000] */ + int16_t gyro_y_rate_integral; /**< accumulated gyro y rates in radians*10000 since last I2C readout [rad*10000] */ + int16_t gyro_z_rate_integral; /**< accumulated gyro z rates in radians*10000 since last I2C readout [rad*10000] */ + uint32_t integration_timespan; /**< accumulation timespan in microseconds since last I2C readout [microseconds] */ + uint32_t sonar_timestamp; /**< time since last sonar update [microseconds] */ + uint16_t ground_distance; /**< Ground distance in meters*1000 [meters*1000] */ + int16_t gyro_temperature; /**< Temperature * 100 in centi-degrees Celsius [degcelsius*100] */ + uint8_t qual; /**< averaged quality of accumulated flow values [0:bad quality;255: max quality] */ } i2c_integral_frame; #define I2C_INTEGRAL_FRAME_SIZE (sizeof(i2c_integral_frame)) -#endif /* I2C_FRAME_H_ */