AP_Baro_LPS2XH.cpp 7.3 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264
  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. This program is distributed in the hope that it will be useful,
  7. but WITHOUT ANY WARRANTY; without even the implied warranty of
  8. MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  9. GNU General Public License for more details.
  10. You should have received a copy of the GNU General Public License
  11. along with this program. If not, see <http://www.gnu.org/licenses/>.
  12. */
  13. #include <utility>
  14. #include <stdio.h>
  15. #include "AP_Baro_LPS2XH.h"
  16. #include <AP_InertialSensor/AP_InertialSensor_Invensense_registers.h>
  17. extern const AP_HAL::HAL &hal;
  18. // WHOAMI values
  19. #define LPS22HB_WHOAMI 0xB1
  20. #define LPS25HB_WHOAMI 0xBD
  21. #define REG_ID 0x0F
  22. #define LPS22H_ID 0xB1
  23. #define LPS22H_CTRL_REG1 0x10
  24. #define LPS22H_CTRL_REG2 0x11
  25. #define LPS22H_CTRL_REG3 0x12
  26. #define LPS22H_CTRL_REG1_SIM (1 << 0)
  27. #define LPS22H_CTRL_REG1_BDU (1 << 1)
  28. #define LPS22H_CTRL_REG1_LPFP_CFG (1 << 2)
  29. #define LPS22H_CTRL_REG1_EN_LPFP (1 << 3)
  30. #define LPS22H_CTRL_REG1_PD (0 << 4)
  31. #define LPS22H_CTRL_REG1_ODR_1HZ (1 << 4)
  32. #define LPS22H_CTRL_REG1_ODR_10HZ (2 << 4)
  33. #define LPS22H_CTRL_REG1_ODR_25HZ (3 << 4)
  34. #define LPS22H_CTRL_REG1_ODR_50HZ (4 << 4)
  35. #define LPS22H_CTRL_REG1_ODR_75HZ (5 << 4)
  36. #define LPS25H_CTRL_REG1_ADDR 0x20
  37. #define LPS25H_CTRL_REG2_ADDR 0x21
  38. #define LPS25H_CTRL_REG3_ADDR 0x22
  39. #define LPS25H_CTRL_REG4_ADDR 0x23
  40. #define LPS25H_FIFO_CTRL 0x2E
  41. #define TEMP_OUT_ADDR 0x2B
  42. #define PRESS_OUT_XL_ADDR 0x28
  43. #define STATUS_ADDR 0x27
  44. //putting 1 in the MSB of those two registers turns on Auto increment for faster reading.
  45. AP_Baro_LPS2XH::AP_Baro_LPS2XH(AP_Baro &baro, AP_HAL::OwnPtr<AP_HAL::Device> dev)
  46. : AP_Baro_Backend(baro)
  47. , _dev(std::move(dev))
  48. {
  49. }
  50. AP_Baro_Backend *AP_Baro_LPS2XH::probe(AP_Baro &baro,
  51. AP_HAL::OwnPtr<AP_HAL::Device> dev)
  52. {
  53. if (!dev) {
  54. return nullptr;
  55. }
  56. AP_Baro_LPS2XH *sensor = new AP_Baro_LPS2XH(baro, std::move(dev));
  57. if (!sensor || !sensor->_init()) {
  58. delete sensor;
  59. return nullptr;
  60. }
  61. return sensor;
  62. }
  63. AP_Baro_Backend *AP_Baro_LPS2XH::probe_InvensenseIMU(AP_Baro &baro,
  64. AP_HAL::OwnPtr<AP_HAL::Device> dev,
  65. uint8_t imu_address)
  66. {
  67. if (!dev) {
  68. return nullptr;
  69. }
  70. AP_Baro_LPS2XH *sensor = new AP_Baro_LPS2XH(baro, std::move(dev));
  71. if (sensor) {
  72. if (!sensor->_imu_i2c_init(imu_address)) {
  73. delete sensor;
  74. return nullptr;
  75. }
  76. }
  77. if (!sensor || !sensor->_init()) {
  78. delete sensor;
  79. return nullptr;
  80. }
  81. return sensor;
  82. }
  83. /*
  84. setup invensense IMU to enable barometer, assuming both IMU and baro
  85. on the same i2c bus
  86. */
  87. bool AP_Baro_LPS2XH::_imu_i2c_init(uint8_t imu_address)
  88. {
  89. if (!_dev->get_semaphore()->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
  90. return false;
  91. }
  92. // as the baro device is already locked we need to re-use it,
  93. // changing its address to match the IMU address
  94. uint8_t old_address = _dev->get_bus_address();
  95. _dev->set_address(imu_address);
  96. _dev->set_retries(4);
  97. uint8_t whoami=0;
  98. _dev->read_registers(MPUREG_WHOAMI, &whoami, 1);
  99. hal.console->printf("IMU: whoami 0x%02x old_address=%02x\n", whoami, old_address);
  100. _dev->write_register(MPUREG_FIFO_EN, 0x00);
  101. _dev->write_register(MPUREG_PWR_MGMT_1, BIT_PWR_MGMT_1_CLK_XGYRO);
  102. // wait for sensor to settle
  103. hal.scheduler->delay(10);
  104. _dev->write_register(MPUREG_INT_PIN_CFG, BIT_BYPASS_EN);
  105. _dev->set_address(old_address);
  106. _dev->get_semaphore()->give();
  107. return true;
  108. }
  109. bool AP_Baro_LPS2XH::_init()
  110. {
  111. if (!_dev || !_dev->get_semaphore()->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
  112. return false;
  113. }
  114. _has_sample = false;
  115. _dev->set_speed(AP_HAL::Device::SPEED_HIGH);
  116. // top bit is for read on SPI
  117. _dev->set_read_flag(0x80);
  118. if(!_check_whoami()){
  119. _dev->get_semaphore()->give();
  120. return false;
  121. }
  122. //init control registers.
  123. if(_lps2xh_type == BARO_LPS25H){
  124. _dev->write_register(LPS25H_CTRL_REG1_ADDR,0x00); // turn off for config
  125. _dev->write_register(LPS25H_CTRL_REG2_ADDR,0x00); //FIFO Disabled
  126. _dev->write_register(LPS25H_FIFO_CTRL, 0x01);
  127. _dev->write_register(LPS25H_CTRL_REG1_ADDR,0xc0);
  128. // request 25Hz update (maximum refresh Rate according to datasheet)
  129. CallTime = 40 * AP_USEC_PER_MSEC;
  130. }
  131. if(_lps2xh_type == BARO_LPS22H){
  132. _dev->write_register(LPS22H_CTRL_REG1, 0x00); // turn off for config
  133. _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);
  134. if (_dev->bus_type() == AP_HAL::Device::BUS_TYPE_SPI) {
  135. _dev->write_register(LPS22H_CTRL_REG2, 0x18); // disable i2c
  136. } else {
  137. _dev->write_register(LPS22H_CTRL_REG2, 0x10);
  138. }
  139. // request 75Hz update
  140. CallTime = 1000000/75;
  141. }
  142. _instance = _frontend.register_sensor();
  143. _dev->get_semaphore()->give();
  144. _dev->register_periodic_callback(CallTime, FUNCTOR_BIND_MEMBER(&AP_Baro_LPS2XH::_timer, void));
  145. return true;
  146. }
  147. //check ID
  148. bool AP_Baro_LPS2XH::_check_whoami(void)
  149. {
  150. uint8_t whoami;
  151. if (! _dev->read_registers(REG_ID, &whoami, 1)) {
  152. return false;
  153. }
  154. hal.console->printf("LPS2XH whoami 0x%02x\n", whoami);
  155. switch(whoami){
  156. case LPS22HB_WHOAMI:
  157. _lps2xh_type = BARO_LPS22H;
  158. return true;
  159. case LPS25HB_WHOAMI:
  160. _lps2xh_type = BARO_LPS25H;
  161. return true;
  162. }
  163. return false;
  164. }
  165. // acumulate a new sensor reading
  166. void AP_Baro_LPS2XH::_timer(void)
  167. {
  168. uint8_t status;
  169. // use status to check if data is available
  170. if (!_dev->read_registers(STATUS_ADDR, &status, 1)) {
  171. return;
  172. }
  173. if (status & 0x02) {
  174. _update_temperature();
  175. }
  176. if (status & 0x01) {
  177. _update_pressure();
  178. }
  179. _has_sample = true;
  180. }
  181. // transfer data to the frontend
  182. void AP_Baro_LPS2XH::update(void)
  183. {
  184. if (!_has_sample) {
  185. return;
  186. }
  187. WITH_SEMAPHORE(_sem);
  188. _copy_to_frontend(_instance, _pressure, _temperature);
  189. _has_sample = false;
  190. }
  191. // calculate temperature
  192. void AP_Baro_LPS2XH::_update_temperature(void)
  193. {
  194. uint8_t pu8[2];
  195. if (!_dev->read_registers(TEMP_OUT_ADDR, pu8, 2)) {
  196. return;
  197. }
  198. int16_t Temp_Reg_s16 = (uint16_t)(pu8[1]<<8) | pu8[0];
  199. WITH_SEMAPHORE(_sem);
  200. if (_lps2xh_type == BARO_LPS25H) {
  201. _temperature = (Temp_Reg_s16 * (1.0/480)) + 42.5;
  202. }
  203. if (_lps2xh_type == BARO_LPS22H) {
  204. _temperature = Temp_Reg_s16 * 0.01;
  205. }
  206. }
  207. // calculate pressure
  208. void AP_Baro_LPS2XH::_update_pressure(void)
  209. {
  210. uint8_t pressure[3];
  211. if (!_dev->read_registers(PRESS_OUT_XL_ADDR, pressure, 3)) {
  212. return;
  213. }
  214. int32_t Pressure_Reg_s32 = ((uint32_t)pressure[2]<<16)|((uint32_t)pressure[1]<<8)|(uint32_t)pressure[0];
  215. int32_t Pressure_mb = Pressure_Reg_s32 * (100.0f / 4096); // scale for pa
  216. WITH_SEMAPHORE(_sem);
  217. _pressure = Pressure_mb;
  218. }