Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AP_Baro/AP_Baro_MS5611.h
9782 views
1
#pragma once
2
3
#include "AP_Baro_Backend.h"
4
5
#if AP_BARO_MS56XX_ENABLED
6
7
#include <AP_HAL/AP_HAL.h>
8
#include <AP_HAL/Semaphores.h>
9
#include <AP_HAL/Device.h>
10
11
#ifndef HAL_BARO_MS5611_I2C_ADDR
12
#define HAL_BARO_MS5611_I2C_ADDR 0x77
13
#endif
14
15
#ifndef HAL_BARO_MS5611_I2C_ADDR2
16
#define HAL_BARO_MS5611_I2C_ADDR2 0x76
17
#endif
18
19
#ifndef HAL_BARO_MS5607_I2C_ADDR
20
#define HAL_BARO_MS5607_I2C_ADDR 0x77
21
#endif
22
23
#ifndef HAL_BARO_MS5837_I2C_ADDR
24
#define HAL_BARO_MS5837_I2C_ADDR 0x76
25
#endif
26
27
#ifndef HAL_BARO_MS5637_I2C_ADDR
28
#define HAL_BARO_MS5637_I2C_ADDR 0x76
29
#endif
30
31
#if AP_BARO_MS5837_ENABLED
32
// Determined in https://github.com/ArduPilot/ardupilot/pull/29122#issuecomment-2877269114
33
#define MS5837_30BA_02BA_SELECTION_THRESHOLD 37000
34
#endif
35
36
class AP_Baro_MS56XX : public AP_Baro_Backend
37
{
38
public:
39
void update() override;
40
41
AP_Baro_MS56XX(AP_Baro &baro, AP_HAL::Device &dev);
42
43
protected:
44
45
// convenience methods for derivative classes to call. Will free
46
// sensor if it can't init it.
47
static AP_Baro_Backend *_probe(AP_Baro &baro, AP_Baro_MS56XX *sensor);
48
49
virtual bool _init();
50
51
bool _read_prom_5611(uint16_t prom[8]);
52
bool _read_prom_5637(uint16_t prom[8]);
53
54
virtual const char *name() const = 0;
55
virtual DevTypes devtype() const = 0;
56
57
uint8_t _instance;
58
59
/* Last compensated values from accumulated sample */
60
float _D1, _D2;
61
62
// Internal calibration registers
63
struct {
64
uint16_t c1, c2, c3, c4, c5, c6;
65
} _cal_reg;
66
67
private:
68
69
static AP_Baro_Backend *probe(AP_Baro &baro, AP_HAL::Device &dev);
70
71
/*
72
* Update @accum and @count with the new sample in @val, taking into
73
* account a maximum number of samples given by @max_count; in case
74
* maximum number is reached, @accum and @count are updated appropriately
75
*/
76
static void _update_and_wrap_accumulator(uint32_t *accum, uint32_t val,
77
uint8_t *count, uint8_t max_count);
78
79
uint16_t _read_prom_word(uint8_t word);
80
uint32_t _read_adc();
81
82
void _timer();
83
84
AP_HAL::Device *_dev;
85
86
/* Shared values between thread sampling the HW and main thread */
87
struct {
88
uint32_t s_D1;
89
uint32_t s_D2;
90
uint8_t d1_count;
91
uint8_t d2_count;
92
} _accum;
93
94
uint8_t _state;
95
96
bool _discard_next;
97
98
virtual bool _read_prom(uint16_t *prom) = 0;
99
virtual void _calculate() = 0;
100
};
101
102
#if AP_BARO_MS5607_ENABLED
103
class AP_Baro_MS5607 : public AP_Baro_MS56XX
104
{
105
public:
106
using AP_Baro_MS56XX::AP_Baro_MS56XX;
107
static AP_Baro_Backend *probe(AP_Baro &baro, AP_HAL::Device &dev);
108
protected:
109
const char *name() const override { return "MS5607"; }
110
bool _read_prom(uint16_t *prom) override { return _read_prom_5611(prom); }
111
DevTypes devtype() const override { return DEVTYPE_BARO_MS5607; }
112
void _calculate() override;
113
};
114
#endif // AP_BARO_MS5607_ENABLED
115
116
#if AP_BARO_MS5611_ENABLED
117
class AP_Baro_MS5611 : public AP_Baro_MS56XX
118
{
119
public:
120
using AP_Baro_MS56XX::AP_Baro_MS56XX;
121
static AP_Baro_Backend *probe(AP_Baro &baro, AP_HAL::Device &dev);
122
protected:
123
const char *name() const override { return "MS5611"; }
124
bool _read_prom(uint16_t *prom) override { return _read_prom_5611(prom); }
125
DevTypes devtype() const override { return DEVTYPE_BARO_MS5611; }
126
void _calculate() override;
127
};
128
#endif // AP_BARO_MS5611_ENABLED
129
130
#if AP_BARO_MS5637_ENABLED
131
class AP_Baro_MS5637 : public AP_Baro_MS56XX
132
{
133
public:
134
using AP_Baro_MS56XX::AP_Baro_MS56XX;
135
static AP_Baro_Backend *probe(AP_Baro &baro, AP_HAL::Device &dev);
136
protected:
137
const char *name() const override { return "MS5637"; }
138
bool _read_prom(uint16_t *prom) override { return _read_prom_5637(prom); }
139
DevTypes devtype() const override { return DEVTYPE_BARO_MS5637; }
140
void _calculate() override;
141
};
142
#endif // AP_BARO_MS5637_ENABLED
143
144
#if AP_BARO_MS5837_ENABLED
145
class AP_Baro_MS5837 : public AP_Baro_MS56XX
146
{
147
public:
148
using AP_Baro_MS56XX::AP_Baro_MS56XX;
149
static AP_Baro_Backend *probe(AP_Baro &baro, AP_HAL::Device &dev);
150
protected:
151
const char *name() const override { return "MS5837"; }
152
bool _read_prom(uint16_t *prom) override { return _read_prom_5637(prom); }
153
DevTypes devtype() const override;
154
bool _init() override;
155
void _calculate() override;
156
void _calculate_5837_02ba();
157
void _calculate_5837_30ba();
158
159
DevTypes _subtype;
160
};
161
#endif // AP_BARO_MS5837_ENABLED
162
163
#endif // AP_BARO_MS56XX_ENABLED
164
165