123456789101112131415161718192021222324252627282930313233343536373839404142 |
- #pragma once
- #include <AP_HAL/AP_HAL.h>
- #include <AP_HAL/Semaphores.h>
- #include <AP_HAL/Device.h>
- #define TSYS01_ADDR 0x77
- class TSYS01 {
- public:
- bool init(uint8_t bus);
- float temperature(void) { return _temperature; }
- bool healthy(void) {
- #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
- return true;
- #endif
- return _healthy;
- }
- AP_HAL::OwnPtr<AP_HAL::Device> _dev;
- private:
- #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
- float _temperature = 42.42;
- #else
- float _temperature;
- #endif
- bool _healthy;
- uint16_t _k[5];
- bool _reset(void);
- bool _read_prom(void);
- bool _convert(void);
- uint32_t _read_adc(void);
- uint16_t _read_prom_word(uint8_t word);
- void _timer(void);
- void _calculate(uint32_t adc);
- };
|