1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465 |
- #pragma once
- #include <AP_HAL/AP_HAL.h>
- #include <AP_Param/AP_Param.h>
- #include <AP_HAL/utility/OwnPtr.h>
- #include <AP_HAL/I2CDevice.h>
- #include <utility>
- #include "AP_Airspeed_Backend.h"
- #include "AP_Airspeed.h"
- class AP_Airspeed_SDP3X : public AP_Airspeed_Backend
- {
- public:
- AP_Airspeed_SDP3X(AP_Airspeed &frontend, uint8_t _instance);
- ~AP_Airspeed_SDP3X(void) {}
-
- bool init() override;
-
- bool get_differential_pressure(float &pressure) override;
-
- bool get_temperature(float &temperature) override;
- private:
- void _timer();
- bool _send_command(uint16_t cmd);
- bool _crc(const uint8_t data[], unsigned size, uint8_t checksum);
- float _correct_pressure(float press);
- float _temp;
- float _press;
- uint16_t _temp_count;
- uint16_t _press_count;
- float _temp_sum;
- float _press_sum;
- uint32_t _last_sample_time_ms;
- uint16_t _scale;
- AP_HAL::OwnPtr<AP_HAL::I2CDevice> _dev;
- };
|