uncrustify libraries/AP_ADC/AP_ADC_ADS7844.cpp

This commit is contained in:
uncrustify 2012-08-16 22:39:21 -07:00 committed by Pat Hickey
parent 7bfe32fd3d
commit dcf4a9824d
1 changed files with 147 additions and 147 deletions

View File

@ -1,56 +1,56 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
/*
AP_ADC_ADS7844.cpp - ADC ADS7844 Library for Ardupilot Mega
Code by Jordi Mu<EFBFBD>oz and Jose Julio. DIYDrones.com
Modified by John Ihlein 6 / 19 / 2010 to:
1)Prevent overflow of adc_counter when more than 8 samples collected between reads. Probably
only an issue on initial read of ADC at program start.
2)Reorder analog read order as follows:
p, q, r, ax, ay, az
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 ADC ADS7844 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 1kHz (Timer2 overflow interrupt)
So if our loop is at 50Hz, our needed sampling freq should be 100Hz, so
we have an 10x oversampling and averaging.
Methods:
Init() : Initialization of interrupts an Timers (Timer2 overflow interrupt)
Ch(ch_num) : Return the ADC channel value
// HJI - Input definitions. USB connector assumed to be on the left, Rx and servo
// connector pins to the rear. IMU shield components facing up. These are board
// referenced sensor inputs, not device referenced.
On Ardupilot Mega Hardware, oriented as described above:
Chennel 0 : yaw rate, r
Channel 1 : roll rate, p
Channel 2 : pitch rate, q
Channel 3 : x / y gyro temperature
Channel 4 : x acceleration, aX
Channel 5 : y acceleration, aY
Channel 6 : z acceleration, aZ
Channel 7 : Differential pressure sensor port
*/
* AP_ADC_ADS7844.cpp - ADC ADS7844 Library for Ardupilot Mega
* Code by Jordi Mu<EFBFBD>oz and Jose Julio. DIYDrones.com
*
* Modified by John Ihlein 6 / 19 / 2010 to:
* 1)Prevent overflow of adc_counter when more than 8 samples collected between reads. Probably
* only an issue on initial read of ADC at program start.
* 2)Reorder analog read order as follows:
* p, q, r, ax, ay, az
*
* 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 ADC ADS7844 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 1kHz (Timer2 overflow interrupt)
*
* So if our loop is at 50Hz, our needed sampling freq should be 100Hz, so
* we have an 10x oversampling and averaging.
*
* Methods:
* Init() : Initialization of interrupts an Timers (Timer2 overflow interrupt)
* Ch(ch_num) : Return the ADC channel value
*
* // HJI - Input definitions. USB connector assumed to be on the left, Rx and servo
* // connector pins to the rear. IMU shield components facing up. These are board
* // referenced sensor inputs, not device referenced.
* On Ardupilot Mega Hardware, oriented as described above:
* Chennel 0 : yaw rate, r
* Channel 1 : roll rate, p
* Channel 2 : pitch rate, q
* Channel 3 : x / y gyro temperature
* Channel 4 : x acceleration, aX
* Channel 5 : y acceleration, aY
* Channel 6 : z acceleration, aZ
* Channel 7 : Differential pressure sensor port
*
*/
#include "AP_ADC_ADS7844.h"
extern "C" {
// AVR LibC Includes
#include <inttypes.h>
#include <stdint.h>
#include <avr/interrupt.h>
// AVR LibC Includes
#include <inttypes.h>
#include <stdint.h>
#include <avr/interrupt.h>
}
#if defined(ARDUINO) && ARDUINO >= 100
#include "Arduino.h"
@ -82,7 +82,7 @@ static inline unsigned char ADC_SPI_transfer(unsigned char data)
/* Put data into buffer, sends the data */
UDR2 = data;
/* Wait for data to be received */
while ( !(UCSR2A & (1 << RXC2)) );
while ( !(UCSR2A & (1 << RXC2)) ) ;
/* Get and return received data from buffer */
return UDR2;
}
@ -172,7 +172,7 @@ float AP_ADC_ADS7844::Ch(uint8_t ch_num)
uint32_t sum;
// ensure we have at least one value
while (_count[ch_num] == 0) /* noop */ ;
while (_count[ch_num] == 0) /* noop */;
// grab the value with interrupts disabled, and clear the count
cli();