From 74083d6bd1197438f626d0c97d0707ab056ea19f Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Wed, 16 Dec 2020 20:04:46 -0500 Subject: [PATCH] optical_flow/paw3902: minor improvements - verify register writes - cleanly reset on lighting mode changes as per the datasheet - perf counters for mode switches and other errors - cleanly reset on false motion detection - minimize sleep on reset - allowing setting custom rotation yaw angle directly on command line with -Y (ignoring SENS_FLOW_ROT) - enable LED output --- src/drivers/optical_flow/paw3902/PAW3902.cpp | 893 ++++++++++-------- src/drivers/optical_flow/paw3902/PAW3902.hpp | 59 +- .../paw3902/PixArt_PAW3902JF_Registers.hpp | 42 +- .../optical_flow/paw3902/paw3902_main.cpp | 26 +- 4 files changed, 538 insertions(+), 482 deletions(-) diff --git a/src/drivers/optical_flow/paw3902/PAW3902.cpp b/src/drivers/optical_flow/paw3902/PAW3902.cpp index 0a299e0bdf..faf34ab645 100644 --- a/src/drivers/optical_flow/paw3902/PAW3902.cpp +++ b/src/drivers/optical_flow/paw3902/PAW3902.cpp @@ -1,6 +1,6 @@ /**************************************************************************** * - * Copyright (c) 2019 PX4 Development Team. All rights reserved. + * Copyright (c) 2019-2020 PX4 Development Team. All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -33,126 +33,142 @@ #include "PAW3902.hpp" -PAW3902::PAW3902(I2CSPIBusOption bus_option, int bus, int devid, enum Rotation yaw_rotation, int bus_frequency, - spi_mode_e spi_mode) : +PAW3902::PAW3902(I2CSPIBusOption bus_option, int bus, int devid, int bus_frequency, spi_mode_e spi_mode, + float yaw_rotation_degrees) : SPI(DRV_FLOW_DEVTYPE_PAW3902, MODULE_NAME, bus, devid, spi_mode, bus_frequency), - I2CSPIDriver(MODULE_NAME, px4::device_bus_to_wq(get_device_id()), bus_option, bus), - _sample_perf(perf_alloc(PC_ELAPSED, MODULE_NAME": read")), - _comms_errors(perf_alloc(PC_COUNT, MODULE_NAME": com_err")), - _dupe_count_perf(perf_alloc(PC_COUNT, MODULE_NAME": duplicate reading")), - _yaw_rotation(yaw_rotation) + I2CSPIDriver(MODULE_NAME, px4::device_bus_to_wq(get_device_id()), bus_option, bus) { + if (PX4_ISFINITE(yaw_rotation_degrees)) { + PX4_INFO("using yaw rotation %.3f degrees (%.3f radians)", + (double)yaw_rotation_degrees, (double)math::radians(yaw_rotation_degrees)); + + _rotation = matrix::Dcmf{matrix::Eulerf{0.f, 0.f, math::radians(yaw_rotation_degrees)}}; + + } else { + // otherwise use the parameter SENS_FLOW_ROT + param_t rot = param_find("SENS_FLOW_ROT"); + int32_t val = 0; + + if (param_get(rot, &val) == PX4_OK) { + _rotation = get_rot_matrix((enum Rotation)val); + + } else { + _rotation.identity(); + } + } } PAW3902::~PAW3902() { // free perf counters perf_free(_sample_perf); + perf_free(_interval_perf); perf_free(_comms_errors); - perf_free(_dupe_count_perf); + perf_free(_false_motion_perf); + perf_free(_mode_change_perf); + perf_free(_register_write_fail_perf); } -int -PAW3902::init() +int PAW3902::init() { - // get yaw rotation from sensor frame to body frame - param_t rot = param_find("SENS_FLOW_ROT"); - - if (rot != PARAM_INVALID) { - int32_t val = 0; - - if (param_get(rot, &val) == PX4_OK) { - _yaw_rotation = (enum Rotation)val; - } - } - - /* For devices competing with NuttX SPI drivers on a bus (Crazyflie SD Card expansion board) */ - SPI::set_lockmode(LOCK_THREADS); - /* do SPI init (and probe) first */ if (SPI::init() != OK) { return PX4_ERROR; } - reset(); + Reset(); // default to low light mode (1) - modeLowLight(); + ModeLowLight(); _previous_collect_timestamp = hrt_absolute_time(); - start(); + // schedule a cycle to start things + ScheduleOnInterval(SAMPLE_INTERVAL_MODE_1, SAMPLE_INTERVAL_MODE_1); return PX4_OK; } -int -PAW3902::probe() +int PAW3902::probe() { - uint8_t product_id = registerRead(Register::Product_ID); + const uint8_t Product_ID = RegisterRead(Register::Product_ID); - PX4_DEBUG("DEVICE_ID: %X", product_id); - - // Test the SPI communication, checking chipId and inverse chipId - if (product_id != PRODUCT_ID) { + if (Product_ID != PRODUCT_ID) { + PX4_ERR("Product_ID: %X", Product_ID); return PX4_ERROR; } - uint8_t revision_id = registerRead(Register::Revision_ID); - PX4_DEBUG("REVISION_ID: %X", revision_id); + const uint8_t Revision_ID = RegisterRead(Register::Revision_ID); - if (revision_id != REVISION_ID) { + if (Revision_ID != REVISION_ID) { + PX4_ERR("Revision_ID: %X", Revision_ID); + return PX4_ERROR; + } + + const uint8_t Inverse_Product_ID = RegisterRead(Register::Inverse_Product_ID); + + if (Inverse_Product_ID != PRODUCT_ID_INVERSE) { + PX4_ERR("Inverse_Product_ID: %X", Inverse_Product_ID); return PX4_ERROR; } return PX4_OK; } -bool -PAW3902::reset() +bool PAW3902::Reset() { // Power on reset - registerWrite(Register::Power_Up_Reset, 0x5A); - usleep(5000); + RegisterWrite(Register::Power_Up_Reset, 0x5A); + usleep(1000); // Read from registers 0x02, 0x03, 0x04, 0x05 and 0x06 one time regardless of the motion state - registerRead(Register::Motion); - registerRead(Register::Delta_X_L); - registerRead(Register::Delta_X_H); - registerRead(Register::Delta_Y_L); - registerRead(Register::Delta_Y_H); - - usleep(1000); + RegisterRead(Register::Motion); + RegisterRead(Register::Delta_X_L); + RegisterRead(Register::Delta_X_H); + RegisterRead(Register::Delta_Y_L); + RegisterRead(Register::Delta_Y_H); return true; } -bool -PAW3902::changeMode(Mode newMode) +bool PAW3902::ChangeMode(Mode newMode) { if (newMode != _mode) { PX4_DEBUG("changing from mode %d -> %d", static_cast(_mode), static_cast(newMode)); ScheduleClear(); - reset(); + + // Issue a soft reset + RegisterWrite(Register::Power_Up_Reset, 0x5A); switch (newMode) { case Mode::Bright: - modeBright(); + ModeBright(); ScheduleOnInterval(SAMPLE_INTERVAL_MODE_0); break; case Mode::LowLight: - modeLowLight(); + ModeLowLight(); ScheduleOnInterval(SAMPLE_INTERVAL_MODE_1); break; case Mode::SuperLowLight: - modeSuperLowLight(); + ModeSuperLowLight(); ScheduleOnInterval(SAMPLE_INTERVAL_MODE_2); break; } + // Discard the first three motion data. + for (int i = 0; i < 3; i++) { + RegisterRead(Register::Motion); + RegisterRead(Register::Delta_X_L); + RegisterRead(Register::Delta_X_H); + RegisterRead(Register::Delta_Y_L); + RegisterRead(Register::Delta_Y_H); + } + _mode = newMode; + + perf_count(_mode_change_perf); } _bright_to_low_counter = 0; @@ -161,390 +177,425 @@ PAW3902::changeMode(Mode newMode) _superlow_to_low_counter = 0; // Approximate Resolution = (Register Value + 1) * (50 / 8450) ≈ 0.6% of data point in Figure 19 // The maximum register value is 0xA8. The minimum register value is 0. - uint8_t resolution = registerRead(Register::Resolution); + uint8_t resolution = RegisterRead(Register::Resolution); PX4_DEBUG("Resolution: %X", resolution); PX4_DEBUG("Resolution is approx: %.3f", (double)((resolution + 1.0f) * (50.0f / 8450.0f))); return true; } -bool -PAW3902::modeBright() +bool PAW3902::ModeBright() { // Mode 0: Bright (126 fps) 60 Lux typical // set performance optimization registers - registerWrite(0x7F, 0x00); - registerWrite(0x55, 0x01); - registerWrite(0x50, 0x07); - registerWrite(0x7f, 0x0e); - registerWrite(0x43, 0x10); + RegisterWriteVerified(0x7F, 0x00); + RegisterWriteVerified(0x55, 0x01); + RegisterWriteVerified(0x50, 0x07); + RegisterWriteVerified(0x7f, 0x0e); + RegisterWriteVerified(0x43, 0x10); - registerWrite(0x48, 0x02); - registerWrite(0x7F, 0x00); - registerWrite(0x51, 0x7b); - registerWrite(0x50, 0x00); - registerWrite(0x55, 0x00); + RegisterWriteVerified(0x48, 0x02); + RegisterWriteVerified(0x7F, 0x00); + RegisterWriteVerified(0x51, 0x7b); + RegisterWriteVerified(0x50, 0x00); + RegisterWriteVerified(0x55, 0x00); - registerWrite(0x7F, 0x00); - registerWrite(0x61, 0xAD); - registerWrite(0x7F, 0x03); - registerWrite(0x40, 0x00); - registerWrite(0x7F, 0x05); - registerWrite(0x41, 0xB3); - registerWrite(0x43, 0xF1); - registerWrite(0x45, 0x14); - registerWrite(0x5F, 0x34); - registerWrite(0x7B, 0x08); - registerWrite(0x5e, 0x34); - registerWrite(0x5b, 0x32); - registerWrite(0x6d, 0x32); - registerWrite(0x45, 0x17); - registerWrite(0x70, 0xe5); - registerWrite(0x71, 0xe5); - registerWrite(0x7F, 0x06); - registerWrite(0x44, 0x1B); - registerWrite(0x40, 0xBF); - registerWrite(0x4E, 0x3F); - registerWrite(0x7F, 0x08); - registerWrite(0x66, 0x44); - registerWrite(0x65, 0x20); - registerWrite(0x6a, 0x3a); - registerWrite(0x61, 0x05); - registerWrite(0x62, 0x05); - registerWrite(0x7F, 0x09); - registerWrite(0x4F, 0xAF); - registerWrite(0x48, 0x80); - registerWrite(0x49, 0x80); - registerWrite(0x57, 0x77); - registerWrite(0x5F, 0x40); - registerWrite(0x60, 0x78); - registerWrite(0x61, 0x78); - registerWrite(0x62, 0x08); - registerWrite(0x63, 0x50); - registerWrite(0x7F, 0x0A); - registerWrite(0x45, 0x60); - registerWrite(0x7F, 0x00); - registerWrite(0x4D, 0x11); - registerWrite(0x55, 0x80); - registerWrite(0x74, 0x21); - registerWrite(0x75, 0x1F); - registerWrite(0x4A, 0x78); - registerWrite(0x4B, 0x78); - registerWrite(0x44, 0x08); - registerWrite(0x45, 0x50); - registerWrite(0x64, 0xFE); - registerWrite(0x65, 0x1F); - registerWrite(0x72, 0x0A); - registerWrite(0x73, 0x00); - registerWrite(0x7F, 0x14); - registerWrite(0x44, 0x84); - registerWrite(0x65, 0x47); - registerWrite(0x66, 0x18); - registerWrite(0x63, 0x70); - registerWrite(0x6f, 0x2c); - registerWrite(0x7F, 0x15); - registerWrite(0x48, 0x48); - registerWrite(0x7F, 0x07); - registerWrite(0x41, 0x0D); - registerWrite(0x43, 0x14); - registerWrite(0x4B, 0x0E); - registerWrite(0x45, 0x0F); - registerWrite(0x44, 0x42); - registerWrite(0x4C, 0x80); - registerWrite(0x7F, 0x10); - registerWrite(0x5B, 0x03); - registerWrite(0x7F, 0x07); - registerWrite(0x40, 0x41); + RegisterWriteVerified(0x7F, 0x00); + RegisterWriteVerified(0x61, 0xAD); + RegisterWriteVerified(0x7F, 0x03); + RegisterWriteVerified(0x40, 0x00); + RegisterWriteVerified(0x7F, 0x05); + RegisterWriteVerified(0x41, 0xB3); + RegisterWriteVerified(0x43, 0xF1); + RegisterWriteVerified(0x45, 0x14); + RegisterWriteVerified(0x5F, 0x34); + RegisterWriteVerified(0x7B, 0x08); + RegisterWriteVerified(0x5e, 0x34); + RegisterWriteVerified(0x5b, 0x32); + RegisterWriteVerified(0x6d, 0x32); + RegisterWriteVerified(0x45, 0x17); + RegisterWriteVerified(0x70, 0xe5); + RegisterWriteVerified(0x71, 0xe5); + RegisterWriteVerified(0x7F, 0x06); + RegisterWriteVerified(0x44, 0x1B); + RegisterWriteVerified(0x40, 0xBF); + RegisterWriteVerified(0x4E, 0x3F); + RegisterWriteVerified(0x7F, 0x08); + RegisterWriteVerified(0x66, 0x44); + RegisterWriteVerified(0x65, 0x20); + RegisterWriteVerified(0x6a, 0x3a); + RegisterWriteVerified(0x61, 0x05); + RegisterWriteVerified(0x62, 0x05); + RegisterWriteVerified(0x7F, 0x09); + RegisterWriteVerified(0x4F, 0xAF); + RegisterWriteVerified(0x48, 0x80); + RegisterWriteVerified(0x49, 0x80); + RegisterWriteVerified(0x57, 0x77); + RegisterWriteVerified(0x5F, 0x40); + RegisterWriteVerified(0x60, 0x78); + RegisterWriteVerified(0x61, 0x78); + RegisterWriteVerified(0x62, 0x08); + RegisterWriteVerified(0x63, 0x50); + RegisterWriteVerified(0x7F, 0x0A); + RegisterWriteVerified(0x45, 0x60); + RegisterWriteVerified(0x7F, 0x00); + RegisterWriteVerified(0x4D, 0x11); + RegisterWriteVerified(0x55, 0x80); + RegisterWriteVerified(0x74, 0x21); + RegisterWriteVerified(0x75, 0x1F); + RegisterWriteVerified(0x4A, 0x78); + RegisterWriteVerified(0x4B, 0x78); + RegisterWriteVerified(0x44, 0x08); + RegisterWriteVerified(0x45, 0x50); + RegisterWriteVerified(0x64, 0xFE); + RegisterWriteVerified(0x65, 0x1F); + RegisterWriteVerified(0x72, 0x0A); + RegisterWriteVerified(0x73, 0x00); + RegisterWriteVerified(0x7F, 0x14); + RegisterWriteVerified(0x44, 0x84); + RegisterWriteVerified(0x65, 0x47); + RegisterWriteVerified(0x66, 0x18); + RegisterWriteVerified(0x63, 0x70); + RegisterWriteVerified(0x6f, 0x2c); + RegisterWriteVerified(0x7F, 0x15); + RegisterWriteVerified(0x48, 0x48); + RegisterWriteVerified(0x7F, 0x07); + RegisterWriteVerified(0x41, 0x0D); + RegisterWriteVerified(0x43, 0x14); + RegisterWriteVerified(0x4B, 0x0E); + RegisterWriteVerified(0x45, 0x0F); + RegisterWriteVerified(0x44, 0x42); + RegisterWriteVerified(0x4C, 0x80); + RegisterWriteVerified(0x7F, 0x10); + RegisterWriteVerified(0x5B, 0x03); + RegisterWriteVerified(0x7F, 0x07); + RegisterWriteVerified(0x40, 0x41); usleep(10_ms); // delay 10ms - registerWrite(0x7F, 0x00); - registerWrite(0x32, 0x00); - registerWrite(0x7F, 0x07); - registerWrite(0x40, 0x40); - registerWrite(0x7F, 0x06); - registerWrite(0x68, 0x70); - registerWrite(0x69, 0x01); - registerWrite(0x7F, 0x0D); - registerWrite(0x48, 0xC0); - registerWrite(0x6F, 0xD5); - registerWrite(0x7F, 0x00); - registerWrite(0x5B, 0xA0); - registerWrite(0x4E, 0xA8); - registerWrite(0x5A, 0x50); - registerWrite(0x40, 0x80); - registerWrite(0x73, 0x1f); + RegisterWriteVerified(0x7F, 0x00); + RegisterWriteVerified(0x32, 0x00); + RegisterWriteVerified(0x7F, 0x07); + RegisterWriteVerified(0x40, 0x40); + RegisterWriteVerified(0x7F, 0x06); + RegisterWriteVerified(0x68, 0x70); + RegisterWriteVerified(0x69, 0x01); + RegisterWriteVerified(0x7F, 0x0D); + RegisterWriteVerified(0x48, 0xC0); + RegisterWriteVerified(0x6F, 0xD5); + RegisterWriteVerified(0x7F, 0x00); + RegisterWriteVerified(0x5B, 0xA0); + RegisterWriteVerified(0x4E, 0xA8); + RegisterWriteVerified(0x5A, 0x50); + RegisterWriteVerified(0x40, 0x80); + RegisterWriteVerified(0x73, 0x1f); usleep(10_ms); // delay 10ms - registerWrite(0x73, 0x00); + RegisterWriteVerified(0x73, 0x00); - return false; + // Enable LED_N controls + RegisterWriteVerified(0x7F, 0x14); + RegisterWriteVerified(0x6F, 0x1c); + RegisterWriteVerified(0x7F, 0x00); + + return true; } -bool -PAW3902::modeLowLight() +bool PAW3902::ModeLowLight() { // Mode 1: Low Light (126 fps) 30 Lux typical // low light and low speed motion tracking // set performance optimization registers - registerWrite(0x7F, 0x00); - registerWrite(0x55, 0x01); - registerWrite(0x50, 0x07); - registerWrite(0x7f, 0x0e); - registerWrite(0x43, 0x10); + RegisterWriteVerified(0x7F, 0x00); + RegisterWriteVerified(0x55, 0x01); + RegisterWriteVerified(0x50, 0x07); + RegisterWriteVerified(0x7f, 0x0e); + RegisterWriteVerified(0x43, 0x10); - registerWrite(0x48, 0x02); - registerWrite(0x7F, 0x00); - registerWrite(0x51, 0x7b); - registerWrite(0x50, 0x00); - registerWrite(0x55, 0x00); + RegisterWriteVerified(0x48, 0x02); + RegisterWriteVerified(0x7F, 0x00); + RegisterWriteVerified(0x51, 0x7b); + RegisterWriteVerified(0x50, 0x00); + RegisterWriteVerified(0x55, 0x00); - registerWrite(0x7F, 0x00); - registerWrite(0x61, 0xAD); - registerWrite(0x7F, 0x03); - registerWrite(0x40, 0x00); - registerWrite(0x7F, 0x05); - registerWrite(0x41, 0xB3); - registerWrite(0x43, 0xF1); - registerWrite(0x45, 0x14); - registerWrite(0x5F, 0x34); - registerWrite(0x7B, 0x08); - registerWrite(0x5e, 0x34); - registerWrite(0x5b, 0x65); - registerWrite(0x6d, 0x65); - registerWrite(0x45, 0x17); - registerWrite(0x70, 0xe5); - registerWrite(0x71, 0xe5); - registerWrite(0x7F, 0x06); - registerWrite(0x44, 0x1B); - registerWrite(0x40, 0xBF); - registerWrite(0x4E, 0x3F); - registerWrite(0x7F, 0x08); - registerWrite(0x66, 0x44); - registerWrite(0x65, 0x20); - registerWrite(0x6a, 0x3a); - registerWrite(0x61, 0x05); - registerWrite(0x62, 0x05); - registerWrite(0x7F, 0x09); - registerWrite(0x4F, 0xAF); - registerWrite(0x48, 0x80); - registerWrite(0x49, 0x80); - registerWrite(0x57, 0x77); - registerWrite(0x5F, 0x40); - registerWrite(0x60, 0x78); - registerWrite(0x61, 0x78); - registerWrite(0x62, 0x08); - registerWrite(0x63, 0x50); - registerWrite(0x7F, 0x0A); - registerWrite(0x45, 0x60); - registerWrite(0x7F, 0x00); - registerWrite(0x4D, 0x11); - registerWrite(0x55, 0x80); - registerWrite(0x74, 0x21); - registerWrite(0x75, 0x1F); - registerWrite(0x4A, 0x78); - registerWrite(0x4B, 0x78); - registerWrite(0x44, 0x08); - registerWrite(0x45, 0x50); - registerWrite(0x64, 0xFE); - registerWrite(0x65, 0x1F); - registerWrite(0x72, 0x0A); - registerWrite(0x73, 0x00); - registerWrite(0x7F, 0x14); - registerWrite(0x44, 0x84); - registerWrite(0x65, 0x67); - registerWrite(0x66, 0x18); - registerWrite(0x63, 0x70); - registerWrite(0x6f, 0x2c); - registerWrite(0x7F, 0x15); - registerWrite(0x48, 0x48); - registerWrite(0x7F, 0x07); - registerWrite(0x41, 0x0D); - registerWrite(0x43, 0x14); - registerWrite(0x4B, 0x0E); - registerWrite(0x45, 0x0F); - registerWrite(0x44, 0x42); - registerWrite(0x4C, 0x80); - registerWrite(0x7F, 0x10); - registerWrite(0x5B, 0x03); - registerWrite(0x7F, 0x07); - registerWrite(0x40, 0x41); + RegisterWriteVerified(0x7F, 0x00); + RegisterWriteVerified(0x61, 0xAD); + RegisterWriteVerified(0x7F, 0x03); + RegisterWriteVerified(0x40, 0x00); + RegisterWriteVerified(0x7F, 0x05); + RegisterWriteVerified(0x41, 0xB3); + RegisterWriteVerified(0x43, 0xF1); + RegisterWriteVerified(0x45, 0x14); + RegisterWriteVerified(0x5F, 0x34); + RegisterWriteVerified(0x7B, 0x08); + RegisterWriteVerified(0x5e, 0x34); + RegisterWriteVerified(0x5b, 0x65); + RegisterWriteVerified(0x6d, 0x65); + RegisterWriteVerified(0x45, 0x17); + RegisterWriteVerified(0x70, 0xe5); + RegisterWriteVerified(0x71, 0xe5); + RegisterWriteVerified(0x7F, 0x06); + RegisterWriteVerified(0x44, 0x1B); + RegisterWriteVerified(0x40, 0xBF); + RegisterWriteVerified(0x4E, 0x3F); + RegisterWriteVerified(0x7F, 0x08); + RegisterWriteVerified(0x66, 0x44); + RegisterWriteVerified(0x65, 0x20); + RegisterWriteVerified(0x6a, 0x3a); + RegisterWriteVerified(0x61, 0x05); + RegisterWriteVerified(0x62, 0x05); + RegisterWriteVerified(0x7F, 0x09); + RegisterWriteVerified(0x4F, 0xAF); + RegisterWriteVerified(0x48, 0x80); + RegisterWriteVerified(0x49, 0x80); + RegisterWriteVerified(0x57, 0x77); + RegisterWriteVerified(0x5F, 0x40); + RegisterWriteVerified(0x60, 0x78); + RegisterWriteVerified(0x61, 0x78); + RegisterWriteVerified(0x62, 0x08); + RegisterWriteVerified(0x63, 0x50); + RegisterWriteVerified(0x7F, 0x0A); + RegisterWriteVerified(0x45, 0x60); + RegisterWriteVerified(0x7F, 0x00); + RegisterWriteVerified(0x4D, 0x11); + RegisterWriteVerified(0x55, 0x80); + RegisterWriteVerified(0x74, 0x21); + RegisterWriteVerified(0x75, 0x1F); + RegisterWriteVerified(0x4A, 0x78); + RegisterWriteVerified(0x4B, 0x78); + RegisterWriteVerified(0x44, 0x08); + RegisterWriteVerified(0x45, 0x50); + RegisterWriteVerified(0x64, 0xFE); + RegisterWriteVerified(0x65, 0x1F); + RegisterWriteVerified(0x72, 0x0A); + RegisterWriteVerified(0x73, 0x00); + RegisterWriteVerified(0x7F, 0x14); + RegisterWriteVerified(0x44, 0x84); + RegisterWriteVerified(0x65, 0x67); + RegisterWriteVerified(0x66, 0x18); + RegisterWriteVerified(0x63, 0x70); + RegisterWriteVerified(0x6f, 0x2c); + RegisterWriteVerified(0x7F, 0x15); + RegisterWriteVerified(0x48, 0x48); + RegisterWriteVerified(0x7F, 0x07); + RegisterWriteVerified(0x41, 0x0D); + RegisterWriteVerified(0x43, 0x14); + RegisterWriteVerified(0x4B, 0x0E); + RegisterWriteVerified(0x45, 0x0F); + RegisterWriteVerified(0x44, 0x42); + RegisterWriteVerified(0x4C, 0x80); + RegisterWriteVerified(0x7F, 0x10); + RegisterWriteVerified(0x5B, 0x03); + RegisterWriteVerified(0x7F, 0x07); + RegisterWriteVerified(0x40, 0x41); usleep(10_ms); // delay 10ms - registerWrite(0x7F, 0x00); - registerWrite(0x32, 0x00); - registerWrite(0x7F, 0x07); - registerWrite(0x40, 0x40); - registerWrite(0x7F, 0x06); - registerWrite(0x68, 0x70); - registerWrite(0x69, 0x01); - registerWrite(0x7F, 0x0D); - registerWrite(0x48, 0xC0); - registerWrite(0x6F, 0xD5); - registerWrite(0x7F, 0x00); - registerWrite(0x5B, 0xA0); - registerWrite(0x4E, 0xA8); - registerWrite(0x5A, 0x50); - registerWrite(0x40, 0x80); - registerWrite(0x73, 0x1f); + RegisterWriteVerified(0x7F, 0x00); + RegisterWriteVerified(0x32, 0x00); + RegisterWriteVerified(0x7F, 0x07); + RegisterWriteVerified(0x40, 0x40); + RegisterWriteVerified(0x7F, 0x06); + RegisterWriteVerified(0x68, 0x70); + RegisterWriteVerified(0x69, 0x01); + RegisterWriteVerified(0x7F, 0x0D); + RegisterWriteVerified(0x48, 0xC0); + RegisterWriteVerified(0x6F, 0xD5); + RegisterWriteVerified(0x7F, 0x00); + RegisterWriteVerified(0x5B, 0xA0); + RegisterWriteVerified(0x4E, 0xA8); + RegisterWriteVerified(0x5A, 0x50); + RegisterWriteVerified(0x40, 0x80); + RegisterWriteVerified(0x73, 0x1f); usleep(10_ms); // delay 10ms - registerWrite(0x73, 0x00); + RegisterWriteVerified(0x73, 0x00); - return false; + // Enable LED_N controls + RegisterWriteVerified(0x7F, 0x14); + RegisterWriteVerified(0x6F, 0x1c); + RegisterWriteVerified(0x7F, 0x00); + + return true; } -bool -PAW3902::modeSuperLowLight() +bool PAW3902::ModeSuperLowLight() { // Mode 2: Super Low Light (50 fps) 9 Lux typical // super low light and low speed motion tracking // set performance optimization registers - registerWrite(0x7F, 0x00); - registerWrite(0x55, 0x01); - registerWrite(0x50, 0x07); - registerWrite(0x7f, 0x0e); - registerWrite(0x43, 0x10); + RegisterWriteVerified(0x7F, 0x00); + RegisterWriteVerified(0x55, 0x01); + RegisterWriteVerified(0x50, 0x07); + RegisterWriteVerified(0x7f, 0x0e); + RegisterWriteVerified(0x43, 0x10); - registerWrite(0x48, 0x04); - registerWrite(0x7F, 0x00); - registerWrite(0x51, 0x7b); - registerWrite(0x50, 0x00); - registerWrite(0x55, 0x00); + RegisterWriteVerified(0x48, 0x04); + RegisterWriteVerified(0x7F, 0x00); + RegisterWriteVerified(0x51, 0x7b); + RegisterWriteVerified(0x50, 0x00); + RegisterWriteVerified(0x55, 0x00); - registerWrite(0x7F, 0x00); - registerWrite(0x61, 0xAD); - registerWrite(0x7F, 0x03); - registerWrite(0x40, 0x00); - registerWrite(0x7F, 0x05); - registerWrite(0x41, 0xB3); - registerWrite(0x43, 0xF1); - registerWrite(0x45, 0x14); - registerWrite(0x5F, 0x34); - registerWrite(0x7B, 0x08); - registerWrite(0x5E, 0x34); - registerWrite(0x5B, 0x32); - registerWrite(0x6D, 0x32); - registerWrite(0x45, 0x17); - registerWrite(0x70, 0xE5); - registerWrite(0x71, 0xE5); - registerWrite(0x7F, 0x06); - registerWrite(0x44, 0x1B); - registerWrite(0x40, 0xBF); - registerWrite(0x4E, 0x3F); - registerWrite(0x7F, 0x08); - registerWrite(0x66, 0x44); - registerWrite(0x65, 0x20); - registerWrite(0x6A, 0x3a); - registerWrite(0x61, 0x05); - registerWrite(0x62, 0x05); - registerWrite(0x7F, 0x09); - registerWrite(0x4F, 0xAF); - registerWrite(0x48, 0x80); - registerWrite(0x49, 0x80); - registerWrite(0x57, 0x77); - registerWrite(0x5F, 0x40); - registerWrite(0x60, 0x78); - registerWrite(0x61, 0x78); - registerWrite(0x62, 0x08); - registerWrite(0x63, 0x50); - registerWrite(0x7F, 0x0A); - registerWrite(0x45, 0x60); - registerWrite(0x7F, 0x00); - registerWrite(0x4D, 0x11); - registerWrite(0x55, 0x80); - registerWrite(0x74, 0x21); - registerWrite(0x75, 0x1F); - registerWrite(0x4A, 0x78); - registerWrite(0x4B, 0x78); - registerWrite(0x44, 0x08); - registerWrite(0x45, 0x50); - registerWrite(0x64, 0xCE); - registerWrite(0x65, 0x0B); - registerWrite(0x72, 0x0A); - registerWrite(0x73, 0x00); - registerWrite(0x7F, 0x14); - registerWrite(0x44, 0x84); - registerWrite(0x65, 0x67); - registerWrite(0x66, 0x18); - registerWrite(0x63, 0x70); - registerWrite(0x6f, 0x2c); - registerWrite(0x7F, 0x15); - registerWrite(0x48, 0x48); - registerWrite(0x7F, 0x07); - registerWrite(0x41, 0x0D); - registerWrite(0x43, 0x14); - registerWrite(0x4B, 0x0E); - registerWrite(0x45, 0x0F); - registerWrite(0x44, 0x42); - registerWrite(0x4C, 0x80); - registerWrite(0x7F, 0x10); - registerWrite(0x5B, 0x02); - registerWrite(0x7F, 0x07); - registerWrite(0x40, 0x41); + RegisterWriteVerified(0x7F, 0x00); + RegisterWriteVerified(0x61, 0xAD); + RegisterWriteVerified(0x7F, 0x03); + RegisterWriteVerified(0x40, 0x00); + RegisterWriteVerified(0x7F, 0x05); + RegisterWriteVerified(0x41, 0xB3); + RegisterWriteVerified(0x43, 0xF1); + RegisterWriteVerified(0x45, 0x14); + RegisterWriteVerified(0x5F, 0x34); + RegisterWriteVerified(0x7B, 0x08); + RegisterWriteVerified(0x5E, 0x34); + RegisterWriteVerified(0x5B, 0x32); + RegisterWriteVerified(0x6D, 0x32); + RegisterWriteVerified(0x45, 0x17); + RegisterWriteVerified(0x70, 0xE5); + RegisterWriteVerified(0x71, 0xE5); + RegisterWriteVerified(0x7F, 0x06); + RegisterWriteVerified(0x44, 0x1B); + RegisterWriteVerified(0x40, 0xBF); + RegisterWriteVerified(0x4E, 0x3F); + RegisterWriteVerified(0x7F, 0x08); + RegisterWriteVerified(0x66, 0x44); + RegisterWriteVerified(0x65, 0x20); + RegisterWriteVerified(0x6A, 0x3a); + RegisterWriteVerified(0x61, 0x05); + RegisterWriteVerified(0x62, 0x05); + RegisterWriteVerified(0x7F, 0x09); + RegisterWriteVerified(0x4F, 0xAF); + RegisterWriteVerified(0x48, 0x80); + RegisterWriteVerified(0x49, 0x80); + RegisterWriteVerified(0x57, 0x77); + RegisterWriteVerified(0x5F, 0x40); + RegisterWriteVerified(0x60, 0x78); + RegisterWriteVerified(0x61, 0x78); + RegisterWriteVerified(0x62, 0x08); + RegisterWriteVerified(0x63, 0x50); + RegisterWriteVerified(0x7F, 0x0A); + RegisterWriteVerified(0x45, 0x60); + RegisterWriteVerified(0x7F, 0x00); + RegisterWriteVerified(0x4D, 0x11); + RegisterWriteVerified(0x55, 0x80); + RegisterWriteVerified(0x74, 0x21); + RegisterWriteVerified(0x75, 0x1F); + RegisterWriteVerified(0x4A, 0x78); + RegisterWriteVerified(0x4B, 0x78); + RegisterWriteVerified(0x44, 0x08); + RegisterWriteVerified(0x45, 0x50); + RegisterWriteVerified(0x64, 0xCE); + RegisterWriteVerified(0x65, 0x0B); + RegisterWriteVerified(0x72, 0x0A); + RegisterWriteVerified(0x73, 0x00); + RegisterWriteVerified(0x7F, 0x14); + RegisterWriteVerified(0x44, 0x84); + RegisterWriteVerified(0x65, 0x67); + RegisterWriteVerified(0x66, 0x18); + RegisterWriteVerified(0x63, 0x70); + RegisterWriteVerified(0x6f, 0x2c); + RegisterWriteVerified(0x7F, 0x15); + RegisterWriteVerified(0x48, 0x48); + RegisterWriteVerified(0x7F, 0x07); + RegisterWriteVerified(0x41, 0x0D); + RegisterWriteVerified(0x43, 0x14); + RegisterWriteVerified(0x4B, 0x0E); + RegisterWriteVerified(0x45, 0x0F); + RegisterWriteVerified(0x44, 0x42); + RegisterWriteVerified(0x4C, 0x80); + RegisterWriteVerified(0x7F, 0x10); + RegisterWriteVerified(0x5B, 0x02); + RegisterWriteVerified(0x7F, 0x07); + RegisterWriteVerified(0x40, 0x41); usleep(25_ms); // delay 25ms - registerWrite(0x7F, 0x00); - registerWrite(0x32, 0x44); - registerWrite(0x7F, 0x07); - registerWrite(0x40, 0x40); - registerWrite(0x7F, 0x06); - registerWrite(0x68, 0x40); - registerWrite(0x69, 0x02); - registerWrite(0x7F, 0x0D); - registerWrite(0x48, 0xC0); - registerWrite(0x6F, 0xD5); - registerWrite(0x7F, 0x00); - registerWrite(0x5B, 0xA0); - registerWrite(0x4E, 0xA8); - registerWrite(0x5A, 0x50); - registerWrite(0x40, 0x80); - registerWrite(0x73, 0x0B); + RegisterWriteVerified(0x7F, 0x00); + RegisterWriteVerified(0x32, 0x44); + RegisterWriteVerified(0x7F, 0x07); + RegisterWriteVerified(0x40, 0x40); + RegisterWriteVerified(0x7F, 0x06); + RegisterWriteVerified(0x68, 0x40); + RegisterWriteVerified(0x69, 0x02); + RegisterWriteVerified(0x7F, 0x0D); + RegisterWriteVerified(0x48, 0xC0); + RegisterWriteVerified(0x6F, 0xD5); + RegisterWriteVerified(0x7F, 0x00); + RegisterWriteVerified(0x5B, 0xA0); + RegisterWriteVerified(0x4E, 0xA8); + RegisterWriteVerified(0x5A, 0x50); + RegisterWriteVerified(0x40, 0x80); + RegisterWriteVerified(0x73, 0x0B); usleep(25_ms); // delay 25ms - registerWrite(0x73, 0x00); + RegisterWriteVerified(0x73, 0x00); + + // Enable LED_N controls + RegisterWriteVerified(0x7F, 0x14); + RegisterWriteVerified(0x6F, 0x1c); + RegisterWriteVerified(0x7F, 0x00); return true; } -uint8_t -PAW3902::registerRead(uint8_t reg) +uint8_t PAW3902::RegisterRead(uint8_t reg, int retries) { - uint8_t cmd[2] {}; - cmd[0] = reg; - transfer(&cmd[0], &cmd[0], sizeof(cmd)); - up_udelay(T_SRR); - return cmd[1]; + for (int i = 0; i < retries; i++) { + uint8_t cmd[2] {reg, 0}; + + if (transfer(&cmd[0], &cmd[0], sizeof(cmd)) == 0) { + return cmd[1]; + } + } + + perf_count(_comms_errors); + return 0; } -void -PAW3902::registerWrite(uint8_t reg, uint8_t data) +void PAW3902::RegisterWrite(uint8_t reg, uint8_t data) { uint8_t cmd[2]; cmd[0] = DIR_WRITE(reg); cmd[1] = data; - transfer(&cmd[0], nullptr, sizeof(cmd)); - up_udelay(T_SWW); + + if (transfer(&cmd[0], nullptr, sizeof(cmd)) != 0) { + perf_count(_comms_errors); + } } -void -PAW3902::RunImpl() +bool PAW3902::RegisterWriteVerified(uint8_t reg, uint8_t data, int retries) +{ + for (int i = 0; i < retries; i++) { + uint8_t cmd[2]; + cmd[0] = DIR_WRITE(reg); + cmd[1] = data; + transfer(&cmd[0], nullptr, sizeof(cmd)); + + // read back to verify + if (RegisterRead(reg) == data) { + return true; + } + } + + perf_count(_register_write_fail_perf); + + return false; +} + +void PAW3902::RunImpl() { perf_begin(_sample_perf); + perf_count(_interval_perf); struct TransferBuffer { uint8_t cmd = Register::Motion_Burst; BURST_TRANSFER data{}; - }; - TransferBuffer buf; + } buf{}; static_assert(sizeof(buf) == (12 + 1)); const hrt_abstime timestamp_sample = hrt_absolute_time(); @@ -555,15 +606,13 @@ PAW3902::RunImpl() return; } + perf_end(_sample_perf); + const uint64_t dt_flow = timestamp_sample - _previous_collect_timestamp; - _flow_dt_sum_usec += dt_flow; - _frame_count_since_last++; // update for next iteration _previous_collect_timestamp = timestamp_sample; - const int16_t delta_x_raw = ((int16_t)buf.data.Delta_X_H << 8) | buf.data.Delta_X_L; - const int16_t delta_y_raw = ((int16_t)buf.data.Delta_Y_H << 8) | buf.data.Delta_Y_L; // check SQUAL & Shutter values // To suppress false motion reports, discard Delta X and Delta Y values if the SQUAL and Shutter values meet the condition @@ -573,19 +622,31 @@ PAW3902::RunImpl() const uint16_t shutter = (buf.data.Shutter_Upper << 8) | buf.data.Shutter_Lower; if ((buf.data.SQUAL < 0x19) && (shutter >= 0x0BC0)) { - PX4_ERR("false motion report, discarding"); + PX4_DEBUG("false motion report, discarding"); + perf_count(_false_motion_perf); perf_end(_sample_perf); + + // reset + _flow_dt_sum_usec = 0; + _flow_sum_x = 0; + _flow_sum_y = 0; + _flow_sample_counter = 0; + _flow_quality_sum = 0; + return; } + const int16_t delta_x_raw = ((int16_t)buf.data.Delta_X_H << 8) | buf.data.Delta_X_L; + const int16_t delta_y_raw = ((int16_t)buf.data.Delta_Y_H << 8) | buf.data.Delta_Y_L; + switch (_mode) { case Mode::Bright: if ((shutter >= 0x1FFE) && (buf.data.RawData_Sum < 0x3C)) { + // Bright -> LowLight _bright_to_low_counter++; if (_bright_to_low_counter >= 10) { // AND valid for 10 consecutive frames - // Bright -> LowLight - changeMode(Mode::LowLight); + ChangeMode(Mode::LowLight); } } else { @@ -596,21 +657,21 @@ PAW3902::RunImpl() case Mode::LowLight: if ((shutter >= 0x1FFE) && (buf.data.RawData_Sum < 0x5A)) { + // LowLight -> SuperLowLight _low_to_bright_counter = 0; _low_to_superlow_counter++; if (_low_to_superlow_counter >= 10) { // AND valid for 10 consecutive frames - // LowLight -> SuperLowLight - changeMode(Mode::SuperLowLight); + ChangeMode(Mode::SuperLowLight); } } else if ((shutter < 0x0BB8)) { + // LowLight -> Bright _low_to_superlow_counter = 0; _low_to_bright_counter++; if (_low_to_bright_counter >= 10) { // AND valid for 10 consecutive frames - // LowLight -> Bright - changeMode(Mode::Bright); + ChangeMode(Mode::Bright); } } @@ -623,7 +684,7 @@ PAW3902::RunImpl() _superlow_to_low_counter++; if (_superlow_to_low_counter >= 10) { // AND valid for 10 consecutive frames - changeMode(Mode::LowLight); + ChangeMode(Mode::LowLight); } } else { @@ -633,68 +694,74 @@ PAW3902::RunImpl() break; } - // TODO: page 35 switching scheme + if (buf.data.SQUAL > 0) { + _flow_dt_sum_usec += dt_flow; + _flow_sum_x += delta_x_raw; + _flow_sum_y += delta_y_raw; + _flow_sample_counter++; + _flow_quality_sum += buf.data.SQUAL; - // As a minimum requirement, PAW3902JF should not operate with Shutter < 0x01F4 in Mode 2, and must switch to the next operation mode. - - _flow_sum_x += delta_x_raw; - _flow_sum_y += delta_y_raw; + } else { + // reset + _flow_dt_sum_usec = 0; + _flow_sum_x = 0; + _flow_sum_y = 0; + _flow_sample_counter = 0; + _flow_quality_sum = 0; + return; + } // returns if the collect time has not been reached - if (_flow_dt_sum_usec < _collect_time) { - perf_end(_sample_perf); + if (_flow_dt_sum_usec < COLLECT_TIME) { return; } optical_flow_s report{}; report.timestamp = timestamp_sample; + //report.device_id = get_device_id(); - report.pixel_flow_x_integral = (float)_flow_sum_x / 500.0f; // proportional factor + convert from pixels to radians - report.pixel_flow_y_integral = (float)_flow_sum_y / 500.0f; // proportional factor + convert from pixels to radians + float pixel_flow_x_integral = (float)_flow_sum_x / 500.0f; // proportional factor + convert from pixels to radians + float pixel_flow_y_integral = (float)_flow_sum_y / 500.0f; // proportional factor + convert from pixels to radians - // rotate measurements in yaw from sensor frame to body frame according to parameter SENS_FLOW_ROT - float zeroval = 0.0f; - rotate_3f(_yaw_rotation, report.pixel_flow_x_integral, report.pixel_flow_y_integral, zeroval); + // rotate measurements in yaw from sensor frame to body frame + const matrix::Vector3f pixel_flow_rotated = _rotation * matrix::Vector3f{pixel_flow_x_integral, pixel_flow_y_integral, 0.f}; + report.pixel_flow_x_integral = pixel_flow_rotated(0); + report.pixel_flow_y_integral = pixel_flow_rotated(1); - report.frame_count_since_last_readout = _frame_count_since_last; - report.integration_timespan = _flow_dt_sum_usec; // microseconds + report.frame_count_since_last_readout = _flow_sample_counter; // number of frames + report.integration_timespan = _flow_dt_sum_usec; // microseconds - report.sensor_id = 0; - report.quality = buf.data.SQUAL; + report.quality = _flow_sample_counter > 0 ? _flow_quality_sum / _flow_sample_counter : 0; - /* No gyro on this board */ + // No gyro on this board report.gyro_x_rate_integral = NAN; report.gyro_y_rate_integral = NAN; report.gyro_z_rate_integral = NAN; // set (conservative) specs according to datasheet - report.max_flow_rate = 5.0f; // Datasheet: 7.4 rad/s + report.max_flow_rate = 7.4f; // Datasheet: 7.4 rad/s report.min_ground_distance = 0.08f; // Datasheet: 80mm report.max_ground_distance = 30.0f; // Datasheet: infinity + report.timestamp = hrt_absolute_time(); _optical_flow_pub.publish(report); // reset _flow_dt_sum_usec = 0; _flow_sum_x = 0; _flow_sum_y = 0; - _frame_count_since_last = 0; - - perf_end(_sample_perf); + _flow_sample_counter = 0; + _flow_quality_sum = 0; } -void -PAW3902::start() -{ - // schedule a cycle to start things - ScheduleOnInterval(SAMPLE_INTERVAL_MODE_1); -} - -void -PAW3902::print_status() +void PAW3902::print_status() { I2CSPIDriverBase::print_status(); + perf_print_counter(_sample_perf); + perf_print_counter(_interval_perf); perf_print_counter(_comms_errors); - perf_print_counter(_dupe_count_perf); + perf_print_counter(_false_motion_perf); + perf_print_counter(_mode_change_perf); + perf_print_counter(_register_write_fail_perf); } diff --git a/src/drivers/optical_flow/paw3902/PAW3902.hpp b/src/drivers/optical_flow/paw3902/PAW3902.hpp index 1bacb54597..5f46a42db9 100644 --- a/src/drivers/optical_flow/paw3902/PAW3902.hpp +++ b/src/drivers/optical_flow/paw3902/PAW3902.hpp @@ -32,7 +32,7 @@ ****************************************************************************/ /** - * @file paw3902.cpp + * @file PAW3902.hpp * * Driver for the Pixart PAW3902 & PAW3903 optical flow sensors connected via SPI. */ @@ -50,27 +50,20 @@ #include #include #include -#include #include #include -/* Configuration Constants */ - -#define PAW3902_SPI_BUS_SPEED (2000000L) // 2MHz - -#define DIR_WRITE(a) ((a) | (1 << 7)) -#define DIR_READ(a) ((a) & 0x7f) - using namespace time_literals; using namespace PixArt_PAW3902JF; -// PAW3902JF-TXQT is PixArt Imaging +#define DIR_WRITE(a) ((a) | (1 << 7)) +#define DIR_READ(a) ((a) & 0x7f) class PAW3902 : public device::SPI, public I2CSPIDriver { public: - PAW3902(I2CSPIBusOption bus_option, int bus, int devid, enum Rotation yaw_rotation, int bus_frequency, - spi_mode_e spi_mode); + PAW3902(I2CSPIBusOption bus_option, int bus, int devid, int bus_frequency, spi_mode_e spi_mode, + float yaw_rotation_degrees = NAN); virtual ~PAW3902(); static I2CSPIDriverBase *instantiate(const BusCLIArguments &cli, const BusInstanceIterator &iterator, @@ -83,37 +76,38 @@ public: void RunImpl(); - void start(); - -protected: +private: int probe() override; -private: + uint8_t RegisterRead(uint8_t reg, int retries = 3); + void RegisterWrite(uint8_t reg, uint8_t data); + bool RegisterWriteVerified(uint8_t reg, uint8_t data, int retries = 5); - uint8_t registerRead(uint8_t reg); - void registerWrite(uint8_t reg, uint8_t data); + bool Reset(); - bool reset(); + bool ModeBright(); + bool ModeLowLight(); + bool ModeSuperLowLight(); - bool modeBright(); - bool modeLowLight(); - bool modeSuperLowLight(); - - bool changeMode(Mode newMode); + bool ChangeMode(Mode newMode); uORB::PublicationMulti _optical_flow_pub{ORB_ID(optical_flow)}; - perf_counter_t _sample_perf; - perf_counter_t _comms_errors; - perf_counter_t _dupe_count_perf; + perf_counter_t _sample_perf{perf_alloc(PC_ELAPSED, MODULE_NAME": read")}; + perf_counter_t _interval_perf{perf_alloc(PC_INTERVAL, MODULE_NAME": interval")}; + perf_counter_t _comms_errors{perf_alloc(PC_COUNT, MODULE_NAME": com err")}; + perf_counter_t _false_motion_perf{perf_alloc(PC_COUNT, MODULE_NAME": false motion report")}; + perf_counter_t _mode_change_perf{perf_alloc(PC_COUNT, MODULE_NAME": mode change")}; + perf_counter_t _register_write_fail_perf{perf_alloc(PC_COUNT, MODULE_NAME": verified register write failed")}; - static constexpr uint64_t _collect_time{15000}; // 15 milliseconds, optical flow data publish rate + static constexpr uint64_t COLLECT_TIME{15000}; // 15 milliseconds, optical flow data publish rate - uint64_t _previous_collect_timestamp{0}; - uint64_t _flow_dt_sum_usec{0}; - unsigned _frame_count_since_last{0}; + uint64_t _previous_collect_timestamp{0}; + uint64_t _flow_dt_sum_usec{0}; + uint8_t _flow_sample_counter{0}; + uint16_t _flow_quality_sum{0}; - enum Rotation _yaw_rotation {ROTATION_NONE}; + matrix::Dcmf _rotation; int _flow_sum_x{0}; int _flow_sum_y{0}; @@ -123,5 +117,4 @@ private: uint8_t _low_to_superlow_counter{0}; uint8_t _low_to_bright_counter{0}; uint8_t _superlow_to_low_counter{0}; - }; diff --git a/src/drivers/optical_flow/paw3902/PixArt_PAW3902JF_Registers.hpp b/src/drivers/optical_flow/paw3902/PixArt_PAW3902JF_Registers.hpp index 8dcbf626af..a012c3f0e8 100644 --- a/src/drivers/optical_flow/paw3902/PixArt_PAW3902JF_Registers.hpp +++ b/src/drivers/optical_flow/paw3902/PixArt_PAW3902JF_Registers.hpp @@ -36,45 +36,45 @@ namespace PixArt_PAW3902JF { -static constexpr uint8_t PRODUCT_ID = 0x49; // shared with the PMW3901 +static constexpr uint8_t PRODUCT_ID = 0x49; static constexpr uint8_t REVISION_ID = 0x01; +static constexpr uint8_t PRODUCT_ID_INVERSE = 0xB6; static constexpr uint32_t SAMPLE_INTERVAL_MODE_0{1000000 / 126}; // 126 fps static constexpr uint32_t SAMPLE_INTERVAL_MODE_1{1000000 / 126}; // 126 fps static constexpr uint32_t SAMPLE_INTERVAL_MODE_2{1000000 / 50}; // 50 fps -static constexpr uint64_t T_SWW{11}; // 10.5 microseconds -static constexpr uint64_t T_SRR{2}; // 1.5 microseconds +static constexpr uint32_t SPI_SPEED = 2 * 1000 * 1000; // 2MHz SPI serial interface enum Register : uint8_t { - Product_ID = 0x00, - Revision_ID = 0x01, - Motion = 0x02, - Delta_X_L = 0x03, - Delta_X_H = 0x04, - Delta_Y_L = 0x05, - Delta_Y_H = 0x06, - Squal = 0x07, - RawData_Sum = 0x08, - Maximum_RawData = 0x09, - Minimum_RawData = 0x0A, - Shutter_Lower = 0x0B, - Shutter_Upper = 0x0C, + Product_ID = 0x00, + Revision_ID = 0x01, + Motion = 0x02, + Delta_X_L = 0x03, + Delta_X_H = 0x04, + Delta_Y_L = 0x05, + Delta_Y_H = 0x06, + Squal = 0x07, + RawData_Sum = 0x08, + Maximum_RawData = 0x09, + Minimum_RawData = 0x0A, + Shutter_Lower = 0x0B, + Shutter_Upper = 0x0C, - Observation = 0x15, - Motion_Burst = 0x16, + Observation = 0x15, + Motion_Burst = 0x16, - Power_Up_Reset = 0x3A, + Power_Up_Reset = 0x3A, - Resolution = 0x4E, + Resolution = 0x4E, + Inverse_Product_ID = 0x5F, }; enum Product_ID_Bit : uint8_t { Reset = 0x5A, }; - enum class Mode { Bright = 0, LowLight = 1, diff --git a/src/drivers/optical_flow/paw3902/paw3902_main.cpp b/src/drivers/optical_flow/paw3902/paw3902_main.cpp index 37633d275c..8bca7ba583 100644 --- a/src/drivers/optical_flow/paw3902/paw3902_main.cpp +++ b/src/drivers/optical_flow/paw3902/paw3902_main.cpp @@ -1,6 +1,6 @@ /**************************************************************************** * - * Copyright (c) 2019 PX4 Development Team. All rights reserved. + * Copyright (c) 2019-2020 PX4 Development Team. All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -34,23 +34,20 @@ #include "PAW3902.hpp" #include -extern "C" __EXPORT int paw3902_main(int argc, char *argv[]); - -void -PAW3902::print_usage() +void PAW3902::print_usage() { PRINT_MODULE_USAGE_NAME("paw3902", "driver"); PRINT_MODULE_USAGE_COMMAND("start"); PRINT_MODULE_USAGE_PARAMS_I2C_SPI_DRIVER(false, true); - PRINT_MODULE_USAGE_PARAM_INT('R', 0, 0, 35, "Rotation", true); + PRINT_MODULE_USAGE_PARAM_INT('Y', 0, 0, 359, "custom yaw rotation (degrees)", true); PRINT_MODULE_USAGE_DEFAULT_COMMANDS(); } I2CSPIDriverBase *PAW3902::instantiate(const BusCLIArguments &cli, const BusInstanceIterator &iterator, int runtime_instance) { - PAW3902 *instance = new PAW3902(iterator.configuredBusOption(), iterator.bus(), iterator.devid(), cli.rotation, - cli.bus_frequency, cli.spi_mode); + PAW3902 *instance = new PAW3902(iterator.configuredBusOption(), iterator.bus(), iterator.devid(), cli.bus_frequency, + cli.spi_mode, cli.custom1); if (!instance) { PX4_ERR("alloc failed"); @@ -65,19 +62,18 @@ I2CSPIDriverBase *PAW3902::instantiate(const BusCLIArguments &cli, const BusInst return instance; } -int -paw3902_main(int argc, char *argv[]) +extern "C" __EXPORT int paw3902_main(int argc, char *argv[]) { - int ch; + int ch = 0; using ThisDriver = PAW3902; BusCLIArguments cli{false, true}; cli.spi_mode = SPIDEV_MODE0; - cli.default_spi_frequency = PAW3902_SPI_BUS_SPEED; + cli.default_spi_frequency = SPI_SPEED; - while ((ch = cli.getopt(argc, argv, "R:")) != EOF) { + while ((ch = cli.getopt(argc, argv, "Y:")) != EOF) { switch (ch) { - case 'R': - cli.rotation = (enum Rotation)atoi(cli.optarg()); + case 'Y': + cli.custom1 = atoi(cli.optarg()); break; } }