APM:Libraries
AnalogIn_IIO.cpp
Go to the documentation of this file.
1 #include "AnalogIn_IIO.h"
2 
3 #include <AP_HAL/AP_HAL.h>
4 
5 extern const AP_HAL::HAL &hal;
6 
7 const char* AnalogSource_IIO::analog_sources[] = {
8  "in_voltage0_raw",
9  "in_voltage1_raw",
10  "in_voltage2_raw",
11  "in_voltage3_raw",
12  "in_voltage4_raw",
13  "in_voltage5_raw",
14  "in_voltage6_raw",
15  "in_voltage7_raw",
16 };
17 
18 AnalogSource_IIO::AnalogSource_IIO(int16_t pin, float initial_value, float voltage_scaling) :
19  _pin(pin),
20  _value(initial_value),
21  _voltage_scaling(voltage_scaling),
22  _sum_value(0),
23  _sum_count(0),
24  _pin_fd(-1)
25 {
26  init_pins();
27  select_pin();
28 }
29 
31 {
32  char buf[100];
33  for (unsigned int i = 0; i < ARRAY_SIZE(AnalogSource_IIO::analog_sources); i++) {
34  // Construct the path by appending strings
35  strncpy(buf, IIO_ANALOG_IN_DIR, sizeof(buf));
36  strncat(buf, AnalogSource_IIO::analog_sources[i], sizeof(buf) - strlen(buf) - 1);
37 
38  fd_analog_sources[i] = open(buf, O_RDONLY | O_NONBLOCK | O_CLOEXEC);
39  }
40 }
41 
42 /*
43  selects a different file descriptor among in the fd_analog_sources array
44  */
46 {
48 }
49 
51 {
52  read_latest();
53  if (_sum_count == 0) {
54  return _value;
55  }
58  _sum_value = 0;
59  _sum_count = 0;
61  return _value;
62 }
63 
65 {
66  char sbuf[10];
67 
68  if (_pin_fd == -1) {
69  _latest = 0;
70  return 0;
71  }
72 
73  memset(sbuf, 0, sizeof(sbuf));
74  if (pread(_pin_fd, sbuf, sizeof(sbuf) - 1, 0) < 0) {
75  _latest = 0;
76  return 0;
77  }
78  _latest = atoi(sbuf) * _voltage_scaling;
80  _sum_count++;
81 
82  return _latest;
83 }
84 
85 // output is in volts
87 {
88  return read_average();
89 }
90 
92 {
93  read_latest();
94  return _latest;
95 }
96 
98 {
99  if (_pin == pin) {
100  return;
101  }
102 
104  _pin = pin;
105  _sum_value = 0;
106  _sum_count = 0;
107  _latest = 0;
108  _value = 0;
109  select_pin();
111 }
112 
114 {}
115 
116 void AnalogSource_IIO::set_settle_time(uint16_t settle_time_ms)
117 {}
118 
120 {}
121 
123 {}
124 
125 
127  return new AnalogSource_IIO(pin, 0.0f, IIO_VOLTAGE_SCALING);
128 }
float voltage_latest()
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
int open(const char *pathname, int flags)
POSIX Open a file with integer mode flags.
Definition: posix.c:885
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)
virtual void resume_timer_procs()=0
AP_HAL::AnalogSource * channel(int16_t n)
AnalogSource_IIO(int16_t pin, float initial_value, float voltage_scaling)
#define f(i)
#define IIO_ANALOG_IN_DIR
Definition: AnalogIn_IIO.h:10
#define ARRAY_SIZE(_arr)
Definition: AP_Common.h:80
virtual void suspend_timer_procs()=0
void set_settle_time(uint16_t settle_time_ms)
#define IIO_VOLTAGE_SCALING
Definition: AnalogIn_IIO.h:14
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
AP_HAL::Scheduler * scheduler
Definition: HAL.h:114