mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
ADC: change adc.Ch() to return a float
this gives us a bit more precision in airspeed measurement, and costs us virtually nothing as we are converting to float immediately after getting the value
This commit is contained in:
parent
43a53aa303
commit
47da2ec992
@ -27,7 +27,7 @@ class AP_ADC
|
||||
virtual void Init(AP_PeriodicProcess * scheduler = NULL) = 0;
|
||||
|
||||
/* read one channel value */
|
||||
virtual uint16_t Ch(uint8_t ch_num) = 0;
|
||||
virtual float Ch(uint8_t ch_num) = 0;
|
||||
|
||||
/* read 6 channels values as a set, used by IMU for 3 gyros
|
||||
and 3 accelerometeres.
|
||||
|
@ -162,7 +162,7 @@ void AP_ADC_ADS7844::Init( AP_PeriodicProcess * scheduler )
|
||||
}
|
||||
|
||||
// Read one channel value
|
||||
uint16_t AP_ADC_ADS7844::Ch(uint8_t ch_num)
|
||||
float AP_ADC_ADS7844::Ch(uint8_t ch_num)
|
||||
{
|
||||
uint16_t count;
|
||||
uint32_t sum;
|
||||
@ -178,7 +178,7 @@ uint16_t AP_ADC_ADS7844::Ch(uint8_t ch_num)
|
||||
_sum[ch_num] = 0;
|
||||
sei();
|
||||
|
||||
return sum/count;
|
||||
return ((float)sum)/count;
|
||||
}
|
||||
|
||||
// Read 6 channel values
|
||||
|
@ -24,7 +24,7 @@ class AP_ADC_ADS7844 : public AP_ADC
|
||||
void Init( AP_PeriodicProcess * scheduler );
|
||||
|
||||
// Read 1 sensor value
|
||||
uint16_t Ch(unsigned char ch_num);
|
||||
float Ch(unsigned char ch_num);
|
||||
|
||||
// Read 6 sensors at once
|
||||
uint32_t Ch6(const uint8_t *channel_numbers, uint16_t *result);
|
||||
|
@ -44,7 +44,7 @@ void AP_ADC_HIL::Init( AP_PeriodicProcess * scheduler )
|
||||
}
|
||||
|
||||
// Read one channel value
|
||||
uint16_t AP_ADC_HIL::Ch(unsigned char ch_num)
|
||||
float AP_ADC_HIL::Ch(unsigned char ch_num)
|
||||
{
|
||||
return adcValue[ch_num];
|
||||
}
|
||||
|
@ -32,7 +32,7 @@ class AP_ADC_HIL : public AP_ADC
|
||||
|
||||
///
|
||||
// Read the sensor, part of public AP_ADC interface
|
||||
uint16_t Ch(unsigned char ch_num);
|
||||
float Ch(unsigned char ch_num);
|
||||
|
||||
///
|
||||
// Read 6 sensors at once
|
||||
|
Loading…
Reference in New Issue
Block a user