APM:Libraries
AP_Airspeed_SDP3X.h
Go to the documentation of this file.
1 /*
2  This program is free software: you can redistribute it and/or modify
3  it under the terms of the GNU General Public License as published by
4  the Free Software Foundation, either version 3 of the License, or
5  (at your option) any later version.
6 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 #pragma once
16 
17 /*
18  backend driver for airspeed from I2C
19  */
20 
21 #include <AP_HAL/AP_HAL.h>
22 #include <AP_Param/AP_Param.h>
23 #include <AP_HAL/utility/OwnPtr.h>
24 #include <AP_HAL/I2CDevice.h>
25 #include <utility>
26 
27 #include "AP_Airspeed_Backend.h"
28 #include "AP_Airspeed.h"
29 
30 /*
31  * Thanks to PX4 for registers definitions
32  */
33 
35 {
36 public:
37  AP_Airspeed_SDP3X(AP_Airspeed &frontend, uint8_t _instance);
39 
40  // probe and initialise the sensor
41  bool init() override;
42 
43  // return the current differential_pressure in Pascal
44  bool get_differential_pressure(float &pressure) override;
45 
46  // return the current temperature in degrees C, if available
47  bool get_temperature(float &temperature) override;
48 
49 private:
50  void _timer();
51  bool _send_command(uint16_t cmd);
52  bool _crc(const uint8_t data[], unsigned size, uint8_t checksum);
53  float _correct_pressure(float press);
54 
55  float _temp;
56  float _press;
57  uint16_t _temp_count;
58  uint16_t _press_count;
59  float _temp_sum;
60  float _press_sum;
62  uint16_t _scale;
63 
65 };
uint32_t _last_sample_time_ms
AP_Airspeed_SDP3X(AP_Airspeed &frontend, uint8_t _instance)
bool _send_command(uint16_t cmd)
float _correct_pressure(float press)
bool get_differential_pressure(float &pressure) override
A system for managing and storing variables that are of general interest to the system.
float temperature
Definition: Airspeed.cpp:32
AP_HAL::OwnPtr< AP_HAL::I2CDevice > _dev
bool _crc(const uint8_t data[], unsigned size, uint8_t checksum)
bool init() override
bool get_temperature(float &temperature) override