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_Baro/AP_Baro_BMP581.cpp
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
#include "AP_Baro_BMP581.h"
16
17
#if AP_BARO_BMP581_ENABLED
18
19
#include <utility>
20
#include <AP_Math/AP_Math.h>
21
22
extern const AP_HAL::HAL &hal;
23
24
#define BMP581_ID 0x50
25
26
#define BMP581_REG_CHIP_ID 0x01
27
#define BMP581_REG_REV_ID 0x02
28
#define BMP581_REG_CHIP_STATUS 0x11
29
#define BMP581_REG_DRIVE_CONFIG 0x13
30
#define BMP581_REG_INT_CONFIG 0x14
31
#define BMP581_REG_INT_SOURCE 0x15
32
#define BMP581_REG_FIFO_CONFIG 0x16
33
#define BMP581_REG_FIFO_COUNT 0x17
34
#define BMP581_REG_FIFO_SEL 0x18
35
#define BMP581_REG_TEMP_DATA_XLSB 0x1D
36
#define BMP581_REG_TEMP_DATA_LSB 0x1E
37
#define BMP581_REG_TEMP_DATA_MSB 0x1F
38
#define BMP581_REG_PRESS_DATA_XLSB 0x20
39
#define BMP581_REG_PRESS_DATA_LSB 0x21
40
#define BMP581_REG_PRESS_DATA_MSB 0x22
41
#define BMP581_REG_INT_STATUS 0x27
42
#define BMP581_REG_STATUS 0x28
43
#define BMP581_REG_FIFO_DATA 0x29
44
#define BMP581_REG_NVM_ADDR 0x2B
45
#define BMP581_REG_NVM_DATA_LSB 0x2C
46
#define BMP581_REG_NVM_DATA_MSB 0x2D
47
#define BMP581_REG_DSP_CONFIG 0x30
48
#define BMP581_REG_DSP_IIR 0x31
49
#define BMP581_REG_OOR_THR_P_LSB 0x32
50
#define BMP581_REG_OOR_THR_P_MSB 0x33
51
#define BMP581_REG_OOR_RANGE 0x34
52
#define BMP581_REG_OOR_CONFIG 0x35
53
#define BMP581_REG_OSR_CONFIG 0x36
54
#define BMP581_REG_ODR_CONFIG 0x37
55
#define BMP581_REG_OSR_EFF 0x38
56
#define BMP581_REG_CMD 0x7E
57
58
AP_Baro_BMP581::AP_Baro_BMP581(AP_Baro &baro, AP_HAL::OwnPtr<AP_HAL::Device> dev)
59
: AP_Baro_Backend(baro)
60
, _dev(std::move(dev))
61
{
62
}
63
64
AP_Baro_Backend *AP_Baro_BMP581::probe(AP_Baro &baro,
65
AP_HAL::OwnPtr<AP_HAL::Device> dev)
66
{
67
if (!dev) {
68
return nullptr;
69
}
70
71
AP_Baro_BMP581 *sensor = NEW_NOTHROW AP_Baro_BMP581(baro, std::move(dev));
72
if (!sensor || !sensor->init()) {
73
delete sensor;
74
return nullptr;
75
}
76
return sensor;
77
}
78
79
bool AP_Baro_BMP581::init()
80
{
81
if (!_dev) {
82
return false;
83
}
84
85
WITH_SEMAPHORE(_dev->get_semaphore());
86
87
_dev->set_speed(AP_HAL::Device::SPEED_HIGH);
88
89
uint8_t whoami;
90
91
// setup to allow reads on SPI
92
if (_dev->bus_type() == AP_HAL::Device::BUS_TYPE_SPI) {
93
_dev->set_read_flag(0x80);
94
95
if (!_dev->read_registers(BMP581_REG_CHIP_ID, &whoami, 1)) {
96
return false;
97
}
98
}
99
100
if (!_dev->read_registers(BMP581_REG_CHIP_ID, &whoami, 1)) {
101
return false;
102
}
103
104
switch (whoami) {
105
case BMP581_ID:
106
_dev->set_device_type(DEVTYPE_BARO_BMP581);
107
break;
108
default:
109
return false;
110
}
111
112
uint8_t status;
113
if (!_dev->read_registers(BMP581_REG_STATUS, &status, 1)) {
114
return false;
115
}
116
117
if ((status & 0b10) == 0 || (status & 0b100) == 1) {
118
return false;
119
}
120
121
uint8_t int_status;
122
if (!_dev->read_registers(BMP581_REG_INT_STATUS, &int_status, 1)) {
123
return false;
124
}
125
126
if ((int_status & 0x10) == 0) {
127
return false;
128
}
129
130
_dev->setup_checked_registers(4);
131
132
// Standby mode
133
_dev->write_register(BMP581_REG_ODR_CONFIG, 0, true);
134
135
// Press EN | osr_p 64X | osr_t 4X
136
_dev->write_register(BMP581_REG_OSR_CONFIG, 0b01110010, true);
137
138
// ORD 50Hz | Normal Mode
139
_dev->write_register(BMP581_REG_ODR_CONFIG, 0b0111101, true);
140
141
instance = _frontend.register_sensor();
142
143
set_bus_id(instance, _dev->get_bus_id());
144
145
// request 50Hz update
146
_dev->register_periodic_callback(20 * AP_USEC_PER_MSEC, FUNCTOR_BIND_MEMBER(&AP_Baro_BMP581::timer, void));
147
148
return true;
149
}
150
151
// acumulate a new sensor reading
152
void AP_Baro_BMP581::timer(void)
153
{
154
uint8_t buf[6];
155
156
if (!_dev->read_registers(BMP581_REG_TEMP_DATA_XLSB, buf, sizeof(buf))) {
157
return;
158
}
159
160
WITH_SEMAPHORE(_sem);
161
162
if (buf[0] != 0x7f || buf[1] != 0x7f || buf[2] != 0x7f) {
163
// we have temperature data
164
temperature = (float)((int32_t)(((uint32_t)buf[2] << 24) | ((uint32_t)buf[1] << 16) | ((uint32_t)buf[0] << 8)) >> 8) * (1.0f / 65536.0f);
165
}
166
167
if (buf[3] != 0x7f || buf[4] != 0x7f || buf[5] != 0x7f) {
168
// we have pressure data
169
pressure_sum += (float)(((uint32_t)buf[5] << 16) | ((uint32_t)buf[4] << 8) | (uint32_t)buf[3]) * (1.0f / 64.0f);
170
pressure_count++;
171
}
172
173
_dev->check_next_register();
174
}
175
176
// transfer data to the frontend
177
void AP_Baro_BMP581::update(void)
178
{
179
WITH_SEMAPHORE(_sem);
180
181
if (pressure_count == 0) {
182
return;
183
}
184
185
_copy_to_frontend(instance,
186
pressure_sum/pressure_count,
187
temperature);
188
189
pressure_sum = 0;
190
pressure_count = 0;
191
}
192
193
#endif // AP_BARO_BMP581_ENABLED
194
195