APM:Libraries
AnalogIn_IIO.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include "AP_HAL_Linux.h"
4 #include <AP_ADC/AP_ADC.h>
5 
6 #include <fcntl.h>
7 #include <unistd.h>
8 
9 #define IIO_ANALOG_IN_COUNT 8
10 #define IIO_ANALOG_IN_DIR "/sys/bus/iio/devices/iio:device0/"
11 
12 #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_PXF
13 // Note that echo BB-ADC cape should be loaded
14 #define IIO_VOLTAGE_SCALING 0.00142602816
15 #elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BBBMINI
16 #define IIO_VOLTAGE_SCALING 3.0*1.8/4095.0
17 #elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BLUE
18 #define IIO_VOLTAGE_SCALING 1.8/4095.0
19 #elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_POCKET
20 #define IIO_VOLTAGE_SCALING 3.0*1.8/4095.0
21 #elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_MINLURE
22 #define IIO_VOLTAGE_SCALING 2.0 / 1000
23 #else
24 #define IIO_VOLTAGE_SCALING 1.0
25 #endif
26 
28 public:
29  friend class AnalogIn_IIO;
30  AnalogSource_IIO(int16_t pin, float initial_value, float voltage_scaling);
31  float read_average();
32  float read_latest();
33  void set_pin(uint8_t p);
34  void set_stop_pin(uint8_t p);
35  void set_settle_time(uint16_t settle_time_ms);
36  float voltage_average();
37  float voltage_latest();
39 private:
40  float _value;
41  float _latest;
42  float _sum_value;
44  uint8_t _sum_count;
45  int16_t _pin;
46  int _pin_fd;
48 
49  void init_pins(void);
50  void select_pin(void);
51 
52  static const char *analog_sources[];
53 };
54 
56 public:
57  AnalogIn_IIO();
58  void init();
59  AP_HAL::AnalogSource* channel(int16_t n);
60 
61  // we don't yet know how to get the board voltage
62  float board_voltage(void) { return 5.0f; }
63 };
float voltage_latest()
float voltage_average_ratiometric()
Definition: AnalogIn_IIO.h:38
friend class AnalogIn_IIO
Definition: AnalogIn_IIO.h:29
uint8_t _sum_count
Definition: AnalogIn_IIO.h:44
int fd_analog_sources[IIO_ANALOG_IN_COUNT]
Definition: AnalogIn_IIO.h:47
float voltage_average()
void set_stop_pin(uint8_t p)
void select_pin(void)
AnalogSource_IIO(int16_t pin, float initial_value, float voltage_scaling)
float board_voltage(void)
Definition: AnalogIn_IIO.h:62
#define IIO_ANALOG_IN_COUNT
Definition: AnalogIn_IIO.h:9
void set_settle_time(uint16_t settle_time_ms)
void init()
Generic board initialization function.
Definition: system.cpp:136
void set_pin(uint8_t p)
static int8_t pin
Definition: AnalogIn.cpp:15
static const char * analog_sources[]
Definition: AnalogIn_IIO.h:52
void init_pins(void)
float _voltage_scaling
Definition: AnalogIn_IIO.h:43