AnalogIn_Navio2.cpp 2.3 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125
  1. #include <cstdio>
  2. #include <cstdlib>
  3. #include <errno.h>
  4. #include <unistd.h>
  5. #include <AP_HAL/AP_HAL.h>
  6. #include "AnalogIn_Navio2.h"
  7. static const AP_HAL::HAL &hal = AP_HAL::get_HAL();
  8. #define ADC_BASE_PATH "/sys/kernel/rcio/adc"
  9. void AnalogSource_Navio2::set_channel(uint8_t pin)
  10. {
  11. char *channel_path;
  12. if (pin == ANALOG_INPUT_NONE) {
  13. return;
  14. }
  15. if (asprintf(&channel_path, "%s/ch%d", ADC_BASE_PATH, pin) == -1) {
  16. AP_HAL::panic("asprintf failed\n");
  17. }
  18. if (_fd >= 0) {
  19. ::close(_fd);
  20. }
  21. _fd = ::open(channel_path, O_RDONLY|O_CLOEXEC);
  22. if (_fd < 0) {
  23. hal.console->printf("%s not opened: %s\n", channel_path, strerror(errno));
  24. }
  25. free(channel_path);
  26. }
  27. AnalogSource_Navio2::AnalogSource_Navio2(uint8_t pin)
  28. : _pin(pin)
  29. {
  30. set_channel(pin);
  31. }
  32. void AnalogSource_Navio2::set_pin(uint8_t pin)
  33. {
  34. if (_pin == pin) {
  35. return;
  36. }
  37. set_channel(pin);
  38. _pin = pin;
  39. }
  40. float AnalogSource_Navio2::read_average()
  41. {
  42. return read_latest();
  43. }
  44. float AnalogSource_Navio2::read_latest()
  45. {
  46. return voltage_average();
  47. }
  48. float AnalogSource_Navio2::voltage_average()
  49. {
  50. char buffer[12];
  51. if (pread(_fd, buffer, sizeof(buffer) - 1, 0) <= 0) {
  52. /* Don't log fails since this could spam the console */
  53. return -1.0f;
  54. }
  55. /* Avoid overriding NULL char at the end of the string */
  56. buffer[sizeof(buffer) - 1] = '\0';
  57. _value = atoi(buffer) / 1000.0f;
  58. return _value;
  59. }
  60. float AnalogSource_Navio2::voltage_latest()
  61. {
  62. read_latest();
  63. return _value;
  64. }
  65. float AnalogSource_Navio2::voltage_average_ratiometric()
  66. {
  67. return voltage_average();
  68. }
  69. AnalogIn_Navio2::AnalogIn_Navio2()
  70. {
  71. }
  72. float AnalogIn_Navio2::board_voltage(void)
  73. {
  74. return _board_voltage_pin->voltage_average();
  75. }
  76. float AnalogIn_Navio2::servorail_voltage(void)
  77. {
  78. return _servorail_pin->voltage_average();
  79. }
  80. AP_HAL::AnalogSource *AnalogIn_Navio2::channel(int16_t pin)
  81. {
  82. for (uint8_t j = 0; j < _channels_number; j++) {
  83. if (_channels[j] == nullptr) {
  84. _channels[j] = new AnalogSource_Navio2(pin);
  85. return _channels[j];
  86. }
  87. }
  88. hal.console->printf("Out of analog channels\n");
  89. return nullptr;
  90. }
  91. void AnalogIn_Navio2::init()
  92. {
  93. _board_voltage_pin = channel(0);
  94. _servorail_pin = channel(1);
  95. }