mirror of https://github.com/ArduPilot/ardupilot
Reorder the channels
Fix overflow issue git-svn-id: https://arducopter.googlecode.com/svn/trunk@449 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
80bc831363
commit
72d031b4b5
|
@ -2,6 +2,12 @@
|
||||||
APM_ADC.cpp - ADC ADS7844 Library for Ardupilot Mega
|
APM_ADC.cpp - ADC ADS7844 Library for Ardupilot Mega
|
||||||
Code by Jordi Muñoz and Jose Julio. DIYDrones.com
|
Code by Jordi Muñ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
|
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
|
||||||
|
@ -21,14 +27,18 @@
|
||||||
Init() : Initialization of interrupts an Timers (Timer2 overflow interrupt)
|
Init() : Initialization of interrupts an Timers (Timer2 overflow interrupt)
|
||||||
Ch(ch_num) : Return the ADC channel value
|
Ch(ch_num) : Return the ADC channel value
|
||||||
|
|
||||||
On Ardupilot Mega Hardware:
|
// HJI - Input definitions. USB connector assumed to be on the left, Rx and servo
|
||||||
Channel 1 : Gyro Z
|
// connector pins to the rear. IMU shield components facing up. These are board
|
||||||
Channel 2 : Gyro X
|
// referenced sensor inputs, not device referenced.
|
||||||
Channel 3 : Gyro Y
|
On Ardupilot Mega Hardware, oriented as described above:
|
||||||
Channel 4 : Acc X
|
Chennel 0 : yaw rate, r
|
||||||
Channel 5 : Acc Y
|
Channel 1 : roll rate, p
|
||||||
Channel 6 : Acc Z
|
Channel 2 : pitch rate, q
|
||||||
Channel 7 : Differential pressure sensor
|
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
|
||||||
|
|
||||||
*/
|
*/
|
||||||
extern "C" {
|
extern "C" {
|
||||||
|
@ -40,10 +50,13 @@ extern "C" {
|
||||||
|
|
||||||
#include "APM_ADC.h"
|
#include "APM_ADC.h"
|
||||||
|
|
||||||
|
// HJI - changed read order to p, q, r, ax, ay, az, gyro temperature, JP5 pin 3
|
||||||
// Commands for reading ADC channels on ADS7844
|
// Commands for reading ADC channels on ADS7844
|
||||||
const unsigned char adc_cmd[9]= { 0x87, 0xC7, 0x97, 0xD7, 0xA7, 0xE7, 0xB7, 0xF7, 0x00 };
|
// Note change in read order pRate qRate rRate aX aY aZ temp JP5
|
||||||
volatile long adc_value[8];
|
// ADC Input Channel Ch1 Ch2 Ch0 Ch4 Ch5 Ch6 Ch3 Ch7
|
||||||
volatile unsigned char adc_counter[8];
|
const unsigned char adc_cmd[9] = { 0xC7, 0x97, 0x87, 0xA7, 0xE7, 0xB7, 0xD7, 0xF7, 0x00 };
|
||||||
|
volatile long adc_value[8] = { 0, 0, 0, 0, 0, 0, 0, 0 };
|
||||||
|
volatile unsigned char adc_counter[8] = { 0, 0, 0, 0, 0, 0, 0, 0 };
|
||||||
|
|
||||||
unsigned char ADC_SPI_transfer(unsigned char data)
|
unsigned char ADC_SPI_transfer(unsigned char data)
|
||||||
{
|
{
|
||||||
|
@ -63,19 +76,24 @@ ISR (TIMER2_OVF_vect)
|
||||||
uint8_t ch;
|
uint8_t ch;
|
||||||
unsigned int adc_tmp;
|
unsigned int adc_tmp;
|
||||||
|
|
||||||
//bit_set(PORTL,6); // To test performance
|
//bit_set(PORTL,6); // To test performance
|
||||||
bit_clear(PORTC,4); // Enable Chip Select (PIN PC4)
|
bit_clear(PORTC,4); // Enable Chip Select (PIN PC4)
|
||||||
ADC_SPI_transfer(adc_cmd[0]); // Command to read the first channel
|
ADC_SPI_transfer(adc_cmd[0]); // Command to read the first channel
|
||||||
for (ch=0;ch<8;ch++)
|
for (ch=0;ch<8;ch++)
|
||||||
{
|
{
|
||||||
adc_tmp = ADC_SPI_transfer(0)<<8; // Read first byte
|
if (adc_counter[ch] >= 17) // HJI - Added this to prevent
|
||||||
adc_tmp |= ADC_SPI_transfer(adc_cmd[ch+1]); // Read second byte and send next command
|
{ // overflow of adc_value
|
||||||
adc_value[ch] += adc_tmp>>3; // Shift to 12 bits
|
adc_value[ch] = 0;
|
||||||
adc_counter[ch]++; // Number of samples
|
adc_counter[ch] = 0;
|
||||||
|
}
|
||||||
|
adc_tmp = ADC_SPI_transfer(0)<<8; // Read first byte
|
||||||
|
adc_tmp |= ADC_SPI_transfer(adc_cmd[ch+1]); // Read second byte and send next command
|
||||||
|
adc_value[ch] += adc_tmp>>3; // Shift to 12 bits
|
||||||
|
adc_counter[ch]++; // Number of samples
|
||||||
}
|
}
|
||||||
bit_set(PORTC,4); // Disable Chip Select (PIN PC4)
|
bit_set(PORTC,4); // Disable Chip Select (PIN PC4)
|
||||||
//bit_clear(PORTL,6); // To test performance
|
//bit_clear(PORTL,6); // To test performance
|
||||||
TCNT2 = 104; // 400 Hz
|
TCNT2 = 104; // 400 Hz
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
@ -91,26 +109,26 @@ void APM_ADC_Class::Init(void)
|
||||||
|
|
||||||
pinMode(ADC_CHIP_SELECT,OUTPUT);
|
pinMode(ADC_CHIP_SELECT,OUTPUT);
|
||||||
|
|
||||||
digitalWrite(ADC_CHIP_SELECT,HIGH); // Disable device (Chip select is active low)
|
digitalWrite(ADC_CHIP_SELECT,HIGH); // Disable device (Chip select is active low)
|
||||||
|
|
||||||
// Setup Serial Port2 in SPI mode
|
// Setup Serial Port2 in SPI mode
|
||||||
UBRR2 = 0;
|
UBRR2 = 0;
|
||||||
DDRH |= (1<<PH2); // SPI clock XCK2 (PH2) as output. This enable SPI Master mode
|
DDRH |= (1<<PH2); // SPI clock XCK2 (PH2) as output. This enable SPI Master mode
|
||||||
// Set MSPI mode of operation and SPI data mode 0.
|
// Set MSPI mode of operation and SPI data mode 0.
|
||||||
UCSR2C = (1<<UMSEL21)|(1<<UMSEL20); //|(0<<UCPHA2)|(0<<UCPOL2);
|
UCSR2C = (1<<UMSEL21)|(1<<UMSEL20); //|(0<<UCPHA2)|(0<<UCPOL2);
|
||||||
// Enable receiver and transmitter.
|
// Enable receiver and transmitter.
|
||||||
UCSR2B = (1<<RXEN2)|(1<<TXEN2);
|
UCSR2B = (1<<RXEN2)|(1<<TXEN2);
|
||||||
// Set Baud rate
|
// Set Baud rate
|
||||||
UBRR2 = 2; // SPI clock running at 2.6MHz
|
UBRR2 = 2; // SPI clock running at 2.6MHz
|
||||||
|
|
||||||
|
|
||||||
// Enable Timer2 Overflow interrupt to capture ADC data
|
// Enable Timer2 Overflow interrupt to capture ADC data
|
||||||
TIMSK2 = 0; // Disable interrupts
|
TIMSK2 = 0; // Disable interrupts
|
||||||
TCCR2A = 0; // normal counting mode
|
TCCR2A = 0; // normal counting mode
|
||||||
TCCR2B = _BV(CS21)|_BV(CS22); // Set prescaler of 256
|
TCCR2B = _BV(CS21)|_BV(CS22); // Set prescaler of 256
|
||||||
TCNT2 = 0;
|
TCNT2 = 0;
|
||||||
TIFR2 = _BV(TOV2); // clear pending interrupts;
|
TIFR2 = _BV(TOV2); // clear pending interrupts;
|
||||||
TIMSK2 = _BV(TOIE2) ; // enable the overflow interrupt
|
TIMSK2 = _BV(TOIE2) ; // enable the overflow interrupt
|
||||||
}
|
}
|
||||||
|
|
||||||
// Read one channel value
|
// Read one channel value
|
||||||
|
@ -118,12 +136,12 @@ int APM_ADC_Class::Ch(unsigned char ch_num)
|
||||||
{
|
{
|
||||||
int result;
|
int result;
|
||||||
|
|
||||||
cli(); // We stop interrupts to read the variables
|
cli(); // We stop interrupts to read the variables
|
||||||
if (adc_counter[ch_num]>0)
|
if (adc_counter[ch_num]>0)
|
||||||
result = adc_value[ch_num]/adc_counter[ch_num];
|
result = adc_value[ch_num]/adc_counter[ch_num]);
|
||||||
else
|
else
|
||||||
result = 0;
|
result = 0;
|
||||||
adc_value[ch_num] = 0; // Initialize for next reading
|
adc_value[ch_num] = 0; // Initialize for next reading
|
||||||
adc_counter[ch_num] = 0;
|
adc_counter[ch_num] = 0;
|
||||||
sei();
|
sei();
|
||||||
return(result);
|
return(result);
|
||||||
|
|
|
@ -1,13 +1,13 @@
|
||||||
#ifndef APM_ADC_h
|
#ifndef APM_ADC_h
|
||||||
#define APM_ADC_h
|
#define APM_ADC_h
|
||||||
|
|
||||||
#define bit_set(p,m) ((p) |= (1<<m))
|
#define bit_set(p,m) ((p) |= ( 1<<m))
|
||||||
#define bit_clear(p,m) ((p) &= ~(1<<m))
|
#define bit_clear(p,m) ((p) &= ~(1<<m))
|
||||||
|
|
||||||
// We use Serial Port 2 in SPI Mode
|
// We use Serial Port 2 in SPI Mode
|
||||||
#define ADC_DATAOUT 51 // MOSI
|
#define ADC_DATAOUT 51 // MOSI
|
||||||
#define ADC_DATAIN 50 // MISO
|
#define ADC_DATAIN 50 // MISO
|
||||||
#define ADC_SPICLOCK 52 // SCK
|
#define ADC_SPICLOCK 52 // SCK
|
||||||
#define ADC_CHIP_SELECT 33 // PC4 9 // PH6 Puerto:0x08 Bit mask : 0x40
|
#define ADC_CHIP_SELECT 33 // PC4 9 // PH6 Puerto:0x08 Bit mask : 0x40
|
||||||
|
|
||||||
class APM_ADC_Class
|
class APM_ADC_Class
|
||||||
|
@ -16,7 +16,7 @@ class APM_ADC_Class
|
||||||
public:
|
public:
|
||||||
APM_ADC_Class(); // Constructor
|
APM_ADC_Class(); // Constructor
|
||||||
void Init();
|
void Init();
|
||||||
int Ch(unsigned char ch_num);
|
float Ch(unsigned char ch_num); // HJI Changed from int to float
|
||||||
};
|
};
|
||||||
|
|
||||||
extern APM_ADC_Class APM_ADC;
|
extern APM_ADC_Class APM_ADC;
|
||||||
|
|
Loading…
Reference in New Issue