AnalogIn.h 1.1 KB

123456789101112131415161718192021222324252627282930313233343536373839404142
  1. #pragma once
  2. #include <inttypes.h>
  3. #include "AP_HAL_Namespace.h"
  4. class AP_HAL::AnalogSource {
  5. public:
  6. virtual float read_average() = 0;
  7. virtual float read_latest() = 0;
  8. virtual void set_pin(uint8_t p) = 0;
  9. // return a voltage from 0.0 to 5.0V, scaled
  10. // against a reference voltage
  11. virtual float voltage_average() = 0;
  12. // return a voltage from 0.0 to 5.0V, scaled
  13. // against a reference voltage
  14. virtual float voltage_latest() = 0;
  15. // return a voltage from 0.0 to 5.0V, assuming a ratiometric
  16. // sensor
  17. virtual float voltage_average_ratiometric() = 0;
  18. };
  19. class AP_HAL::AnalogIn {
  20. public:
  21. virtual void init() = 0;
  22. virtual AP_HAL::AnalogSource* channel(int16_t n) = 0;
  23. // board 5V rail voltage in volts
  24. virtual float board_voltage(void) = 0;
  25. // servo rail voltage in volts, or 0 if unknown
  26. virtual float servorail_voltage(void) { return 0; }
  27. // power supply status flags, see MAV_POWER_STATUS
  28. virtual uint16_t power_status_flags(void) { return 0; }
  29. };
  30. #define ANALOG_INPUT_BOARD_VCC 254
  31. #define ANALOG_INPUT_NONE 255