30 #define PX4FLOW_BASE_I2C_ADDR 0x42 31 #define PX4FLOW_INIT_RETRIES 10 // attempt to initialise the sensor up to 10 times at startup 60 uint8_t retry_attempt = 0;
63 for (uint8_t bus = 0; bus < 3; bus++) {
64 #ifdef HAL_OPTFLOW_PX4FLOW_I2C_BUS 81 printf(
"Found PX4Flow on bus %u\n", bus);
82 dev = std::move(tdev);
121 if (frame.integration_timespan > 0) {
123 float flowScaleFactorX = 1.0f + 0.001f * flowScaler.
x;
124 float flowScaleFactorY = 1.0f + 0.001f * flowScaler.
y;
125 float integralToRate = 1.0e6 / frame.integration_timespan;
129 frame.pixel_flow_y_integral * flowScaleFactorY) * 1.0e-4 * integralToRate;
130 state.
bodyRate =
Vector2f(frame.gyro_x_rate_integral, frame.gyro_y_rate_integral) * 1.0e-4 * integralToRate;
int printf(const char *fmt,...)
static const uint8_t REG_INTEGRAL_FRAME
Vector2< float > Vector2f
#define PX4FLOW_BASE_I2C_ADDR
void _applyYaw(Vector2f &v)
uint8_t get_address(void) const
virtual PeriodicHandle register_periodic_callback(uint32_t period_usec, PeriodicCb)=0
Vector2f _flowScaler(void) const
virtual AP_HAL::Semaphore * get_semaphore()=0
#define HAL_SEMAPHORE_BLOCK_FOREVER
virtual bool take(uint32_t timeout_ms) WARN_IF_UNUSED=0
static AP_OpticalFlow_PX4Flow * detect(OpticalFlow &_frontend)
AP_OpticalFlow_PX4Flow(OpticalFlow &_frontend)
constructor
virtual void delay(uint16_t ms)=0
#define HAL_OPTFLOW_PX4FLOW_I2C_BUS
void _update_frontend(const struct OpticalFlow::OpticalFlow_state &state)
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
AP_HAL::I2CDeviceManager * i2c_mgr
bool read_registers(uint8_t first_reg, uint8_t *recv, uint32_t recv_len)
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
virtual OwnPtr< AP_HAL::I2CDevice > get_device(uint8_t bus, uint8_t address, uint32_t bus_clock=400000, bool use_smbus=false, uint32_t timeout_ms=4)=0
void update(void) override
AP_HAL::OwnPtr< AP_HAL::Device > dev
#define PX4FLOW_INIT_RETRIES
AP_HAL::Scheduler * scheduler