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,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"
@ -73,7 +73,7 @@ union NumericIntType
byte byteValue[2];
};
// Constructors ////////////////////////////////////////////////////////////////
// Constructors ////////////////////////////////////////////////////////////////
AP_OpticalFlow_ADNS3080_APM2::AP_OpticalFlow_ADNS3080_APM2(int cs_pin, int reset_pin) : _cs_pin(cs_pin), _reset_pin(reset_pin)
{
num_pixels = ADNS3080_PIXELS_X;
@ -87,13 +87,13 @@ unsigned char AP_OpticalFlow_ADNS3080_APM2::SPI_transfer(uint8_t data)
{
/* Wait for empty transmit buffer */
while ( !( UCSR3A & (1<<UDRE3)) );
while ( !( UCSR3A & (1<<UDRE3)) ) ;
/* Put data into buffer, sends the data */
UDR3 = data;
/* Wait for data to be received */
while ( !(UCSR3A & (1<<RXC3)) );
while ( !(UCSR3A & (1<<RXC3)) ) ;
/* Get and return received data from buffer */
return UDR3;
@ -154,7 +154,7 @@ void AP_OpticalFlow_ADNS3080_APM2::backup_spi_settings()
uint8_t temp;
/* Wait for empty transmit buffer */
while ( !( UCSR3A & (1<<UDRE3)) );
while ( !( UCSR3A & (1<<UDRE3)) ) ;
// store current spi values
orig_spi_settings_ucsr3c = UCSR3C;
@ -170,7 +170,7 @@ void AP_OpticalFlow_ADNS3080_APM2::backup_spi_settings()
void AP_OpticalFlow_ADNS3080_APM2::restore_spi_settings()
{
/* Wait for empty transmit buffer */
while ( !( UCSR3A & (1<<UDRE3)) );
while ( !( UCSR3A & (1<<UDRE3)) ) ;
// restore UCSRC3C and UBRR3
UCSR3C = orig_spi_settings_ucsr3c;