123456789101112131415161718192021222324252627282930313233 |
- #pragma once
- class AP_HAL::OpticalFlow {
- public:
- class Data_Frame {
- public:
- float pixel_flow_x_integral;
- float pixel_flow_y_integral;
- float gyro_x_integral;
- float gyro_y_integral;
- uint32_t delta_time;
- uint8_t quality;
- };
- virtual void init() = 0;
- virtual bool read(Data_Frame& frame) = 0;
- virtual void push_gyro(float gyro_x, float gyro_y, float dt) = 0;
- virtual void push_gyro_bias(float gyro_bias_x, float gyro_bias_y) = 0;
- };
|