AP_HAL: added board_voltage AnalogIn method

this makes it easier to get the board voltage from any library,
without having to allocate another analog channel object
This commit is contained in:
Andrew Tridgell 2014-02-13 17:07:32 +11:00
parent aa5a098adb
commit 1849db7074
11 changed files with 39 additions and 11 deletions

View File

@ -41,6 +41,9 @@ class AP_HAL::AnalogIn {
public:
virtual void init(void* implspecific) = 0;
virtual AP_HAL::AnalogSource* channel(int16_t n) = 0;
// board 5V rail voltage in volts
virtual float board_voltage(void) = 0;
};
#define ANALOG_INPUT_BOARD_VCC 254

View File

@ -68,6 +68,7 @@ public:
AVRAnalogIn();
void init(void* ap_hal_scheduler);
AP_HAL::AnalogSource* channel(int16_t n);
float board_voltage(void);
protected:
ADCSource* _create_channel(int16_t num);

View File

@ -114,4 +114,12 @@ AP_HAL::AnalogSource* AVRAnalogIn::channel(int16_t ch)
}
}
/*
return board voltage in volts
*/
float AVRAnalogIn::board_voltage(void)
{
return _vcc.voltage_latest();
}
#endif

View File

@ -38,7 +38,7 @@ public:
}
void init(void* ap_hal_scheduler);
AP_HAL::AnalogSource* channel(int16_t n);
float board_voltage(void) { return 5.0f; }
private:
static ADCSource* _channels[SITL_INPUT_MAX_CHANNELS];
SITL_State *_sitlState;

View File

@ -41,4 +41,7 @@ AP_HAL::AnalogSource* EmptyAnalogIn::channel(int16_t n) {
return new EmptyAnalogSource(1.11);
}
float EmptyAnalogIn::board_voltage(void)
{
return 0;
}

View File

@ -24,5 +24,6 @@ public:
EmptyAnalogIn();
void init(void* implspecific);
AP_HAL::AnalogSource* channel(int16_t n);
float board_voltage(void);
};
#endif // __AP_HAL_EMPTY_ANALOGIN_H__

View File

@ -126,4 +126,9 @@ AP_HAL::AnalogSource* FLYMAPLEAnalogIn::channel(int16_t ch)
}
}
float FLYMAPLEAnalogIn::board_voltage(void)
{
return _vcc.voltage_latest();
}
#endif

View File

@ -84,6 +84,7 @@ public:
FLYMAPLEAnalogIn();
void init(void* implspecific);
AP_HAL::AnalogSource* channel(int16_t n);
float board_voltage(void);
protected:
FLYMAPLEAnalogSource* _create_channel(int16_t num);

View File

@ -24,5 +24,9 @@ public:
LinuxAnalogIn();
void init(void* implspecific);
AP_HAL::AnalogSource* channel(int16_t n);
// we don't yet know how to get the board voltage
float board_voltage(void) { return 0.0f; }
};
#endif // __AP_HAL_LINUX_ANALOGIN_H__

View File

@ -160,16 +160,16 @@ void PX4AnalogSource::set_pin(uint8_t pin)
/*
apply a reading in ADC counts
*/
void PX4AnalogSource::_add_value(float v, uint16_t vcc5V_mV)
void PX4AnalogSource::_add_value(float v, float vcc5V)
{
_latest_value = v;
_sum_value += v;
if (vcc5V_mV == 0) {
if (vcc5V < 3.0f) {
_sum_ratiometric += v;
} else {
// this compensates for changes in the 5V rail relative to the
// 3.3V reference used by the ADC.
_sum_ratiometric += v * 5000 / vcc5V_mV;
_sum_ratiometric += v * 5.0f / vcc5V;
}
_sum_count++;
if (_sum_count == 254) {
@ -180,7 +180,8 @@ void PX4AnalogSource::_add_value(float v, uint16_t vcc5V_mV)
}
PX4AnalogIn::PX4AnalogIn()
PX4AnalogIn::PX4AnalogIn() :
_board_voltage(0)
{}
void PX4AnalogIn::init(void* machtnichts)
@ -211,14 +212,13 @@ void PX4AnalogIn::_timer_tick(void)
/* read all channels available */
int ret = read(_adc_fd, &buf_adc, sizeof(buf_adc));
if (ret > 0) {
uint16_t vcc5V_mV = 0;
// match the incoming channels to the currently active pins
for (uint8_t i=0; i<ret/sizeof(buf_adc[0]); i++) {
#ifdef CONFIG_ARCH_BOARD_PX4FMU_V2
if (buf_adc[i].am_channel == 4) {
// record the Vcc value for later use in
// voltage_average_ratiometric()
vcc5V_mV = buf_adc[i].am_data * 6600 / 4096;
_board_voltage = buf_adc[i].am_data * 6.6f / 4096;
}
#endif
}
@ -229,7 +229,7 @@ void PX4AnalogIn::_timer_tick(void)
for (uint8_t j=0; j<PX4_ANALOG_MAX_CHANNELS; j++) {
PX4::PX4AnalogSource *c = _channels[j];
if (c != NULL && buf_adc[i].am_channel == c->_pin) {
c->_add_value(buf_adc[i].am_data, vcc5V_mV);
c->_add_value(buf_adc[i].am_data, _board_voltage);
}
}
}

View File

@ -46,7 +46,7 @@ private:
uint8_t _sum_count;
float _sum_value;
float _sum_ratiometric;
void _add_value(float v, uint16_t vcc5V_mV);
void _add_value(float v, float vcc5V);
float _pin_scaler();
};
@ -56,6 +56,7 @@ public:
void init(void* implspecific);
AP_HAL::AnalogSource* channel(int16_t pin);
void _timer_tick(void);
float board_voltage(void) { return _board_voltage; }
private:
int _adc_fd;
@ -65,5 +66,6 @@ private:
uint64_t _servorail_timestamp;
PX4::PX4AnalogSource* _channels[PX4_ANALOG_MAX_CHANNELS];
uint32_t _last_run;
float _board_voltage;
};
#endif // __AP_HAL_PX4_ANALOGIN_H__