mirror of https://github.com/ArduPilot/ardupilot
correct typo
git-svn-id: https://arducopter.googlecode.com/svn/trunk@450 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
72d031b4b5
commit
8a4b060873
|
@ -138,7 +138,7 @@ int APM_ADC_Class::Ch(unsigned char ch_num)
|
||||||
|
|
||||||
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
|
||||||
|
|
|
@ -16,7 +16,7 @@ class APM_ADC_Class
|
||||||
public:
|
public:
|
||||||
APM_ADC_Class(); // Constructor
|
APM_ADC_Class(); // Constructor
|
||||||
void Init();
|
void Init();
|
||||||
float Ch(unsigned char ch_num); // HJI Changed from int to float
|
int Ch(unsigned char ch_num);
|
||||||
};
|
};
|
||||||
|
|
||||||
extern APM_ADC_Class APM_ADC;
|
extern APM_ADC_Class APM_ADC;
|
||||||
|
|
Loading…
Reference in New Issue