AnalogIn.h 1.2 KB

123456789101112131415161718192021222324252627282930313233343536373839404142
  1. #pragma once
  2. #include <AP_HAL/AP_HAL.h>
  3. #include "AP_HAL_SITL_Namespace.h"
  4. #define SITL_INPUT_MAX_CHANNELS 12
  5. class HALSITL::ADCSource : public AP_HAL::AnalogSource {
  6. public:
  7. friend class HALSITL::AnalogIn;
  8. /* pin designates the ADC input number */
  9. ADCSource(SITL_State *sitlState, int16_t pin);
  10. /* implement AnalogSource virtual api: */
  11. float read_average() override;
  12. float read_latest() override;
  13. void set_pin(uint8_t p) override;
  14. float voltage_average() override;
  15. float voltage_latest() override;
  16. float voltage_average_ratiometric() override {
  17. return voltage_average();
  18. }
  19. private:
  20. SITL_State *_sitlState;
  21. int16_t _pin;
  22. };
  23. /* AnalogIn : a concrete class providing the implementations of the
  24. * timer event and the AP_HAL::AnalogIn interface */
  25. class HALSITL::AnalogIn : public AP_HAL::AnalogIn {
  26. public:
  27. explicit AnalogIn(SITL_State *sitlState): _sitlState(sitlState) {}
  28. void init() override;
  29. AP_HAL::AnalogSource* channel(int16_t n) override;
  30. float board_voltage(void) override {
  31. return 5.0f;
  32. }
  33. private:
  34. static ADCSource* _channels[SITL_INPUT_MAX_CHANNELS];
  35. SITL_State *_sitlState;
  36. };