mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-09 01:13:57 -04:00
AP_HAL_AVR: AnalogIn uses only sized int types
This commit is contained in:
parent
de4adefe4e
commit
2ee214ee36
@ -31,7 +31,7 @@ public:
|
|||||||
* implements read(). */
|
* implements read(). */
|
||||||
float read_average();
|
float read_average();
|
||||||
|
|
||||||
int get_pin() { return _pin; };
|
int16_t get_pin() { return _pin; };
|
||||||
private:
|
private:
|
||||||
/* _sum_count and _sum are used from both an interrupt and normal thread */
|
/* _sum_count and _sum are used from both an interrupt and normal thread */
|
||||||
volatile uint8_t _sum_count;
|
volatile uint8_t _sum_count;
|
||||||
@ -49,18 +49,18 @@ class AP_HAL_AVR::AVRAnalogIn : public AP_HAL::AnalogIn {
|
|||||||
public:
|
public:
|
||||||
AVRAnalogIn();
|
AVRAnalogIn();
|
||||||
void init(void* ap_hal_scheduler);
|
void init(void* ap_hal_scheduler);
|
||||||
AP_HAL::AnalogSource* channel(int n);
|
AP_HAL::AnalogSource* channel(int16_t n);
|
||||||
AP_HAL::AnalogSource* channel(int n, float prescale);
|
AP_HAL::AnalogSource* channel(int16_t n, float prescale);
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
static ADCSource* _find_or_create_channel(int num, float scale);
|
static ADCSource* _find_or_create_channel(int16_t num, float scale);
|
||||||
static ADCSource* _create_channel(int num, float scale);
|
static ADCSource* _create_channel(int16_t num, float scale);
|
||||||
static void _register_channel(ADCSource*);
|
static void _register_channel(ADCSource*);
|
||||||
static void _timer_event(uint32_t);
|
static void _timer_event(uint32_t);
|
||||||
static ADCSource* _channels[AVR_INPUT_MAX_CHANNELS];
|
static ADCSource* _channels[AVR_INPUT_MAX_CHANNELS];
|
||||||
static int _num_channels;
|
static int16_t _num_channels;
|
||||||
static int _active_channel;
|
static int16_t _active_channel;
|
||||||
static int _channel_repeat_count;
|
static int16_t _channel_repeat_count;
|
||||||
|
|
||||||
private:
|
private:
|
||||||
ADCSource _vcc;
|
ADCSource _vcc;
|
||||||
|
@ -14,9 +14,9 @@ extern const AP_HAL::HAL& hal;
|
|||||||
|
|
||||||
/* Static variable instances */
|
/* Static variable instances */
|
||||||
ADCSource* AVRAnalogIn::_channels[AVR_INPUT_MAX_CHANNELS] = {NULL};
|
ADCSource* AVRAnalogIn::_channels[AVR_INPUT_MAX_CHANNELS] = {NULL};
|
||||||
int AVRAnalogIn::_num_channels = 0;
|
int16_t AVRAnalogIn::_num_channels = 0;
|
||||||
int AVRAnalogIn::_active_channel = 0;
|
int16_t AVRAnalogIn::_active_channel = 0;
|
||||||
int AVRAnalogIn::_channel_repeat_count = 0;
|
int16_t AVRAnalogIn::_channel_repeat_count = 0;
|
||||||
|
|
||||||
AVRAnalogIn::AVRAnalogIn() :
|
AVRAnalogIn::AVRAnalogIn() :
|
||||||
_vcc(ADCSource(ANALOG_INPUT_BOARD_VCC))
|
_vcc(ADCSource(ANALOG_INPUT_BOARD_VCC))
|
||||||
@ -29,8 +29,8 @@ void AVRAnalogIn::init(void* machtnichts) {
|
|||||||
_register_channel(&_vcc);
|
_register_channel(&_vcc);
|
||||||
}
|
}
|
||||||
|
|
||||||
ADCSource* AVRAnalogIn::_find_or_create_channel(int pin, float scale) {
|
ADCSource* AVRAnalogIn::_find_or_create_channel(int16_t pin, float scale) {
|
||||||
for(int i = 0; i < _num_channels; i++) {
|
for(int16_t i = 0; i < _num_channels; i++) {
|
||||||
if (_channels[i]->_pin == pin) {
|
if (_channels[i]->_pin == pin) {
|
||||||
return _channels[i];
|
return _channels[i];
|
||||||
}
|
}
|
||||||
@ -38,7 +38,7 @@ ADCSource* AVRAnalogIn::_find_or_create_channel(int pin, float scale) {
|
|||||||
return _create_channel(pin, 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);
|
ADCSource *ch = new ADCSource(chnum, scale);
|
||||||
_register_channel(ch);
|
_register_channel(ch);
|
||||||
return 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);
|
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) {
|
if (ch == ANALOG_INPUT_BOARD_VCC) {
|
||||||
return &_vcc;
|
return &_vcc;
|
||||||
} else {
|
} else {
|
||||||
|
Loading…
Reference in New Issue
Block a user