AP_Baro_DPS280.cpp 6.3 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234
  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. /*
  14. DPS280 barometer driver
  15. */
  16. #include "AP_Baro_DPS280.h"
  17. #include <utility>
  18. #include <stdio.h>
  19. extern const AP_HAL::HAL &hal;
  20. #define DPS280_REG_PRESS 0x00
  21. #define DPS280_REG_TEMP 0x03
  22. #define DPS280_REG_PCONF 0x06
  23. #define DPS280_REG_TCONF 0x07
  24. #define DPS280_REG_MCONF 0x08
  25. #define DPS280_REG_CREG 0x09
  26. #define DPS280_REG_ISTS 0x0A
  27. #define DPS280_REG_FSTS 0x0B
  28. #define DPS280_REG_RESET 0x0C
  29. #define DPS280_REG_PID 0x0D
  30. #define DPS280_REG_COEF 0x10
  31. #define DPS280_REG_CSRC 0x28
  32. #define DPS280_WHOAMI 0x10
  33. AP_Baro_DPS280::AP_Baro_DPS280(AP_Baro &baro, AP_HAL::OwnPtr<AP_HAL::Device> _dev)
  34. : AP_Baro_Backend(baro)
  35. , dev(std::move(_dev))
  36. {
  37. }
  38. AP_Baro_Backend *AP_Baro_DPS280::probe(AP_Baro &baro,
  39. AP_HAL::OwnPtr<AP_HAL::Device> _dev)
  40. {
  41. if (!_dev) {
  42. return nullptr;
  43. }
  44. AP_Baro_DPS280 *sensor = new AP_Baro_DPS280(baro, std::move(_dev));
  45. if (!sensor || !sensor->init()) {
  46. delete sensor;
  47. return nullptr;
  48. }
  49. return sensor;
  50. }
  51. /*
  52. handle bit width for 16 bit config registers
  53. */
  54. void AP_Baro_DPS280::fix_config_bits16(int16_t &v, uint8_t bits) const
  55. {
  56. if (v > int16_t((1U<<(bits-1))-1)) {
  57. v = v - (1U<<bits);
  58. }
  59. }
  60. /*
  61. handle bit width for 32 bit config registers
  62. */
  63. void AP_Baro_DPS280::fix_config_bits32(int32_t &v, uint8_t bits) const
  64. {
  65. if (v > int32_t((1U<<(bits-1))-1)) {
  66. v = v - (1U<<bits);
  67. }
  68. }
  69. /*
  70. read calibration data
  71. */
  72. bool AP_Baro_DPS280::read_calibration(void)
  73. {
  74. uint8_t buf[18];
  75. if (!dev->read_registers(DPS280_REG_COEF, buf, 18)) {
  76. return false;
  77. }
  78. calibration.C0 = (buf[0] << 4) + ((buf[1] >>4) & 0x0F);
  79. calibration.C1 = (buf[2] + ((buf[1] & 0x0F)<<8));
  80. calibration.C00 = ((buf[4]<<4) + (buf[3]<<12)) + ((buf[5]>>4) & 0x0F);
  81. calibration.C10 = ((buf[5] & 0x0F)<<16) + buf[7] + (buf[6]<<8);
  82. calibration.C01 = (buf[9] + (buf[8]<<8));
  83. calibration.C11 = (buf[11] + (buf[10]<<8));
  84. calibration.C20 = (buf[13] + (buf[12]<<8));
  85. calibration.C21 = (buf[15] + (buf[14]<<8));
  86. calibration.C30 = (buf[17] + (buf[16]<<8));
  87. fix_config_bits16(calibration.C0, 12);
  88. fix_config_bits16(calibration.C1, 12);
  89. fix_config_bits32(calibration.C00, 20);
  90. fix_config_bits32(calibration.C10, 20);
  91. fix_config_bits16(calibration.C01, 16);
  92. fix_config_bits16(calibration.C11, 16);
  93. fix_config_bits16(calibration.C20, 16);
  94. fix_config_bits16(calibration.C21, 16);
  95. fix_config_bits16(calibration.C30, 16);
  96. /* get calibration source */
  97. if (!dev->read_registers(DPS280_REG_CSRC, &calibration.temp_source, 1)) {
  98. return false;
  99. }
  100. calibration.temp_source &= 0x80;
  101. return true;
  102. }
  103. bool AP_Baro_DPS280::init()
  104. {
  105. if (!dev || !dev->get_semaphore()->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
  106. return false;
  107. }
  108. dev->set_read_flag(0x80);
  109. dev->set_speed(AP_HAL::Device::SPEED_HIGH);
  110. uint8_t whoami=0;
  111. if (!dev->read_registers(DPS280_REG_PID, &whoami, 1) ||
  112. whoami != DPS280_WHOAMI) {
  113. // not a DPS280
  114. printf("DPS280 whoami=0x%x\n", whoami);
  115. dev->get_semaphore()->give();
  116. return false;
  117. }
  118. if (!read_calibration()) {
  119. dev->get_semaphore()->give();
  120. return false;
  121. }
  122. dev->write_register(DPS280_REG_CREG, 0x0C); // shift for 16x oversampling
  123. dev->write_register(DPS280_REG_PCONF, 0x54); // 32 Hz, 16x oversample
  124. dev->write_register(DPS280_REG_TCONF, 0x54 | calibration.temp_source); // 32 Hz, 16x oversample
  125. dev->write_register(DPS280_REG_MCONF, 0x07); // continuous temp and pressure
  126. instance = _frontend.register_sensor();
  127. dev->get_semaphore()->give();
  128. // request 64Hz update. New data will be available at 32Hz
  129. dev->register_periodic_callback((1000 / 64) * AP_USEC_PER_MSEC, FUNCTOR_BIND_MEMBER(&AP_Baro_DPS280::timer, void));
  130. return true;
  131. }
  132. /*
  133. calculate corrected pressure and temperature
  134. */
  135. void AP_Baro_DPS280::calculate_PT(int32_t UT, int32_t UP, float &pressure, float &temperature)
  136. {
  137. const struct dps280_cal &cal = calibration;
  138. // scaling for 16x oversampling
  139. const float scaling_16 = 1.0f/253952;
  140. float temp_scaled;
  141. float press_scaled;
  142. temp_scaled = float(UT) * scaling_16;
  143. temperature = cal.C0 * 0.5f + cal.C1 * temp_scaled;
  144. press_scaled = float(UP) * scaling_16;
  145. pressure = cal.C00;
  146. pressure += press_scaled * (cal.C10 + press_scaled * (cal.C20 + press_scaled * cal.C30));
  147. pressure += temp_scaled * cal.C01;
  148. pressure += temp_scaled * press_scaled * (cal.C11 + press_scaled * cal.C21);
  149. }
  150. // acumulate a new sensor reading
  151. void AP_Baro_DPS280::timer(void)
  152. {
  153. uint8_t buf[6];
  154. uint8_t ready;
  155. if (!dev->read_registers(DPS280_REG_MCONF, &ready, 1) || !(ready & (1U<<4))) {
  156. // pressure not ready
  157. return;
  158. }
  159. if (!dev->read_registers(DPS280_REG_PRESS, buf, 3)) {
  160. return;
  161. }
  162. if (!dev->read_registers(DPS280_REG_TEMP, &buf[3], 3)) {
  163. return;
  164. }
  165. int32_t press = (buf[2]) + (buf[1]<<8) + (buf[0]<<16);
  166. int32_t temp = (buf[5]) + (buf[4]<<8) + (buf[3]<<16);
  167. fix_config_bits32(press, 24);
  168. fix_config_bits32(temp, 24);
  169. float pressure, temperature;
  170. calculate_PT(temp, press, pressure, temperature);
  171. if (!pressure_ok(pressure)) {
  172. return;
  173. }
  174. WITH_SEMAPHORE(_sem);
  175. pressure_sum += pressure;
  176. temperature_sum += temperature;
  177. count++;
  178. }
  179. // transfer data to the frontend
  180. void AP_Baro_DPS280::update(void)
  181. {
  182. if (count == 0) {
  183. return;
  184. }
  185. WITH_SEMAPHORE(_sem);
  186. _copy_to_frontend(instance, pressure_sum/count, temperature_sum/count);
  187. pressure_sum = 0;
  188. temperature_sum = 0;
  189. count=0;
  190. }