2016-01-25 15:13:48 -04:00
|
|
|
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
2016-01-11 12:45:09 -04:00
|
|
|
#pragma once
|
2015-08-20 09:21:26 -03:00
|
|
|
|
|
|
|
#include "AP_HAL_Linux.h"
|
2015-12-30 19:38:56 -04:00
|
|
|
#include <AP_ADC/AP_ADC.h>
|
|
|
|
|
2015-08-20 09:21:26 -03:00
|
|
|
#include <fcntl.h>
|
|
|
|
#include <unistd.h>
|
|
|
|
|
2016-01-07 12:37:46 -04:00
|
|
|
#define IIO_ANALOG_IN_COUNT 8
|
|
|
|
#define IIO_ANALOG_IN_DIR "/sys/bus/iio/devices/iio:device0/"
|
2016-02-17 23:09:50 -04:00
|
|
|
|
2016-01-25 15:13:48 -04:00
|
|
|
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_PXF
|
|
|
|
// Note that echo BB-ADC cape should be loaded
|
|
|
|
#define IIO_VOLTAGE_SCALING 0.00142602816
|
|
|
|
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BBBMINI
|
2016-02-16 15:41:58 -04:00
|
|
|
#define IIO_VOLTAGE_SCALING 3.0*1.8/4095.0
|
2016-02-17 23:09:50 -04:00
|
|
|
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_MINLURE
|
|
|
|
#define IIO_VOLTAGE_SCALING 2.0 / 1000
|
2016-01-07 12:37:46 -04:00
|
|
|
#else
|
2016-01-25 15:13:48 -04:00
|
|
|
#define IIO_VOLTAGE_SCALING 1.0
|
2016-01-07 12:37:46 -04:00
|
|
|
#endif
|
2015-08-20 09:21:26 -03:00
|
|
|
|
2016-01-11 12:48:07 -04:00
|
|
|
class AnalogSource_IIO : public AP_HAL::AnalogSource {
|
2015-08-20 09:21:26 -03:00
|
|
|
public:
|
2016-01-11 12:48:07 -04:00
|
|
|
friend class AnalogIn_IIO;
|
2016-01-25 15:13:48 -04:00
|
|
|
AnalogSource_IIO(int16_t pin, float initial_value, float voltage_scaling);
|
2015-08-20 09:21:26 -03:00
|
|
|
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() { return voltage_average(); }
|
|
|
|
private:
|
|
|
|
float _value;
|
|
|
|
float _latest;
|
|
|
|
float _sum_value;
|
2016-01-25 15:13:48 -04:00
|
|
|
float _voltage_scaling;
|
2015-08-20 09:21:26 -03:00
|
|
|
uint8_t _sum_count;
|
|
|
|
int16_t _pin;
|
2016-01-11 12:45:09 -04:00
|
|
|
int _pin_fd;
|
2016-01-07 14:22:50 -04:00
|
|
|
int fd_analog_sources[IIO_ANALOG_IN_COUNT];
|
2015-08-20 09:21:26 -03:00
|
|
|
|
2016-01-07 13:52:53 -04:00
|
|
|
void init_pins(void);
|
2016-01-07 14:22:50 -04:00
|
|
|
void select_pin(void);
|
2015-08-20 09:21:26 -03:00
|
|
|
|
2016-01-25 15:13:48 -04:00
|
|
|
static const char *analog_sources[];
|
2015-08-20 09:21:26 -03:00
|
|
|
};
|
|
|
|
|
2016-01-11 12:48:07 -04:00
|
|
|
class AnalogIn_IIO : public AP_HAL::AnalogIn {
|
2015-08-20 09:21:26 -03:00
|
|
|
public:
|
2016-01-11 12:48:07 -04:00
|
|
|
AnalogIn_IIO();
|
2015-12-30 19:38:56 -04:00
|
|
|
void init();
|
2015-08-20 09:21:26 -03:00
|
|
|
AP_HAL::AnalogSource* channel(int16_t n);
|
|
|
|
|
|
|
|
// we don't yet know how to get the board voltage
|
2016-02-17 23:08:18 -04:00
|
|
|
float board_voltage(void) { return 5.0f; }
|
2015-08-20 09:21:26 -03:00
|
|
|
};
|