2016-11-18 05:56:05 -04:00
|
|
|
#pragma once
|
|
|
|
|
2021-12-23 20:05:30 -04:00
|
|
|
#include "AP_OpticalFlow.h"
|
2021-12-24 01:47:21 -04:00
|
|
|
|
|
|
|
#ifndef AP_OPTICALFLOW_PIXART_ENABLED
|
|
|
|
#define AP_OPTICALFLOW_PIXART_ENABLED AP_OPTICALFLOW_ENABLED
|
|
|
|
#endif
|
|
|
|
|
|
|
|
#if AP_OPTICALFLOW_PIXART_ENABLED
|
|
|
|
|
2016-11-18 05:56:05 -04:00
|
|
|
#include <AP_HAL/utility/OwnPtr.h>
|
|
|
|
|
|
|
|
class AP_OpticalFlow_Pixart : public OpticalFlow_backend
|
|
|
|
{
|
|
|
|
public:
|
|
|
|
/// constructor
|
2022-08-14 22:31:14 -03:00
|
|
|
AP_OpticalFlow_Pixart(const char *devname, AP_OpticalFlow &_frontend);
|
2016-11-18 05:56:05 -04:00
|
|
|
|
|
|
|
// init - initialise the sensor
|
|
|
|
void init() override {}
|
|
|
|
|
|
|
|
// update - read latest values from sensor and fill in x,y and totals.
|
|
|
|
void update(void) override;
|
|
|
|
|
|
|
|
// detect if the sensor is available
|
2022-08-14 22:31:14 -03:00
|
|
|
static AP_OpticalFlow_Pixart *detect(const char *devname, AP_OpticalFlow &_frontend);
|
2016-11-18 05:56:05 -04:00
|
|
|
|
|
|
|
private:
|
|
|
|
AP_HAL::OwnPtr<AP_HAL::SPIDevice> _dev;
|
|
|
|
|
2017-03-09 19:45:01 -04:00
|
|
|
enum {
|
|
|
|
PIXART_3900=0,
|
|
|
|
PIXART_3901=1
|
|
|
|
} model;
|
|
|
|
|
2016-11-18 05:56:05 -04:00
|
|
|
struct RegData {
|
|
|
|
uint8_t reg;
|
|
|
|
uint8_t value;
|
|
|
|
};
|
|
|
|
|
|
|
|
struct PACKED MotionBurst {
|
|
|
|
uint8_t motion;
|
|
|
|
uint8_t observation;
|
|
|
|
int16_t delta_x;
|
|
|
|
int16_t delta_y;
|
|
|
|
uint8_t squal;
|
|
|
|
uint8_t rawdata_sum;
|
|
|
|
uint8_t max_raw;
|
|
|
|
uint8_t min_raw;
|
|
|
|
uint8_t shutter_upper;
|
|
|
|
uint8_t shutter_lower;
|
|
|
|
} burst;
|
2016-11-19 05:04:03 -04:00
|
|
|
|
|
|
|
struct {
|
|
|
|
Vector2l sum;
|
|
|
|
uint32_t last_frame_us;
|
|
|
|
uint32_t sum_us;
|
|
|
|
Vector2f gyro;
|
|
|
|
} integral;
|
2016-11-18 05:56:05 -04:00
|
|
|
|
|
|
|
static const uint8_t srom_data[];
|
|
|
|
static const uint8_t srom_id;
|
2017-03-09 19:45:01 -04:00
|
|
|
static const RegData init_data_3900[];
|
|
|
|
static const RegData init_data_3901_1[];
|
|
|
|
static const RegData init_data_3901_2[];
|
2016-11-19 17:23:01 -04:00
|
|
|
const float flow_pixel_scaling = 1.26e-3;
|
2016-11-18 05:56:05 -04:00
|
|
|
|
|
|
|
// setup sensor
|
|
|
|
bool setup_sensor(void);
|
|
|
|
|
|
|
|
void reg_write(uint8_t reg, uint8_t value);
|
|
|
|
uint8_t reg_read(uint8_t reg);
|
|
|
|
int16_t reg_read16s(uint8_t reg);
|
|
|
|
uint16_t reg_read16u(uint8_t reg);
|
|
|
|
|
|
|
|
void srom_download(void);
|
2017-03-09 19:45:01 -04:00
|
|
|
void load_configuration(const RegData *init_data, uint16_t n);
|
2016-11-18 05:56:05 -04:00
|
|
|
|
2017-01-13 15:26:14 -04:00
|
|
|
void timer(void);
|
2016-11-18 05:56:05 -04:00
|
|
|
void motion_burst(void);
|
|
|
|
|
|
|
|
uint32_t last_burst_us;
|
2016-11-19 05:04:03 -04:00
|
|
|
uint32_t last_update_ms;
|
2016-11-18 05:56:05 -04:00
|
|
|
};
|
2021-12-24 01:47:21 -04:00
|
|
|
|
|
|
|
#endif // AP_OPTICALFLOW_PIXART_ENABLED
|