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_LPS2XH.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_LPS2XH.h"
16
17
#if AP_BARO_LPS2XH_ENABLED
18
19
#include <utility>
20
#include <stdio.h>
21
22
#include <AP_InertialSensor/AP_InertialSensor_Invensense_registers.h>
23
24
extern const AP_HAL::HAL &hal;
25
26
// WHOAMI values
27
#define LPS22HB_WHOAMI 0xB1
28
#define LPS25HB_WHOAMI 0xBD
29
30
#define REG_ID 0x0F
31
32
#define LPS22H_ID 0xB1
33
#define LPS22H_CTRL_REG1 0x10
34
#define LPS22H_CTRL_REG2 0x11
35
#define LPS22H_CTRL_REG3 0x12
36
37
#define LPS22H_CTRL_REG1_SIM (1 << 0)
38
#define LPS22H_CTRL_REG1_BDU (1 << 1)
39
#define LPS22H_CTRL_REG1_LPFP_CFG (1 << 2)
40
#define LPS22H_CTRL_REG1_EN_LPFP (1 << 3)
41
#define LPS22H_CTRL_REG1_PD (0 << 4)
42
#define LPS22H_CTRL_REG1_ODR_1H (1 << 4)
43
#define LPS22H_CTRL_REG1_ODR_10HZ (2 << 4)
44
#define LPS22H_CTRL_REG1_ODR_25HZ (3 << 4)
45
#define LPS22H_CTRL_REG1_ODR_50HZ (4 << 4)
46
#define LPS22H_CTRL_REG1_ODR_75HZ (5 << 4)
47
48
#define LPS25H_CTRL_REG1_ADDR 0x20
49
#define LPS25H_CTRL_REG2_ADDR 0x21
50
#define LPS25H_CTRL_REG3_ADDR 0x22
51
#define LPS25H_CTRL_REG4_ADDR 0x23
52
#define LPS25H_FIFO_CTRL 0x2E
53
#define TEMP_OUT_ADDR 0x2B
54
#define PRESS_OUT_XL_ADDR 0x28
55
#define STATUS_ADDR 0x27
56
57
//putting 1 in the MSB of those two registers turns on Auto increment for faster reading.
58
59
AP_Baro_LPS2XH::AP_Baro_LPS2XH(AP_Baro &baro, AP_HAL::OwnPtr<AP_HAL::Device> dev)
60
: AP_Baro_Backend(baro)
61
, _dev(std::move(dev))
62
{
63
}
64
65
AP_Baro_Backend *AP_Baro_LPS2XH::probe(AP_Baro &baro,
66
AP_HAL::OwnPtr<AP_HAL::Device> dev)
67
{
68
if (!dev) {
69
return nullptr;
70
}
71
72
AP_Baro_LPS2XH *sensor = NEW_NOTHROW AP_Baro_LPS2XH(baro, std::move(dev));
73
if (!sensor || !sensor->_init()) {
74
delete sensor;
75
return nullptr;
76
}
77
78
return sensor;
79
}
80
81
AP_Baro_Backend *AP_Baro_LPS2XH::probe_InvensenseIMU(AP_Baro &baro,
82
AP_HAL::OwnPtr<AP_HAL::Device> dev,
83
uint8_t imu_address)
84
{
85
if (!dev) {
86
return nullptr;
87
}
88
89
AP_Baro_LPS2XH *sensor = NEW_NOTHROW AP_Baro_LPS2XH(baro, std::move(dev));
90
if (sensor) {
91
if (!sensor->_imu_i2c_init(imu_address)) {
92
delete sensor;
93
return nullptr;
94
}
95
}
96
97
if (!sensor || !sensor->_init()) {
98
delete sensor;
99
return nullptr;
100
}
101
102
return sensor;
103
}
104
105
/*
106
setup invensense IMU to enable barometer, assuming both IMU and baro
107
on the same i2c bus
108
*/
109
bool AP_Baro_LPS2XH::_imu_i2c_init(uint8_t imu_address)
110
{
111
_dev->get_semaphore()->take_blocking();
112
113
// as the baro device is already locked we need to re-use it,
114
// changing its address to match the IMU address
115
uint8_t old_address = _dev->get_bus_address();
116
_dev->set_address(imu_address);
117
118
_dev->set_retries(4);
119
120
uint8_t whoami=0;
121
_dev->read_registers(MPUREG_WHOAMI, &whoami, 1);
122
DEV_PRINTF("IMU: whoami 0x%02x old_address=%02x\n", whoami, old_address);
123
124
_dev->write_register(MPUREG_FIFO_EN, 0x00);
125
_dev->write_register(MPUREG_PWR_MGMT_1, BIT_PWR_MGMT_1_CLK_XGYRO);
126
127
// wait for sensor to settle
128
hal.scheduler->delay(10);
129
130
_dev->write_register(MPUREG_INT_PIN_CFG, BIT_BYPASS_EN);
131
132
_dev->set_address(old_address);
133
134
_dev->get_semaphore()->give();
135
136
return true;
137
}
138
139
bool AP_Baro_LPS2XH::_init()
140
{
141
if (!_dev) {
142
return false;
143
}
144
_dev->get_semaphore()->take_blocking();
145
146
_dev->set_speed(AP_HAL::Device::SPEED_HIGH);
147
148
// top bit is for read on SPI
149
if (_dev->bus_type() == AP_HAL::Device::BUS_TYPE_SPI) {
150
_dev->set_read_flag(0x80);
151
}
152
153
if (!_check_whoami()) {
154
_dev->get_semaphore()->give();
155
return false;
156
}
157
158
//init control registers.
159
if (_lps2xh_type == BARO_LPS25H) {
160
_dev->write_register(LPS25H_CTRL_REG1_ADDR,0x00); // turn off for config
161
_dev->write_register(LPS25H_CTRL_REG2_ADDR,0x00); //FIFO Disabled
162
_dev->write_register(LPS25H_FIFO_CTRL, 0x01);
163
_dev->write_register(LPS25H_CTRL_REG1_ADDR,0xc0);
164
165
// request 25Hz update (maximum refresh Rate according to datasheet)
166
CallTime = 40 * AP_USEC_PER_MSEC;
167
}
168
169
if (_lps2xh_type == BARO_LPS22H) {
170
_dev->write_register(LPS22H_CTRL_REG1, 0x00); // turn off for config
171
_dev->write_register(LPS22H_CTRL_REG1, LPS22H_CTRL_REG1_ODR_75HZ|LPS22H_CTRL_REG1_BDU|LPS22H_CTRL_REG1_EN_LPFP|LPS22H_CTRL_REG1_LPFP_CFG);
172
if (_dev->bus_type() == AP_HAL::Device::BUS_TYPE_SPI) {
173
_dev->write_register(LPS22H_CTRL_REG2, 0x18); // disable i2c
174
} else {
175
_dev->write_register(LPS22H_CTRL_REG2, 0x10);
176
}
177
178
// request 75Hz update
179
CallTime = 1000000/75;
180
}
181
182
_instance = _frontend.register_sensor();
183
184
_dev->set_device_type(DEVTYPE_BARO_LPS2XH);
185
set_bus_id(_instance, _dev->get_bus_id());
186
187
_dev->get_semaphore()->give();
188
189
_dev->register_periodic_callback(CallTime, FUNCTOR_BIND_MEMBER(&AP_Baro_LPS2XH::_timer, void));
190
191
return true;
192
}
193
194
//check ID
195
bool AP_Baro_LPS2XH::_check_whoami(void)
196
{
197
uint8_t whoami;
198
if (!_dev->read_registers(REG_ID, &whoami, 1)) {
199
return false;
200
}
201
DEV_PRINTF("LPS2XH whoami 0x%02x\n", whoami);
202
203
switch(whoami){
204
case LPS22HB_WHOAMI:
205
_lps2xh_type = BARO_LPS22H;
206
return true;
207
case LPS25HB_WHOAMI:
208
_lps2xh_type = BARO_LPS25H;
209
return true;
210
}
211
212
return false;
213
}
214
215
// accumulate a new sensor reading
216
void AP_Baro_LPS2XH::_timer(void)
217
{
218
uint8_t status;
219
// use status to check if data is available
220
if (!_dev->read_registers(STATUS_ADDR, &status, 1)) {
221
return;
222
}
223
224
if (status & 0x02) {
225
_update_temperature();
226
}
227
228
if (status & 0x01) {
229
_update_pressure();
230
}
231
}
232
233
// transfer data to the frontend
234
void AP_Baro_LPS2XH::update(void)
235
{
236
if (_pressure_count == 0) {
237
return;
238
}
239
240
WITH_SEMAPHORE(_sem);
241
_copy_to_frontend(_instance, _pressure_sum/_pressure_count, _temperature);
242
_pressure_sum = 0;
243
_pressure_count = 0;
244
}
245
246
// calculate temperature
247
void AP_Baro_LPS2XH::_update_temperature(void)
248
{
249
uint8_t pu8[2];
250
if (!_dev->read_registers(TEMP_OUT_ADDR, pu8, 2)) {
251
return;
252
}
253
int16_t Temp_Reg_s16 = (uint16_t)(pu8[1]<<8) | pu8[0];
254
255
WITH_SEMAPHORE(_sem);
256
257
if (_lps2xh_type == BARO_LPS25H) {
258
_temperature = (Temp_Reg_s16 * (1.0/480)) + 42.5;
259
}
260
261
if (_lps2xh_type == BARO_LPS22H) {
262
_temperature = Temp_Reg_s16 * 0.01;
263
}
264
}
265
266
// calculate pressure
267
void AP_Baro_LPS2XH::_update_pressure(void)
268
{
269
uint8_t pressure[3];
270
if (!_dev->read_registers(PRESS_OUT_XL_ADDR, pressure, 3)) {
271
return;
272
}
273
274
int32_t Pressure_Reg_s32 = ((uint32_t)pressure[2]<<16)|((uint32_t)pressure[1]<<8)|(uint32_t)pressure[0];
275
int32_t Pressure_mb = Pressure_Reg_s32 * (100.0f / 4096); // scale for pa
276
277
WITH_SEMAPHORE(_sem);
278
_pressure_sum += Pressure_mb;
279
_pressure_count++;
280
}
281
282
#endif // AP_BARO_LPS2XH_ENABLED
283
284