32 #define debug(fmt, args ...) do {printf(fmt, ## args); } while(0) 36 #define PIXART_REG_PRODUCT_ID 0x00 37 #define PIXART_REG_REVISION_ID 0x01 38 #define PIXART_REG_MOTION 0x02 39 #define PIXART_REG_DELTA_X_L 0x03 40 #define PIXART_REG_DELTA_X_H 0x04 41 #define PIXART_REG_DELTA_Y_L 0x05 42 #define PIXART_REG_DELTA_Y_H 0x06 43 #define PIXART_REG_SQUAL 0x07 44 #define PIXART_REG_RAWDATA_SUM 0x08 45 #define PIXART_REG_RAWDATA_MAX 0x09 46 #define PIXART_REG_RAWDATA_MIN 0x0A 47 #define PIXART_REG_SHUTTER_LOW 0x0B 48 #define PIXART_REG_SHUTTER_HI 0x0C 49 #define PIXART_REG_CONFIG1 0x0F 50 #define PIXART_REG_CONFIG2 0x10 51 #define PIXART_REG_FRAME_CAP 0x12 52 #define PIXART_REG_SROM_EN 0x13 53 #define PIXART_REG_RUN_DS 0x14 54 #define PIXART_REG_REST1_RATE 0x15 55 #define PIXART_REG_REST1_DS 0x16 56 #define PIXART_REG_REST2_RATE 0x17 57 #define PIXART_REG_REST2_DS 0x18 58 #define PIXART_REG_REST3_RATE 0x19 59 #define PIXART_REG_OBS 0x24 60 #define PIXART_REG_DOUT_L 0x25 61 #define PIXART_REG_DOUT_H 0x26 62 #define PIXART_REG_RAW_GRAB 0x29 63 #define PIXART_REG_SROM_ID 0x2A 64 #define PIXART_REG_POWER_RST 0x3A 65 #define PIXART_REG_SHUTDOWN 0x3B 66 #define PIXART_REG_INV_PROD_ID 0x3F 67 #define PIXART_REG_INV_PROD_ID2 0x5F // for 3901 68 #define PIXART_REG_MOT_BURST 0x50 69 #define PIXART_REG_MOT_BURST2 0x16 70 #define PIXART_REG_SROM_BURST 0x62 71 #define PIXART_REG_RAW_BURST 0x64 74 #define PIXART_WRITE_FLAG 0x80 77 #define PIXART_Tsrad 300 80 #define PIXART_SROM_CRC_RESULT 0xBEEF 129 debug(
"id1=0x%02x id2=0x%02x ~id1=0x%02x\n", id1, id2, uint8_t(~id1));
130 if (id1 == 0x3F && id2 == uint8_t(~id1)) {
132 }
else if (id1 == 0x49 && id2 == uint8_t(~id1)) {
135 debug(
"Not a recognised device\n");
144 debug(
"Pixart: bad SROM ID: 0x%02x\n",
id);
153 debug(
"Pixart: bad SROM CRC: 0x%04x\n", crc);
213 return low | (high<<8);
232 debug(
"Failed to force CS\n");
245 debug(
"Failed to force CS off\n");
252 for (uint16_t i = 0; i < n; i++) {
254 for (uint8_t tries=0; tries<5; tries++) {
257 if (v == init_data[i].value) {
268 uint8_t *b = (uint8_t *)&
burst;
279 for (uint8_t i=0; i<
sizeof(
burst); i++) {
299 float dt = dt_us * 1.0e-6;
312 static uint32_t last_print_ms;
315 fd =
open(
"/dev/ttyACM0", O_WRONLY);
318 static int32_t sum_x;
319 static int32_t sum_y;
324 if (now - last_print_ms >= 100 && (sum_x != 0 || sum_y != 0)) {
326 dprintf(fd,
"Motion: %d %d obs:0x%02x squal:%u rds:%u maxr:%u minr:%u sup:%u slow:%u\n",
349 float flowScaleFactorX = 1.0f + 0.001f * flowScaler.
x;
350 float flowScaleFactorY = 1.0f + 0.001f * flowScaler.
y;
351 float dt =
integral.sum_us * 1.0e-6;
enum AP_OpticalFlow_Pixart::@159 model
Vector2< float > Vector2f
#define PIXART_REG_MOT_BURST
void _applyYaw(Vector2f &v)
#define debug(fmt, args ...)
AP_AHRS_NavEKF & get_ahrs(void)
const Vector3f & get_gyro(void) const override
#define PIXART_REG_INV_PROD_ID2
int open(const char *pathname, int flags)
POSIX Open a file with integer mode flags.
#define PIXART_REG_POWER_RST
AP_OpticalFlow_Pixart(const char *devname, OpticalFlow &_frontend)
constructor
Vector2f _flowScaler(void) const
#define PIXART_REG_SROM_BURST
virtual Device::PeriodicHandle register_periodic_callback(uint32_t period_usec, Device::PeriodicCb) override=0
void update(void) override
void load_configuration(const RegData *init_data, uint16_t n)
#define HAL_SEMAPHORE_BLOCK_FOREVER
struct PACKED AP_OpticalFlow_Pixart::MotionBurst burst
virtual bool take(uint32_t timeout_ms) WARN_IF_UNUSED=0
#define PIXART_REG_DOUT_L
#define PIXART_REG_PRODUCT_ID
uint16_t reg_read16u(uint8_t reg)
#define PIXART_REG_SROM_ID
void reg_write(uint8_t reg, uint8_t value)
virtual void delay(uint16_t ms)=0
#define PIXART_REG_INV_PROD_ID
virtual OwnPtr< SPIDevice > get_device(const char *name)
static const RegData init_data_3901_1[]
virtual Semaphore * get_semaphore() override=0
void _update_frontend(const struct OpticalFlow::OpticalFlow_state &state)
int16_t reg_read16s(uint8_t reg)
#define PIXART_WRITE_FLAG
virtual bool set_chip_select(bool set)
static const RegData init_data_3900[]
AP_HAL::SPIDeviceManager * spi
virtual bool transfer(const uint8_t *send, uint32_t send_len, uint8_t *recv, uint32_t recv_len) override=0
static const RegData init_data_3901_2[]
static AP_OpticalFlow_Pixart * detect(const char *devname, OpticalFlow &_frontend)
virtual void delay_microseconds(uint16_t us)=0
struct AP_OpticalFlow_Pixart::@160 integral
static const uint8_t srom_data[]
#define PIXART_REG_MOT_BURST2
uint8_t reg_read(uint8_t reg)
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
void panic(const char *errormsg,...) FMT_PRINTF(1
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
AP_HAL::OwnPtr< AP_HAL::SPIDevice > _dev
AP_HAL::Scheduler * scheduler
#define PIXART_REG_SROM_EN
const float flow_pixel_scaling
static const uint8_t srom_id