AnalogIn.cpp 1.3 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172
  1. #include <AP_HAL/AP_HAL.h>
  2. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  3. #include "AP_HAL_SITL.h"
  4. #include "AnalogIn.h"
  5. #include <stdint.h>
  6. using namespace HALSITL;
  7. extern const AP_HAL::HAL& hal;
  8. ADCSource::ADCSource(SITL_State *sitlState, int16_t pin) :
  9. _sitlState(sitlState),
  10. _pin(pin)
  11. {}
  12. float ADCSource::read_average() {
  13. return read_latest();
  14. }
  15. float ADCSource::voltage_average() {
  16. return (5.0f/1023.0f) * read_average();
  17. }
  18. float ADCSource::voltage_latest() {
  19. return (5.0f/1023.0f) * read_latest();
  20. }
  21. float ADCSource::read_latest() {
  22. switch (_pin) {
  23. case ANALOG_INPUT_BOARD_VCC:
  24. return 1023;
  25. case 0:
  26. return _sitlState->sonar_pin_value;
  27. case 1:
  28. return _sitlState->airspeed_pin_value;
  29. case 2:
  30. return _sitlState->airspeed_2_pin_value;
  31. case 12:
  32. return _sitlState->current_pin_value;
  33. case 13:
  34. return _sitlState->voltage_pin_value;
  35. case 14:
  36. return _sitlState->current2_pin_value;
  37. case 15:
  38. return _sitlState->voltage2_pin_value;
  39. case ANALOG_INPUT_NONE:
  40. default:
  41. return 0.0f;
  42. }
  43. }
  44. void ADCSource::set_pin(uint8_t pin) {
  45. _pin = pin;
  46. }
  47. void AnalogIn::init() {
  48. }
  49. AP_HAL::AnalogSource* AnalogIn::channel(int16_t pin) {
  50. return new ADCSource(_sitlState, pin);
  51. }
  52. #endif