AP_HAL_AVR: AnalogIn uses only sized int types

This commit is contained in:
Pat Hickey 2012-12-06 10:57:59 -08:00 committed by Andrew Tridgell
parent de4adefe4e
commit 2ee214ee36
2 changed files with 16 additions and 16 deletions

View File

@ -31,7 +31,7 @@ public:
* implements read(). */
float read_average();
int get_pin() { return _pin; };
int16_t get_pin() { return _pin; };
private:
/* _sum_count and _sum are used from both an interrupt and normal thread */
volatile uint8_t _sum_count;
@ -49,18 +49,18 @@ class AP_HAL_AVR::AVRAnalogIn : public AP_HAL::AnalogIn {
public:
AVRAnalogIn();
void init(void* ap_hal_scheduler);
AP_HAL::AnalogSource* channel(int n);
AP_HAL::AnalogSource* channel(int n, float prescale);
AP_HAL::AnalogSource* channel(int16_t n);
AP_HAL::AnalogSource* channel(int16_t n, float prescale);
protected:
static ADCSource* _find_or_create_channel(int num, float scale);
static ADCSource* _create_channel(int num, float scale);
static ADCSource* _find_or_create_channel(int16_t num, float scale);
static ADCSource* _create_channel(int16_t num, float scale);
static void _register_channel(ADCSource*);
static void _timer_event(uint32_t);
static ADCSource* _channels[AVR_INPUT_MAX_CHANNELS];
static int _num_channels;
static int _active_channel;
static int _channel_repeat_count;
static int16_t _num_channels;
static int16_t _active_channel;
static int16_t _channel_repeat_count;
private:
ADCSource _vcc;

View File

@ -14,9 +14,9 @@ extern const AP_HAL::HAL& hal;
/* Static variable instances */
ADCSource* AVRAnalogIn::_channels[AVR_INPUT_MAX_CHANNELS] = {NULL};
int AVRAnalogIn::_num_channels = 0;
int AVRAnalogIn::_active_channel = 0;
int AVRAnalogIn::_channel_repeat_count = 0;
int16_t AVRAnalogIn::_num_channels = 0;
int16_t AVRAnalogIn::_active_channel = 0;
int16_t AVRAnalogIn::_channel_repeat_count = 0;
AVRAnalogIn::AVRAnalogIn() :
_vcc(ADCSource(ANALOG_INPUT_BOARD_VCC))
@ -29,8 +29,8 @@ void AVRAnalogIn::init(void* machtnichts) {
_register_channel(&_vcc);
}
ADCSource* AVRAnalogIn::_find_or_create_channel(int pin, float scale) {
for(int i = 0; i < _num_channels; i++) {
ADCSource* AVRAnalogIn::_find_or_create_channel(int16_t pin, float scale) {
for(int16_t i = 0; i < _num_channels; i++) {
if (_channels[i]->_pin == pin) {
return _channels[i];
}
@ -38,7 +38,7 @@ ADCSource* AVRAnalogIn::_find_or_create_channel(int pin, float scale) {
return _create_channel(pin, scale);
}
ADCSource* AVRAnalogIn::_create_channel(int chnum, float scale) {
ADCSource* AVRAnalogIn::_create_channel(int16_t chnum, float scale) {
ADCSource *ch = new ADCSource(chnum, scale);
_register_channel(ch);
return ch;
@ -112,10 +112,10 @@ next_channel:
}
AP_HAL::AnalogSource* AVRAnalogIn::channel(int ch) {
AP_HAL::AnalogSource* AVRAnalogIn::channel(int16_t ch) {
return this->channel(ch, 1.0);
}
AP_HAL::AnalogSource* AVRAnalogIn::channel(int ch, float scale) {
AP_HAL::AnalogSource* AVRAnalogIn::channel(int16_t ch, float scale) {
if (ch == ANALOG_INPUT_BOARD_VCC) {
return &_vcc;
} else {