APM:Libraries
AP_Baro_LPS2XH.cpp
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 #include <utility>
16 #include <stdio.h>
17 
18 #include "AP_Baro_LPS2XH.h"
19 
21 
22 extern const AP_HAL::HAL &hal;
23 
24 // WHOAMI values
25 #define LPS22HB_WHOAMI 0xB1
26 #define LPS25HB_WHOAMI 0xBD
27 
28 #define REG_ID 0x0F
29 
30 #define LPS22H_ID 0xB1
31 #define LPS22H_CTRL_REG1 0x10
32 #define LPS22H_CTRL_REG2 0x11
33 #define LPS22H_CTRL_REG3 0x12
34 
35 #define LPS22H_CTRL_REG1_SIM (1 << 0)
36 #define LPS22H_CTRL_REG1_BDU (1 << 1)
37 #define LPS22H_CTRL_REG1_LPFP_CFG (1 << 2)
38 #define LPS22H_CTRL_REG1_EN_LPFP (1 << 3)
39 #define LPS22H_CTRL_REG1_PD (0 << 4)
40 #define LPS22H_CTRL_REG1_ODR_1HZ (1 << 4)
41 #define LPS22H_CTRL_REG1_ODR_10HZ (2 << 4)
42 #define LPS22H_CTRL_REG1_ODR_25HZ (3 << 4)
43 #define LPS22H_CTRL_REG1_ODR_50HZ (4 << 4)
44 #define LPS22H_CTRL_REG1_ODR_75HZ (5 << 4)
45 
46 
47 #define LPS25H_CTRL_REG1_ADDR 0x20
48 #define LPS25H_CTRL_REG2_ADDR 0x21
49 #define LPS25H_CTRL_REG3_ADDR 0x22
50 #define LPS25H_CTRL_REG4_ADDR 0x23
51 #define LPS25H_FIFO_CTRL 0x2E
52 #define TEMP_OUT_ADDR 0x2B
53 #define PRESS_OUT_XL_ADDR 0x28
54 //putting 1 in the MSB of those two registers turns on Auto increment for faster reading.
55 
57  : AP_Baro_Backend(baro)
58  , _dev(std::move(dev))
59 {
60 }
61 
64 {
65  if (!dev) {
66  return nullptr;
67  }
68  AP_Baro_LPS2XH *sensor = new AP_Baro_LPS2XH(baro, std::move(dev));
69  if (!sensor || !sensor->_init()) {
70  delete sensor;
71  return nullptr;
72  }
73  return sensor;
74 }
75 
78  uint8_t imu_address)
79 {
80  if (!dev) {
81  return nullptr;
82  }
83  AP_Baro_LPS2XH *sensor = new AP_Baro_LPS2XH(baro, std::move(dev));
84  if (sensor) {
85  if (!sensor->_imu_i2c_init(imu_address)) {
86  delete sensor;
87  return nullptr;
88  }
89  }
90  if (!sensor || !sensor->_init()) {
91  delete sensor;
92  return nullptr;
93  }
94  return sensor;
95 }
96 
97 /*
98  setup invensense IMU to enable barometer, assuming both IMU and baro
99  on the same i2c bus
100 */
101 bool AP_Baro_LPS2XH::_imu_i2c_init(uint8_t imu_address)
102 {
104  return false;
105  }
106  // as the baro device is already locked we need to re-use it,
107  // changing its address to match the IMU address
108  uint8_t old_address = _dev->get_bus_address();
109  _dev->set_address(imu_address);
110 
111  _dev->set_retries(4);
112 
113  uint8_t whoami=0;
114  _dev->read_registers(MPUREG_WHOAMI, &whoami, 1);
115  hal.console->printf("IMU: whoami 0x%02x old_address=%02x\n", whoami, old_address);
116 
119 
120  // wait for sensor to settle
121  hal.scheduler->delay(10);
122 
124 
125  _dev->set_address(old_address);
126 
127  _dev->get_semaphore()->give();
128 
129  return true;
130 }
131 
133 {
135  return false;
136  }
137  _has_sample = false;
138 
140 
141  // top bit is for read on SPI
142  _dev->set_read_flag(0x80);
143 
144  if(!_check_whoami()){
145  _dev->get_semaphore()->give();
146  return false;
147  }
148 
149  //init control registers.
150  if(_lps2xh_type == BARO_LPS25H){
151  _dev->write_register(LPS25H_CTRL_REG1_ADDR,0x00); // turn off for config
152  _dev->write_register(LPS25H_CTRL_REG2_ADDR,0x00); //FIFO Disabled
155 
156  // request 25Hz update (maximum refresh Rate according to datasheet)
157  CallTime = 40 * AP_USEC_PER_MSEC;
158  }
159  if(_lps2xh_type == BARO_LPS22H){
162 
163  // request 75Hz update
164  CallTime = 1000000/75;
165  }
166 
168 
169  _dev->get_semaphore()->give();
170 
172 
173  return true;
174 }
175 
176 //check ID
178 {
179  uint8_t whoami;
180  if (! _dev->read_registers(REG_ID, &whoami, 1)) {
181  return false;
182  }
183  hal.console->printf("LPS2XH whoami 0x%02x\n", whoami);
184 
185  switch(whoami){
186  case LPS22HB_WHOAMI:
188  return true;
189  case LPS25HB_WHOAMI:
191  return true;
192  }
193  return false;
194 }
195 
196 
197 // acumulate a new sensor reading
199 {
202  _has_sample = true;
203 }
204 
205 // transfer data to the frontend
207 {
208  if (_sem->take_nonblocking()) {
209  if (!_has_sample) {
210  _sem->give();
211  return;
212  }
213 
215  _has_sample = false;
216  _sem->give();
217  }
218 }
219 
220 // calculate temperature
222 {
223  uint8_t pu8[2];
225  int16_t Temp_Reg_s16 = (uint16_t)(pu8[1]<<8) | pu8[0];
226  if (_sem->take_nonblocking()) {
227  if(_lps2xh_type == BARO_LPS25H){
228  _temperature=((float)(Temp_Reg_s16/480)+42.5);
229  }
230  if(_lps2xh_type == BARO_LPS22H){
231  _temperature=(float)(Temp_Reg_s16/100);
232  }
233  _sem->give();
234  }
235 }
236 
237 // calculate pressure
239 {
240  uint8_t pressure[3];
241  _dev->read_registers(PRESS_OUT_XL_ADDR, pressure, 3);
242  int32_t Pressure_Reg_s32 = ((uint32_t)pressure[2]<<16)|((uint32_t)pressure[1]<<8)|(uint32_t)pressure[0];
243  int32_t Pressure_mb = Pressure_Reg_s32 * (100.0 / 4096); // scale for pa
244  if (_sem->take_nonblocking()) {
245  _pressure=Pressure_mb;
246  _sem->give();
247  }
248 }
uint32_t CallTime
bool _check_whoami(void)
#define BIT_BYPASS_EN
Definition: ICM20789.cpp:24
#define AP_USEC_PER_MSEC
Definition: definitions.h:93
#define LPS22H_CTRL_REG1_BDU
#define MPUREG_INT_PIN_CFG
Definition: ICM20789.cpp:23
virtual PeriodicHandle register_periodic_callback(uint32_t period_usec, PeriodicCb)=0
#define LPS22H_CTRL_REG2
AP_Baro_LPS2XH(AP_Baro &baro, AP_HAL::OwnPtr< AP_HAL::Device > dev)
AP_HAL::UARTDriver * console
Definition: HAL.h:110
void _copy_to_frontend(uint8_t instance, float pressure, float temperature)
uint8_t register_sensor(void)
Definition: AP_Baro.cpp:705
AP_HAL::Semaphore * _sem
virtual AP_HAL::Semaphore * get_semaphore()=0
virtual void set_retries(uint8_t retries)
Definition: Device.h:260
#define PRESS_OUT_XL_ADDR
uint8_t get_bus_address(void) const
Definition: Device.h:65
#define HAL_SEMAPHORE_BLOCK_FOREVER
Definition: Semaphores.h:5
virtual bool take(uint32_t timeout_ms) WARN_IF_UNUSED=0
static AP_Baro_Backend * probe(AP_Baro &baro, AP_HAL::OwnPtr< AP_HAL::Device > dev)
#define MPUREG_WHOAMI
Definition: ICM20789.cpp:19
#define LPS25H_FIFO_CTRL
#define LPS22HB_WHOAMI
void _update_pressure(void)
#define LPS22H_CTRL_REG1
bool _imu_i2c_init(uint8_t imu_address)
virtual void delay(uint16_t ms)=0
virtual void printf(const char *,...) FMT_PRINTF(2
Definition: BetterStream.cpp:5
virtual bool take_nonblocking() WARN_IF_UNUSED=0
void _update_temperature(void)
AP_Baro & _frontend
static AP_HAL::OwnPtr< AP_HAL::Device > dev
Definition: ICM20789.cpp:16
virtual bool set_speed(Speed speed)=0
static AP_Baro baro
Definition: ModuleTest.cpp:18
#define LPS25H_CTRL_REG1_ADDR
enum LPS2XH_TYPE _lps2xh_type
virtual bool give()=0
#define MPUREG_PWR_MGMT_1
Definition: ICM20789.cpp:21
virtual void set_address(uint8_t address)
Definition: Device.h:85
#define LPS22H_CTRL_REG1_EN_LPFP
void set_read_flag(uint8_t flag)
Definition: Device.h:221
#define TEMP_OUT_ADDR
#define REG_ID
#define BIT_PWR_MGMT_1_CLK_XGYRO
Definition: ICM20789.cpp:31
#define LPS22H_CTRL_REG1_ODR_75HZ
bool read_registers(uint8_t first_reg, uint8_t *recv, uint32_t recv_len)
Definition: Device.h:113
#define LPS25HB_WHOAMI
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
Definition: functor.h:31
static AP_Baro_Backend * probe_InvensenseIMU(AP_Baro &baro, AP_HAL::OwnPtr< AP_HAL::Device > dev, uint8_t imu_address)
bool write_register(uint8_t reg, uint8_t val, bool checked=false)
Definition: Device.h:125
const AP_HAL::HAL & hal
Definition: AC_PID_test.cpp:14
#define LPS22H_CTRL_REG1_LPFP_CFG
#define LPS25H_CTRL_REG2_ADDR
AP_HAL::OwnPtr< AP_HAL::Device > _dev
AP_HAL::Scheduler * scheduler
Definition: HAL.h:114