Added ability to grab an unfiltered value from the ADC

git-svn-id: https://arducopter.googlecode.com/svn/trunk@2963 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
jasonshort 2011-07-30 20:33:45 +00:00
parent 74edb558f4
commit 5c3837757a
5 changed files with 25 additions and 9 deletions

View File

@ -22,6 +22,7 @@ class AP_ADC
AP_ADC() {}; // Constructor
virtual void Init() {};
virtual int Ch(unsigned char ch_num) = 0;
virtual int Ch_raw(unsigned char ch_num) = 0;
private:
};

View File

@ -156,3 +156,9 @@ int AP_ADC_ADS7844::Ch(unsigned char ch_num)
return(result);
}
// Read one channel value
int AP_ADC_ADS7844::Ch_raw(unsigned char ch_num)
{
return _filter[ch_num][_filter_index]; // close enough
}

View File

@ -19,7 +19,8 @@ class AP_ADC_ADS7844 : public AP_ADC
public:
AP_ADC_ADS7844(); // Constructor
void Init();
int Ch(unsigned char ch_num);
int Ch(unsigned char ch_num);
int Ch_raw(unsigned char ch_num);
private:
};

View File

@ -12,12 +12,12 @@
version 2.1 of the License, or (at your option) any later version.
*/
const uint8_t AP_ADC_HIL::sensors[6] = {1,2,0,4,5,6};
const uint8_t AP_ADC_HIL::sensors[6] = {1,2,0,4,5,6};
const int8_t AP_ADC_HIL::sensorSign[6] = { 1, -1, -1,-1, 1, 1};
const float AP_ADC_HIL::gyroBias[3] = {1665,1665,1665};
const float AP_ADC_HIL::accelBias[3] = {2025,2025,2025};
// gyroScale = 1/[GyroGain*pi/180] GyroGains (0.4,0.41,0.41)
const float AP_ADC_HIL::gyroScale[3] = {143.239, 139.746, 139.746};
const float AP_ADC_HIL::gyroScale[3] = {143.239, 139.746, 139.746};
const float AP_ADC_HIL::accelScale[3] = {418,418,418}; // adcPerG
AP_ADC_HIL::AP_ADC_HIL()
@ -42,7 +42,12 @@ void AP_ADC_HIL::Init(void)
}
// Read one channel value
int AP_ADC_HIL::Ch(unsigned char ch_num)
int AP_ADC_HIL::Ch(unsigned char ch_num)
{
return adcValue[ch_num];
}
// Read one channel value
int AP_ADC_HIL::Ch_raw(unsigned char ch_num)
{
return adcValue[ch_num];
}

View File

@ -32,7 +32,10 @@ class AP_ADC_HIL : public AP_ADC
///
// Read the sensor, part of public AP_ADC interface
int Ch(unsigned char ch_num);
int Ch(unsigned char ch_num);
///
// Read the sensor, part of public AP_ADC interface
int Ch_raw(unsigned char ch_num);
///
// Set the adc raw values given the current rotations rates,
@ -50,10 +53,10 @@ class AP_ADC_HIL : public AP_ADC
// sensor constants
// constants declared in cpp file
// @see AP_ADC_HIL.cpp
static const uint8_t sensors[6];
static const float gyroBias[3];
static const uint8_t sensors[6];
static const float gyroBias[3];
static const float gyroScale[3];
static const float accelBias[3];
static const float accelBias[3];
static const float accelScale[3];
static const int8_t sensorSign[6];
@ -78,7 +81,7 @@ class AP_ADC_HIL : public AP_ADC
///
// Sets the differential pressure adc channel
// TODO: implement
void setPressure(int16_t val) {}
void setPressure(int16_t val) {}
///
// Sets the gyro temp adc channel