uncrustify libraries/AP_OpticalFlow/AP_OpticalFlow_ADNS3080_APM2.cpp

This commit is contained in:
uncrustify 2012-08-16 23:20:51 -07:00 committed by Pat Hickey
parent 8f5c22d448
commit dcee71d442
1 changed files with 245 additions and 245 deletions

View File

@ -1,26 +1,26 @@
/* /*
AP_OpticalFlow_ADNS3080.cpp - ADNS3080 OpticalFlow Library for Ardupilot Mega * AP_OpticalFlow_ADNS3080.cpp - ADNS3080 OpticalFlow Library for Ardupilot Mega
Code by Randy Mackay. DIYDrones.com * Code by Randy Mackay. DIYDrones.com
*
This library is free software; you can redistribute it and/or * This library is free software; you can redistribute it and/or
modify it under the terms of the GNU Lesser General Public * modify it under the terms of the GNU Lesser General Public
License as published by the Free Software Foundation; either * License as published by the Free Software Foundation; either
version 2.1 of the License, or (at your option) any later version. * 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) * External ADNS3080 OpticalFlow is connected via Serial port 2 (in SPI mode)
TXD2 = MOSI = pin PH1 * TXD2 = MOSI = pin PH1
RXD2 = MISO = pin PH0 * RXD2 = MISO = pin PH0
XCK2 = SCK = pin PH2 * XCK2 = SCK = pin PH2
Chip Select pin is PC4 (33) [PH6 (9)] * Chip Select pin is PC4 (33) [PH6 (9)]
We are using the 16 clocks per conversion timming to increase efficiency (fast) * We are using the 16 clocks per conversion timming to increase efficiency (fast)
The sampling frequency is 400Hz (Timer2 overflow interrupt) * The sampling frequency is 400Hz (Timer2 overflow interrupt)
So if our loop is at 50Hz, our needed sampling freq should be 100Hz, so * So if our loop is at 50Hz, our needed sampling freq should be 100Hz, so
we have an 4x oversampling and averaging. * we have an 4x oversampling and averaging.
*
Methods: * Methods:
Init() : Initialization of interrupts an Timers (Timer2 overflow interrupt) * Init() : Initialization of interrupts an Timers (Timer2 overflow interrupt)
Read() : Read latest values from OpticalFlow and store to x,y, surface_quality parameters * Read() : Read latest values from OpticalFlow and store to x,y, surface_quality parameters
*
*/ */
#include "AP_OpticalFlow_ADNS3080.h" #include "AP_OpticalFlow_ADNS3080.h"