mirror of https://github.com/ArduPilot/ardupilot
Optical Flow - added overflow check
This commit is contained in:
parent
9195006541
commit
99506accf4
|
@ -190,11 +190,14 @@ AP_OpticalFlow_ADNS3080::reset()
|
|||
bool
|
||||
AP_OpticalFlow_ADNS3080::update()
|
||||
{
|
||||
byte motion_reg;
|
||||
surface_quality = (unsigned int)read_register(ADNS3080_SQUAL);
|
||||
delayMicroseconds(50); // small delay
|
||||
|
||||
// check for movement, update x,y values
|
||||
if( (read_register(ADNS3080_MOTION) & 0x80) != 0 ) {
|
||||
motion_reg = read_register(ADNS3080_MOTION);
|
||||
_overflow = ((motion_reg & 0x10) != 0); // check if we've had an overflow
|
||||
if( (motion_reg & 0x80) != 0 ) {
|
||||
raw_dx = ((char)read_register(ADNS3080_DELTA_X));
|
||||
delayMicroseconds(50); // small delay
|
||||
raw_dy = ((char)read_register(ADNS3080_DELTA_Y));
|
||||
|
|
|
@ -100,7 +100,8 @@ class AP_OpticalFlow_ADNS3080 : public AP_OpticalFlow
|
|||
public:
|
||||
int _cs_pin; // pin used for chip select
|
||||
int _reset_pin; // pin used for chip reset
|
||||
bool _motion; // true if there has been motion
|
||||
bool _motion; // true if there has been motion
|
||||
bool _overflow; // true if the x or y data buffers overflowed
|
||||
|
||||
public:
|
||||
AP_OpticalFlow_ADNS3080(int cs_pin = ADNS3080_CHIP_SELECT, int reset_pin = ADNS3080_RESET);
|
||||
|
|
|
@ -312,6 +312,10 @@ void display_motion()
|
|||
flowSensor.update();
|
||||
flowSensor.update_position(0,0,0,1,100);
|
||||
|
||||
// check for errors
|
||||
if( flowSensor._overflow )
|
||||
Serial.println("overflow!!");
|
||||
|
||||
// x,y,squal
|
||||
//if( flowSensor.motion() || first_time ) {
|
||||
Serial.print("x/dx: ");
|
||||
|
|
Loading…
Reference in New Issue