mirror of https://github.com/ArduPilot/ardupilot
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:
parent
74edb558f4
commit
5c3837757a
|
@ -22,6 +22,7 @@ class AP_ADC
|
||||||
AP_ADC() {}; // Constructor
|
AP_ADC() {}; // Constructor
|
||||||
virtual void Init() {};
|
virtual void Init() {};
|
||||||
virtual int Ch(unsigned char ch_num) = 0;
|
virtual int Ch(unsigned char ch_num) = 0;
|
||||||
|
virtual int Ch_raw(unsigned char ch_num) = 0;
|
||||||
private:
|
private:
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
|
@ -156,3 +156,9 @@ int AP_ADC_ADS7844::Ch(unsigned char ch_num)
|
||||||
|
|
||||||
return(result);
|
return(result);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// Read one channel value
|
||||||
|
int AP_ADC_ADS7844::Ch_raw(unsigned char ch_num)
|
||||||
|
{
|
||||||
|
return _filter[ch_num][_filter_index]; // close enough
|
||||||
|
}
|
||||||
|
|
|
@ -19,7 +19,8 @@ class AP_ADC_ADS7844 : public AP_ADC
|
||||||
public:
|
public:
|
||||||
AP_ADC_ADS7844(); // Constructor
|
AP_ADC_ADS7844(); // Constructor
|
||||||
void Init();
|
void Init();
|
||||||
int Ch(unsigned char ch_num);
|
int Ch(unsigned char ch_num);
|
||||||
|
int Ch_raw(unsigned char ch_num);
|
||||||
|
|
||||||
private:
|
private:
|
||||||
};
|
};
|
||||||
|
|
|
@ -46,6 +46,11 @@ int AP_ADC_HIL::Ch(unsigned char ch_num)
|
||||||
{
|
{
|
||||||
return adcValue[ch_num];
|
return adcValue[ch_num];
|
||||||
}
|
}
|
||||||
|
// Read one channel value
|
||||||
|
int AP_ADC_HIL::Ch_raw(unsigned char ch_num)
|
||||||
|
{
|
||||||
|
return adcValue[ch_num];
|
||||||
|
}
|
||||||
|
|
||||||
// Set one channel value
|
// Set one channel value
|
||||||
void AP_ADC_HIL::setHIL(int16_t p, int16_t q, int16_t r, int16_t gyroTemp,
|
void AP_ADC_HIL::setHIL(int16_t p, int16_t q, int16_t r, int16_t gyroTemp,
|
||||||
|
|
|
@ -33,6 +33,9 @@ class AP_ADC_HIL : public AP_ADC
|
||||||
///
|
///
|
||||||
// Read the sensor, part of public AP_ADC interface
|
// 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,
|
// Set the adc raw values given the current rotations rates,
|
||||||
|
|
Loading…
Reference in New Issue