mirror of https://github.com/ArduPilot/ardupilot
uncrustify libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080_APM2.h
This commit is contained in:
parent
9d29effd2b
commit
f7af330bfe
|
@ -26,7 +26,7 @@
|
|||
// ADNS3080 hardware config
|
||||
#define ADNS3080_PIXELS_X 30
|
||||
#define ADNS3080_PIXELS_Y 30
|
||||
#define ADNS3080_CLOCK_SPEED 24000000
|
||||
#define ADNS3080_CLOCK_SPEED 24000000
|
||||
|
||||
// Register Map for the ADNS3080 Optical OpticalFlow Sensor
|
||||
#define ADNS3080_PRODUCT_ID 0x00
|
||||
|
@ -65,11 +65,11 @@
|
|||
#define ADNS3080_LED_MODE_ALWAYS_ON 0x00
|
||||
#define ADNS3080_LED_MODE_WHEN_REQUIRED 0x01
|
||||
|
||||
#define ADNS3080_RESOLUTION_400 400
|
||||
#define ADNS3080_RESOLUTION_1600 1600
|
||||
#define ADNS3080_RESOLUTION_400 400
|
||||
#define ADNS3080_RESOLUTION_1600 1600
|
||||
|
||||
// Extended Configuration bits
|
||||
#define ADNS3080_SERIALNPU_OFF 0x02
|
||||
#define ADNS3080_SERIALNPU_OFF 0x02
|
||||
|
||||
#define ADNS3080_FRAME_RATE_MAX 6469
|
||||
#define ADNS3080_FRAME_RATE_MIN 2000
|
||||
|
@ -77,65 +77,67 @@
|
|||
|
||||
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;
|
||||
byte orig_spi_settings_ucsr3c;
|
||||
byte orig_spi_settings_ubrr3;
|
||||
|
||||
// save and restore SPI settings
|
||||
void backup_spi_settings();
|
||||
void restore_spi_settings();
|
||||
// save and restore SPI settings
|
||||
void backup_spi_settings();
|
||||
void restore_spi_settings();
|
||||
|
||||
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:
|
||||
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:
|
||||
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);
|
||||
void write_register(byte address, byte value);
|
||||
void reset(); // reset sensor by holding a pin high (or is it low?) for 10us.
|
||||
bool update(); // read latest values from sensor and fill in x,y and totals, return true on successful read
|
||||
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);
|
||||
void write_register(byte address, byte value);
|
||||
void reset(); // reset sensor by holding a pin high (or is it low?) for 10us.
|
||||
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
|
||||
// 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
|
||||
|
||||
void disable_serial_pullup();
|
||||
void disable_serial_pullup();
|
||||
|
||||
bool get_led_always_on(); // returns true if LED is always on, false if only on when required
|
||||
void set_led_always_on( bool alwaysOn ); // set parameter to true if you want LED always on, otherwise false for only when required
|
||||
bool get_led_always_on(); // returns true if LED is always on, false if only on when required
|
||||
void set_led_always_on( bool alwaysOn ); // set parameter to true if you want LED always on, otherwise false for only when required
|
||||
|
||||
int get_resolution(); // returns resolution (either 400 or 1600 counts per inch)
|
||||
void set_resolution(int resolution); // set parameter to 400 or 1600 counts per inch
|
||||
int get_resolution(); // returns resolution (either 400 or 1600 counts per inch)
|
||||
void set_resolution(int resolution); // set parameter to 400 or 1600 counts per inch
|
||||
|
||||
bool get_frame_rate_auto(); // get_frame_rate_auto - return true if frame rate is set to "auto", false if manual
|
||||
void set_frame_rate_auto(bool auto_frame_rate); // set_frame_rate_auto(bool) - set frame rate to auto (true), or manual (false)
|
||||
bool get_frame_rate_auto(); // get_frame_rate_auto - return true if frame rate is set to "auto", false if manual
|
||||
void set_frame_rate_auto(bool auto_frame_rate); // set_frame_rate_auto(bool) - set frame rate to auto (true), or manual (false)
|
||||
|
||||
unsigned int get_frame_period(); // get_frame_period -
|
||||
void set_frame_period(unsigned int period);
|
||||
unsigned int get_frame_period(); // get_frame_period -
|
||||
void set_frame_period(unsigned int period);
|
||||
|
||||
unsigned int get_frame_rate();
|
||||
void set_frame_rate(unsigned int rate);
|
||||
unsigned int get_frame_rate();
|
||||
void set_frame_rate(unsigned int rate);
|
||||
|
||||
bool get_shutter_speed_auto(); // get_shutter_speed_auto - returns true if shutter speed is adjusted automatically, false if manual
|
||||
void set_shutter_speed_auto(bool auto_shutter_speed); // set_shutter_speed_auto - set shutter speed to auto (true), or manual (false)
|
||||
bool get_shutter_speed_auto(); // get_shutter_speed_auto - returns true if shutter speed is adjusted automatically, false if manual
|
||||
void set_shutter_speed_auto(bool auto_shutter_speed); // set_shutter_speed_auto - set shutter speed to auto (true), or manual (false)
|
||||
|
||||
unsigned int get_shutter_speed();
|
||||
void set_shutter_speed(unsigned int shutter_speed);
|
||||
unsigned int get_shutter_speed();
|
||||
void set_shutter_speed(unsigned int shutter_speed);
|
||||
|
||||
void clear_motion(); // will cause the x,y, dx, dy, and the sensor's motion registers to be cleared
|
||||
void clear_motion(); // will cause the x,y, dx, dy, and the sensor's motion registers to be cleared
|
||||
|
||||
void print_pixel_data(Stream *serPort); // dumps a 30x30 image to the Serial port
|
||||
void print_pixel_data(Stream *serPort); // dumps a 30x30 image to the Serial port
|
||||
|
||||
// SPI functions - we use UAT3 which is not supported by Arduino
|
||||
unsigned char SPI_transfer(unsigned char data);
|
||||
void CS_inactive();
|
||||
void CS_active();
|
||||
void PageErase (uint16_t PageAdr);
|
||||
void ChipErase ();
|
||||
// SPI functions - we use UAT3 which is not supported by Arduino
|
||||
unsigned char SPI_transfer(unsigned char data);
|
||||
void CS_inactive();
|
||||
void CS_active();
|
||||
void PageErase (uint16_t PageAdr);
|
||||
void ChipErase ();
|
||||
};
|
||||
|
||||
#endif
|
||||
|
|
Loading…
Reference in New Issue