|
|
|
@ -6,8 +6,7 @@
@@ -6,8 +6,7 @@
|
|
|
|
|
|
|
|
|
|
extern const AP_HAL::HAL& hal; |
|
|
|
|
|
|
|
|
|
const char* AnalogSource_IIO::analog_sources[IIO_ANALOG_IN_COUNT] = { |
|
|
|
|
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_PXF |
|
|
|
|
const char* AnalogSource_IIO::analog_sources[] = { |
|
|
|
|
"in_voltage0_raw", |
|
|
|
|
"in_voltage1_raw", |
|
|
|
|
"in_voltage2_raw", |
|
|
|
@ -16,14 +15,12 @@ const char* AnalogSource_IIO::analog_sources[IIO_ANALOG_IN_COUNT] = {
@@ -16,14 +15,12 @@ const char* AnalogSource_IIO::analog_sources[IIO_ANALOG_IN_COUNT] = {
|
|
|
|
|
"in_voltage5_raw", |
|
|
|
|
"in_voltage6_raw", |
|
|
|
|
"in_voltage7_raw", |
|
|
|
|
#else |
|
|
|
|
"in_voltage0_raw", |
|
|
|
|
#endif |
|
|
|
|
}; |
|
|
|
|
|
|
|
|
|
AnalogSource_IIO::AnalogSource_IIO(int16_t pin, float initial_value) : |
|
|
|
|
AnalogSource_IIO::AnalogSource_IIO(int16_t pin, float initial_value, float voltage_scaling) : |
|
|
|
|
_pin(pin), |
|
|
|
|
_value(initial_value), |
|
|
|
|
_voltage_scaling(voltage_scaling), |
|
|
|
|
_sum_value(0), |
|
|
|
|
_sum_count(0), |
|
|
|
|
_pin_fd(-1) |
|
|
|
@ -35,15 +32,12 @@ AnalogSource_IIO::AnalogSource_IIO(int16_t pin, float initial_value) :
@@ -35,15 +32,12 @@ AnalogSource_IIO::AnalogSource_IIO(int16_t pin, float initial_value) :
|
|
|
|
|
void AnalogSource_IIO::init_pins(void) |
|
|
|
|
{ |
|
|
|
|
char buf[100]; |
|
|
|
|
for (int i=0; i < IIO_ANALOG_IN_COUNT; i++) { |
|
|
|
|
for (unsigned int i = 0; i < ARRAY_SIZE(AnalogSource_IIO::analog_sources); i++) { |
|
|
|
|
// Construct the path by appending strings
|
|
|
|
|
strncpy(buf, IIO_ANALOG_IN_DIR, sizeof(buf)); |
|
|
|
|
strncat(buf, AnalogSource_IIO::analog_sources[i], sizeof(buf) - strlen(buf) -1); |
|
|
|
|
strncat(buf, AnalogSource_IIO::analog_sources[i], sizeof(buf) - strlen(buf) - 1); |
|
|
|
|
|
|
|
|
|
fd_analog_sources[i] = open(buf, O_RDONLY | O_NONBLOCK); |
|
|
|
|
if (fd_analog_sources[i] == -1) { |
|
|
|
|
::printf("Failed to open analog pin %s\n", buf); |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
@ -55,39 +49,6 @@ void AnalogSource_IIO::select_pin(void)
@@ -55,39 +49,6 @@ void AnalogSource_IIO::select_pin(void)
|
|
|
|
|
_pin_fd = fd_analog_sources[_pin]; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
/*
|
|
|
|
|
reopens an analog source (by closing and opening it again) and selects it |
|
|
|
|
*/ |
|
|
|
|
void AnalogSource_IIO::reopen_pin(void) |
|
|
|
|
{ |
|
|
|
|
char buf[100]; |
|
|
|
|
|
|
|
|
|
if (fd_analog_sources[_pin] != -1) { |
|
|
|
|
close(fd_analog_sources[_pin]); |
|
|
|
|
fd_analog_sources[_pin] = -1; |
|
|
|
|
_pin_fd = -1; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
if (_pin < 0) { |
|
|
|
|
return; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
if (_pin > IIO_ANALOG_IN_COUNT) { |
|
|
|
|
// invalid pin
|
|
|
|
|
return; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// Construct the path by appending strings
|
|
|
|
|
strncpy(buf, IIO_ANALOG_IN_DIR, sizeof(buf)); |
|
|
|
|
strncat(buf, AnalogSource_IIO::analog_sources[_pin], sizeof(buf) - strlen(buf) - 1); |
|
|
|
|
|
|
|
|
|
fd_analog_sources[_pin] = open(buf, O_RDONLY | O_NONBLOCK); |
|
|
|
|
if (fd_analog_sources[_pin] == -1) { |
|
|
|
|
::printf("Failed to open analog pin %s\n", buf); |
|
|
|
|
} |
|
|
|
|
_pin_fd = fd_analog_sources[_pin]; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
float AnalogSource_IIO::read_average() |
|
|
|
|
{ |
|
|
|
|
read_latest(); |
|
|
|
@ -96,9 +57,7 @@ float AnalogSource_IIO::read_average()
@@ -96,9 +57,7 @@ float AnalogSource_IIO::read_average()
|
|
|
|
|
} |
|
|
|
|
hal.scheduler->suspend_timer_procs(); |
|
|
|
|
_value = _sum_value / _sum_count; |
|
|
|
|
// _value_ratiometric = _sum_ratiometric / _sum_count;
|
|
|
|
|
_sum_value = 0; |
|
|
|
|
// _sum_ratiometric = 0;
|
|
|
|
|
_sum_count = 0; |
|
|
|
|
hal.scheduler->resume_timer_procs(); |
|
|
|
|
return _value; |
|
|
|
@ -114,12 +73,8 @@ float AnalogSource_IIO::read_latest()
@@ -114,12 +73,8 @@ float AnalogSource_IIO::read_latest()
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
memset(sbuf, 0, sizeof(sbuf)); |
|
|
|
|
pread(_pin_fd, sbuf, sizeof(sbuf)-1, 0); |
|
|
|
|
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_PXF |
|
|
|
|
_latest = atoi(sbuf) * BBB_VOLTAGE_SCALING; |
|
|
|
|
#else |
|
|
|
|
_latest = atoi(sbuf); |
|
|
|
|
#endif |
|
|
|
|
pread(_pin_fd, sbuf, sizeof(sbuf) - 1, 0); |
|
|
|
|
_latest = atoi(sbuf) * _voltage_scaling; |
|
|
|
|
_sum_value += _latest; |
|
|
|
|
_sum_count++; |
|
|
|
|
|
|
|
|
@ -147,12 +102,10 @@ void AnalogSource_IIO::set_pin(uint8_t pin)
@@ -147,12 +102,10 @@ void AnalogSource_IIO::set_pin(uint8_t pin)
|
|
|
|
|
hal.scheduler->suspend_timer_procs(); |
|
|
|
|
_pin = pin; |
|
|
|
|
_sum_value = 0; |
|
|
|
|
// _sum_ratiometric = 0;
|
|
|
|
|
_sum_count = 0; |
|
|
|
|
_latest = 0; |
|
|
|
|
_value = 0; |
|
|
|
|
select_pin(); |
|
|
|
|
// _value_ratiometric = 0;
|
|
|
|
|
hal.scheduler->resume_timer_procs(); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
@ -170,7 +123,7 @@ void AnalogIn_IIO::init()
@@ -170,7 +123,7 @@ void AnalogIn_IIO::init()
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
AP_HAL::AnalogSource* AnalogIn_IIO::channel(int16_t pin) { |
|
|
|
|
return new AnalogSource_IIO(pin, 0); |
|
|
|
|
return new AnalogSource_IIO(pin, 0.0f, IIO_VOLTAGE_SCALING); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
#endif // CONFIG_HAL_BOARD
|
|
|
|
|