AP_ADC_ADS1115.h 729 B

12345678910111213141516171819202122232425262728293031323334353637383940
  1. #pragma once
  2. #include <inttypes.h>
  3. #include <AP_HAL/AP_HAL.h>
  4. #include <AP_HAL/I2CDevice.h>
  5. struct adc_report_s
  6. {
  7. uint8_t id;
  8. float data;
  9. };
  10. class AP_ADC_ADS1115
  11. {
  12. public:
  13. AP_ADC_ADS1115();
  14. ~AP_ADC_ADS1115();
  15. bool init();
  16. size_t read(adc_report_s *report, size_t length) const;
  17. uint8_t get_channels_number() const
  18. {
  19. return _channels_number;
  20. }
  21. private:
  22. static const uint8_t _channels_number;
  23. AP_HAL::OwnPtr<AP_HAL::I2CDevice> _dev;
  24. uint16_t _gain;
  25. int _channel_to_read;
  26. adc_report_s *_samples;
  27. void _update();
  28. bool _start_conversion(uint8_t channel);
  29. float _convert_register_data_to_mv(int16_t word) const;
  30. };