4 changed files with 168 additions and 0 deletions
@ -0,0 +1,114 @@
@@ -0,0 +1,114 @@
|
||||
#include <AP_HAL.h> |
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX |
||||
|
||||
#include "NavioAnalogIn.h" |
||||
|
||||
#define NAVIO_ANALOGIN_DEBUG 0 |
||||
#if NAVIO_ANALOGIN_DEBUG |
||||
#include <cstdio> |
||||
#define debug(fmt, args ...) do {hal.console->printf("%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); } while(0) |
||||
#define error(fmt, args ...) do {fprintf(stderr,"%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); } while(0) |
||||
#else |
||||
#define debug(fmt, args ...) |
||||
#define error(fmt, args ...) |
||||
#endif |
||||
|
||||
NavioAnalogSource::NavioAnalogSource(int16_t pin): |
||||
_pin(pin), |
||||
_value(0.0f) |
||||
{ |
||||
} |
||||
|
||||
void NavioAnalogSource::set_pin(uint8_t pin) |
||||
{ |
||||
if (_pin == pin) { |
||||
return; |
||||
} |
||||
_pin = pin; |
||||
} |
||||
|
||||
float NavioAnalogSource::read_average() |
||||
{
|
||||
return read_latest(); |
||||
} |
||||
|
||||
float NavioAnalogSource::read_latest() |
||||
{ |
||||
return _value; |
||||
} |
||||
|
||||
float NavioAnalogSource::voltage_average() |
||||
{ |
||||
return _value; |
||||
} |
||||
|
||||
float NavioAnalogSource::voltage_latest() |
||||
{ |
||||
return _value; |
||||
} |
||||
|
||||
float NavioAnalogSource::voltage_average_ratiometric() |
||||
{ |
||||
return _value; |
||||
} |
||||
|
||||
extern const AP_HAL::HAL& hal; |
||||
|
||||
NavioAnalogIn::NavioAnalogIn()
|
||||
{ |
||||
_adc = new AP_ADC_ADS1115(); |
||||
_channels_number = _adc->get_channels_number(); |
||||
} |
||||
|
||||
AP_HAL::AnalogSource* NavioAnalogIn::channel(int16_t pin) |
||||
{ |
||||
for (uint8_t j = 0; j < _channels_number; j++) { |
||||
if (_channels[j] == NULL) { |
||||
_channels[j] = new NavioAnalogSource(pin); |
||||
return _channels[j]; |
||||
} |
||||
} |
||||
|
||||
hal.console->println("Out of analog channels"); |
||||
return NULL; |
||||
} |
||||
|
||||
void NavioAnalogIn::init(void* implspecific) |
||||
{ |
||||
_adc->init(); |
||||
hal.scheduler->suspend_timer_procs(); |
||||
hal.scheduler->register_timer_process( AP_HAL_MEMBERPROC(&NavioAnalogIn::_update)); |
||||
hal.scheduler->resume_timer_procs(); |
||||
} |
||||
|
||||
void NavioAnalogIn::_update() |
||||
{ |
||||
if (hal.scheduler->micros() - _last_update_timestamp < 100000) { |
||||
return; |
||||
} |
||||
|
||||
adc_report_s reports[NAVIO_ADC_MAX_CHANNELS]; |
||||
|
||||
size_t rc = _adc->read(reports, 6); |
||||
|
||||
for (size_t i = 0; i < rc; i++) { |
||||
for (uint8_t j=0; j < rc; j++) { |
||||
NavioAnalogSource *source = _channels[j]; |
||||
|
||||
#if 0 |
||||
if (source != NULL) { |
||||
fprintf(stderr, "pin: %d id: %d data: %.3f\n", source->_pin, reports[i].id, reports[i].data); |
||||
} |
||||
#endif |
||||
|
||||
if (source != NULL && reports[i].id == source->_pin) { |
||||
source->_value = reports[i].data / 1000; |
||||
} |
||||
} |
||||
} |
||||
|
||||
_last_update_timestamp = hal.scheduler->micros(); |
||||
} |
||||
|
||||
#endif |
@ -0,0 +1,48 @@
@@ -0,0 +1,48 @@
|
||||
#ifndef __NavioAnalogIn_H__ |
||||
#define __NavioAnalogIn_H__ |
||||
|
||||
#include <AP_HAL_Linux.h> |
||||
#include <AP_ADC.h> |
||||
|
||||
#define NAVIO_ADC_MAX_CHANNELS 6 |
||||
|
||||
class NavioAnalogSource: public AP_HAL::AnalogSource { |
||||
public: |
||||
friend class NavioAnalogIn; |
||||
NavioAnalogSource(int16_t pin); |
||||
float read_average(); |
||||
float read_latest(); |
||||
void set_pin(uint8_t p); |
||||
void set_stop_pin(uint8_t p) {} |
||||
void set_settle_time(uint16_t settle_time_ms){} |
||||
float voltage_average(); |
||||
float voltage_latest(); |
||||
float voltage_average_ratiometric(); |
||||
private: |
||||
int16_t _pin; |
||||
float _value; |
||||
}; |
||||
|
||||
class NavioAnalogIn: public AP_HAL::AnalogIn { |
||||
public: |
||||
NavioAnalogIn(); |
||||
void init(void* implspecific); |
||||
AP_HAL::AnalogSource* channel(int16_t n); |
||||
|
||||
/* Board voltage is not available */ |
||||
float board_voltage(void)
|
||||
{
|
||||
return 0.0f;
|
||||
} |
||||
private: |
||||
AP_ADC_ADS1115 *_adc; |
||||
NavioAnalogSource *_channels[NAVIO_ADC_MAX_CHANNELS]; |
||||
|
||||
uint8_t _channels_number; |
||||
|
||||
void _update(); |
||||
|
||||
uint32_t _last_update_timestamp; |
||||
}; |
||||
|
||||
#endif |
Loading…
Reference in new issue