AnalogIn_IIO.cpp 2.4 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126
  1. #include "AnalogIn_IIO.h"
  2. #include <AP_HAL/AP_HAL.h>
  3. extern const AP_HAL::HAL &hal;
  4. const char* AnalogSource_IIO::analog_sources[] = {
  5. "in_voltage0_raw",
  6. "in_voltage1_raw",
  7. "in_voltage2_raw",
  8. "in_voltage3_raw",
  9. "in_voltage4_raw",
  10. "in_voltage5_raw",
  11. "in_voltage6_raw",
  12. "in_voltage7_raw",
  13. };
  14. AnalogSource_IIO::AnalogSource_IIO(int16_t pin, float initial_value, float voltage_scaling) :
  15. _pin(pin),
  16. _value(initial_value),
  17. _voltage_scaling(voltage_scaling),
  18. _sum_value(0),
  19. _sum_count(0),
  20. _pin_fd(-1)
  21. {
  22. init_pins();
  23. select_pin();
  24. }
  25. void AnalogSource_IIO::init_pins(void)
  26. {
  27. char buf[100];
  28. for (unsigned int i = 0; i < ARRAY_SIZE(AnalogSource_IIO::analog_sources); i++) {
  29. // Construct the path by appending strings
  30. strncpy(buf, IIO_ANALOG_IN_DIR, sizeof(buf));
  31. strncat(buf, AnalogSource_IIO::analog_sources[i], sizeof(buf) - strlen(buf) - 1);
  32. fd_analog_sources[i] = open(buf, O_RDONLY | O_NONBLOCK | O_CLOEXEC);
  33. }
  34. }
  35. /*
  36. selects a different file descriptor among in the fd_analog_sources array
  37. */
  38. void AnalogSource_IIO::select_pin(void)
  39. {
  40. _pin_fd = fd_analog_sources[_pin];
  41. }
  42. float AnalogSource_IIO::read_average()
  43. {
  44. read_latest();
  45. WITH_SEMAPHORE(_semaphore);
  46. if (_sum_count == 0) {
  47. return _value;
  48. }
  49. _value = _sum_value / _sum_count;
  50. _sum_value = 0;
  51. _sum_count = 0;
  52. return _value;
  53. }
  54. float AnalogSource_IIO::read_latest()
  55. {
  56. char sbuf[10];
  57. if (_pin_fd == -1) {
  58. _latest = 0;
  59. return 0;
  60. }
  61. memset(sbuf, 0, sizeof(sbuf));
  62. if (pread(_pin_fd, sbuf, sizeof(sbuf) - 1, 0) < 0) {
  63. _latest = 0;
  64. return 0;
  65. }
  66. WITH_SEMAPHORE(_semaphore);
  67. _latest = atoi(sbuf) * _voltage_scaling;
  68. _sum_value += _latest;
  69. _sum_count++;
  70. return _latest;
  71. }
  72. // output is in volts
  73. float AnalogSource_IIO::voltage_average()
  74. {
  75. return read_average();
  76. }
  77. float AnalogSource_IIO::voltage_latest()
  78. {
  79. read_latest();
  80. return _latest;
  81. }
  82. void AnalogSource_IIO::set_pin(uint8_t pin)
  83. {
  84. if (_pin == pin) {
  85. return;
  86. }
  87. WITH_SEMAPHORE(_semaphore);
  88. _pin = pin;
  89. _sum_value = 0;
  90. _sum_count = 0;
  91. _latest = 0;
  92. _value = 0;
  93. select_pin();
  94. }
  95. AnalogIn_IIO::AnalogIn_IIO()
  96. {}
  97. void AnalogIn_IIO::init()
  98. {}
  99. AP_HAL::AnalogSource* AnalogIn_IIO::channel(int16_t pin) {
  100. return new AnalogSource_IIO(pin, 0.0f, IIO_VOLTAGE_SCALING);
  101. }