mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
uncrustify libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp
This commit is contained in:
parent
ce14ba0868
commit
b505b26226
@ -1,27 +1,27 @@
|
||||
/*
|
||||
AP_OpticalFlow_ADNS3080.cpp - ADNS3080 OpticalFlow Library for Ardupilot Mega
|
||||
Code by Randy Mackay. DIYDrones.com
|
||||
|
||||
This library is free software; you can redistribute it and/or
|
||||
modify it under the terms of the GNU Lesser General Public
|
||||
License as published by the Free Software Foundation; either
|
||||
version 2.1 of the License, or (at your option) any later version.
|
||||
|
||||
External ADNS3080 OpticalFlow is connected via Serial port 2 (in SPI mode)
|
||||
TXD2 = MOSI = pin PH1
|
||||
RXD2 = MISO = pin PH0
|
||||
XCK2 = SCK = pin PH2
|
||||
Chip Select pin is PC4 (33) [PH6 (9)]
|
||||
We are using the 16 clocks per conversion timming to increase efficiency (fast)
|
||||
The sampling frequency is 400Hz (Timer2 overflow interrupt)
|
||||
So if our loop is at 50Hz, our needed sampling freq should be 100Hz, so
|
||||
we have an 4x oversampling and averaging.
|
||||
|
||||
Methods:
|
||||
Init() : Initialization of interrupts an Timers (Timer2 overflow interrupt)
|
||||
Read() : Read latest values from OpticalFlow and store to x,y, surface_quality parameters
|
||||
|
||||
*/
|
||||
* AP_OpticalFlow_ADNS3080.cpp - ADNS3080 OpticalFlow Library for Ardupilot Mega
|
||||
* Code by Randy Mackay. DIYDrones.com
|
||||
*
|
||||
* This library is free software; you can redistribute it and/or
|
||||
* modify it under the terms of the GNU Lesser General Public
|
||||
* License as published by the Free Software Foundation; either
|
||||
* version 2.1 of the License, or (at your option) any later version.
|
||||
*
|
||||
* External ADNS3080 OpticalFlow is connected via Serial port 2 (in SPI mode)
|
||||
* TXD2 = MOSI = pin PH1
|
||||
* RXD2 = MISO = pin PH0
|
||||
* XCK2 = SCK = pin PH2
|
||||
* Chip Select pin is PC4 (33) [PH6 (9)]
|
||||
* We are using the 16 clocks per conversion timming to increase efficiency (fast)
|
||||
* The sampling frequency is 400Hz (Timer2 overflow interrupt)
|
||||
* So if our loop is at 50Hz, our needed sampling freq should be 100Hz, so
|
||||
* we have an 4x oversampling and averaging.
|
||||
*
|
||||
* Methods:
|
||||
* Init() : Initialization of interrupts an Timers (Timer2 overflow interrupt)
|
||||
* Read() : Read latest values from OpticalFlow and store to x,y, surface_quality parameters
|
||||
*
|
||||
*/
|
||||
|
||||
#include "AP_OpticalFlow_ADNS3080.h"
|
||||
#include "SPI.h"
|
||||
@ -51,7 +51,7 @@ union NumericIntType
|
||||
byte byteValue[2];
|
||||
};
|
||||
|
||||
// Constructors ////////////////////////////////////////////////////////////////
|
||||
// Constructors ////////////////////////////////////////////////////////////////
|
||||
AP_OpticalFlow_ADNS3080::AP_OpticalFlow_ADNS3080(int cs_pin, int reset_pin) : _cs_pin(cs_pin), _reset_pin(reset_pin)
|
||||
{
|
||||
num_pixels = ADNS3080_PIXELS_X;
|
||||
|
Loading…
Reference in New Issue
Block a user