uncrustify libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080_APM2.h

This commit is contained in:
uncrustify 2012-08-16 23:20:51 -07:00 committed by Pat Hickey
parent 9d29effd2b
commit f7af330bfe
1 changed files with 49 additions and 47 deletions

View File

@ -77,7 +77,7 @@
class AP_OpticalFlow_ADNS3080_APM2 : public AP_OpticalFlow
{
private:
private:
// bytes to store SPI settings
byte orig_spi_settings_ucsr3c;
byte orig_spi_settings_ubrr3;
@ -86,13 +86,13 @@ class AP_OpticalFlow_ADNS3080_APM2 : public AP_OpticalFlow
void backup_spi_settings();
void restore_spi_settings();
public:
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 _overflow; // true if the x or y data buffers overflowed
public:
public:
AP_OpticalFlow_ADNS3080_APM2(int cs_pin = ADNS3080_CHIP_SELECT, int reset_pin = ADNS3080_RESET);
bool init(bool initCommAPI = true); // parameter controls whether I2C/SPI interface is initialised (set to false if other devices are on the I2C/SPI bus and have already initialised the interface)
byte read_register(byte address);
@ -101,7 +101,9 @@ class AP_OpticalFlow_ADNS3080_APM2 : public AP_OpticalFlow
bool update(); // read latest values from sensor and fill in x,y and totals, return true on successful read
// ADNS3080 specific features
bool motion() { if( _motion ) { _motion = false; return true; }else{ return false; } } // return true if there has been motion since the last time this was called
bool motion() {
if( _motion ) { _motion = false; return true; }else{ return false; }
} // return true if there has been motion since the last time this was called
void disable_serial_pullup();