CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.

GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AP_Airspeed/AP_Airspeed_MS5525.h
Views: 1798
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_Airspeed_config.h"
22
23
#if AP_AIRSPEED_MS5525_ENABLED
24
25
#include <AP_HAL/AP_HAL.h>
26
#include <AP_HAL/utility/OwnPtr.h>
27
#include <AP_HAL/I2CDevice.h>
28
#include <utility>
29
30
#include "AP_Airspeed_Backend.h"
31
32
class AP_Airspeed_MS5525 : public AP_Airspeed_Backend
33
{
34
public:
35
enum MS5525_ADDR {
36
MS5525_ADDR_1 = 0,
37
MS5525_ADDR_2 = 1,
38
MS5525_ADDR_AUTO = 255, // does not need to be 255, just needs to be out of the address array
39
};
40
41
AP_Airspeed_MS5525(AP_Airspeed &frontend, uint8_t _instance, MS5525_ADDR address);
42
~AP_Airspeed_MS5525(void) {}
43
44
// probe and initialise the sensor
45
bool init() override;
46
47
// return the current differential_pressure in Pascal
48
bool get_differential_pressure(float &pressure) override;
49
50
// return the current temperature in degrees C, if available
51
bool get_temperature(float &temperature) override;
52
53
private:
54
void measure();
55
void collect();
56
void timer();
57
bool read_prom(void);
58
uint16_t crc4_prom(void);
59
int32_t read_adc();
60
void calculate();
61
62
float pressure;
63
float temperature;
64
float temperature_sum;
65
float pressure_sum;
66
uint32_t temp_count;
67
uint32_t press_count;
68
69
uint32_t last_sample_time_ms;
70
71
uint16_t prom[8];
72
uint8_t state;
73
int32_t D1;
74
int32_t D2;
75
uint32_t command_send_us;
76
bool ignore_next;
77
uint8_t cmd_sent;
78
MS5525_ADDR _address;
79
80
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev;
81
};
82
83
#endif // AP_AIRSPEED_MS5525_ENABLED
84
85