AP_Baro_BMP085.cpp 8.3 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343
  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 "AP_Baro_BMP085.h"
  14. #include <utility>
  15. #include <stdio.h>
  16. #include <AP_Common/AP_Common.h>
  17. #include <AP_HAL/AP_HAL.h>
  18. extern const AP_HAL::HAL &hal;
  19. #define BMP085_OVERSAMPLING_ULTRALOWPOWER 0
  20. #define BMP085_OVERSAMPLING_STANDARD 1
  21. #define BMP085_OVERSAMPLING_HIGHRES 2
  22. #define BMP085_OVERSAMPLING_ULTRAHIGHRES 3
  23. #ifndef BMP085_EOC
  24. #define BMP085_EOC -1
  25. #define OVERSAMPLING BMP085_OVERSAMPLING_ULTRAHIGHRES
  26. #else
  27. #define OVERSAMPLING BMP085_OVERSAMPLING_HIGHRES
  28. #endif
  29. AP_Baro_BMP085::AP_Baro_BMP085(AP_Baro &baro, AP_HAL::OwnPtr<AP_HAL::Device> dev)
  30. : AP_Baro_Backend(baro)
  31. , _dev(std::move(dev))
  32. { }
  33. AP_Baro_Backend * AP_Baro_BMP085::probe(AP_Baro &baro, AP_HAL::OwnPtr<AP_HAL::Device> dev)
  34. {
  35. if (!dev) {
  36. return nullptr;
  37. }
  38. AP_Baro_BMP085 *sensor = new AP_Baro_BMP085(baro, std::move(dev));
  39. if (!sensor || !sensor->_init()) {
  40. delete sensor;
  41. return nullptr;
  42. }
  43. return sensor;
  44. }
  45. bool AP_Baro_BMP085::_init()
  46. {
  47. union {
  48. uint8_t buff[22];
  49. uint16_t wb[11];
  50. } bb;
  51. // get pointer to i2c bus semaphore
  52. AP_HAL::Semaphore *sem = _dev->get_semaphore();
  53. // take i2c bus sempahore
  54. WITH_SEMAPHORE(sem);
  55. if (BMP085_EOC >= 0) {
  56. _eoc = hal.gpio->channel(BMP085_EOC);
  57. _eoc->mode(HAL_GPIO_INPUT);
  58. }
  59. uint8_t id;
  60. if (!_dev->read_registers(0xD0, &id, 1)) {
  61. return false;
  62. }
  63. if (id!=0x55) {
  64. return false; // not BMP180
  65. }
  66. _dev->read_registers(0xD1, &_vers, 1);
  67. bool prom_ok=false;
  68. _type=0;
  69. // We read the calibration data registers
  70. if (_dev->read_registers(0xAA, bb.buff, sizeof(bb.buff))) {
  71. prom_ok=true;
  72. }
  73. if (!prom_ok) {
  74. if (_read_prom((uint16_t *)&bb.wb[0])) { // BMP180 requires reads by 2 bytes
  75. prom_ok=true;
  76. _type=1;
  77. }
  78. }
  79. if (!prom_ok) {
  80. return false;
  81. }
  82. ac1 = ((int16_t)bb.buff[0] << 8) | bb.buff[1];
  83. ac2 = ((int16_t)bb.buff[2] << 8) | bb.buff[3];
  84. ac3 = ((int16_t)bb.buff[4] << 8) | bb.buff[5];
  85. ac4 = ((int16_t)bb.buff[6] << 8) | bb.buff[7];
  86. ac5 = ((int16_t)bb.buff[8] << 8) | bb.buff[9];
  87. ac6 = ((int16_t)bb.buff[10]<< 8) | bb.buff[11];
  88. b1 = ((int16_t)bb.buff[12] << 8) | bb.buff[13];
  89. b2 = ((int16_t)bb.buff[14] << 8) | bb.buff[15];
  90. mb = ((int16_t)bb.buff[16] << 8) | bb.buff[17];
  91. mc = ((int16_t)bb.buff[18] << 8) | bb.buff[19];
  92. md = ((int16_t)bb.buff[20] << 8) | bb.buff[21];
  93. if ((ac1==0 || ac1==-1) ||
  94. (ac2==0 || ac2==-1) ||
  95. (ac3==0 || ac3==-1) ||
  96. (ac4==0 || ac4==0xFFFF) ||
  97. (ac5==0 || ac5==0xFFFF) ||
  98. (ac6==0 || ac6==0xFFFF)) {
  99. return false;
  100. }
  101. _last_press_read_command_time = 0;
  102. _last_temp_read_command_time = 0;
  103. // Send a command to read temperature
  104. _cmd_read_temp();
  105. _state = 0;
  106. _instance = _frontend.register_sensor();
  107. _dev->register_periodic_callback(20000, FUNCTOR_BIND_MEMBER(&AP_Baro_BMP085::_timer, void));
  108. return true;
  109. }
  110. uint16_t AP_Baro_BMP085::_read_prom_word(uint8_t word)
  111. {
  112. const uint8_t reg = 0xAA + (word << 1);
  113. uint8_t val[2];
  114. if (!_dev->transfer(&reg, 1, val, sizeof(val))) {
  115. return 0;
  116. }
  117. return (val[0] << 8) | val[1];
  118. }
  119. bool AP_Baro_BMP085::_read_prom(uint16_t *prom)
  120. {
  121. bool all_zero = true;
  122. for (uint8_t i = 0; i < 11; i++) {
  123. prom[i] = _read_prom_word(i);
  124. if (prom[i] != 0) {
  125. all_zero = false;
  126. }
  127. }
  128. if (all_zero) {
  129. return false;
  130. }
  131. return true;
  132. }
  133. /*
  134. This is a state machine. Acumulate a new sensor reading.
  135. */
  136. void AP_Baro_BMP085::_timer(void)
  137. {
  138. if (!_data_ready()) {
  139. return;
  140. }
  141. if (_state == 0) {
  142. _read_temp();
  143. } else if (_read_pressure()) {
  144. _calculate();
  145. }
  146. _state++;
  147. if (_state == 25) {
  148. _state = 0;
  149. _cmd_read_temp();
  150. } else {
  151. _cmd_read_pressure();
  152. }
  153. }
  154. /*
  155. transfer data to the frontend
  156. */
  157. void AP_Baro_BMP085::update(void)
  158. {
  159. WITH_SEMAPHORE(_sem);
  160. if (!_has_sample) {
  161. return;
  162. }
  163. float temperature = 0.1f * _temp;
  164. float pressure = _pressure_filter.getf();
  165. _copy_to_frontend(_instance, pressure, temperature);
  166. }
  167. // Send command to Read Pressure
  168. void AP_Baro_BMP085::_cmd_read_pressure()
  169. {
  170. _dev->write_register(0xF4, 0x34 + (OVERSAMPLING << 6));
  171. _last_press_read_command_time = AP_HAL::millis();
  172. }
  173. // Read raw pressure values
  174. bool AP_Baro_BMP085::_read_pressure()
  175. {
  176. uint8_t buf[3];
  177. if (_dev->read_registers(0xF6, buf, sizeof(buf))) {
  178. _raw_pressure = (((uint32_t)buf[0] << 16)
  179. | ((uint32_t)buf[1] << 8)
  180. | ((uint32_t)buf[2])) >> (8 - OVERSAMPLING);
  181. return true;
  182. }
  183. uint8_t xlsb;
  184. if (_dev->read_registers(0xF6, buf, 2) && _dev->read_registers(0xF8, &xlsb, 1)) {
  185. _raw_pressure = (((uint32_t)buf[0] << 16)
  186. | ((uint32_t)buf[1] << 8)
  187. | ((uint32_t)xlsb)) >> (8 - OVERSAMPLING);
  188. return true;
  189. }
  190. _last_press_read_command_time = AP_HAL::millis() + 1000;
  191. _dev->set_speed(AP_HAL::Device::SPEED_LOW);
  192. return false;
  193. }
  194. // Send Command to Read Temperature
  195. void AP_Baro_BMP085::_cmd_read_temp()
  196. {
  197. _dev->write_register(0xF4, 0x2E);
  198. _last_temp_read_command_time = AP_HAL::millis();
  199. }
  200. // Read raw temperature values
  201. void AP_Baro_BMP085::_read_temp()
  202. {
  203. uint8_t buf[2];
  204. int32_t _temp_sensor;
  205. if (!_dev->read_registers(0xF6, buf, sizeof(buf))) {
  206. _dev->set_speed(AP_HAL::Device::SPEED_LOW);
  207. return;
  208. }
  209. _temp_sensor = buf[0];
  210. _temp_sensor = (_temp_sensor << 8) | buf[1];
  211. _raw_temp = _temp_sensor;
  212. }
  213. // _calculate Temperature and Pressure in real units.
  214. void AP_Baro_BMP085::_calculate()
  215. {
  216. int32_t x1, x2, x3, b3, b5, b6, p;
  217. uint32_t b4, b7;
  218. int32_t tmp;
  219. // See Datasheet page 13 for this formulas
  220. // Based also on Jee Labs BMP085 example code. Thanks for share.
  221. // Temperature calculations
  222. x1 = ((int32_t)_raw_temp - ac6) * ac5 >> 15;
  223. x2 = ((int32_t) mc << 11) / (x1 + md);
  224. b5 = x1 + x2;
  225. _temp = (b5 + 8) >> 4;
  226. // Pressure calculations
  227. b6 = b5 - 4000;
  228. x1 = (b2 * (b6 * b6 >> 12)) >> 11;
  229. x2 = ac2 * b6 >> 11;
  230. x3 = x1 + x2;
  231. //b3 = (((int32_t) ac1 * 4 + x3)<<OVERSAMPLING + 2) >> 2; // BAD
  232. //b3 = ((int32_t) ac1 * 4 + x3 + 2) >> 2; //OK for OVERSAMPLING=0
  233. tmp = ac1;
  234. tmp = (tmp*4 + x3)<<OVERSAMPLING;
  235. b3 = (tmp+2)/4;
  236. x1 = ac3 * b6 >> 13;
  237. x2 = (b1 * (b6 * b6 >> 12)) >> 16;
  238. x3 = ((x1 + x2) + 2) >> 2;
  239. b4 = (ac4 * (uint32_t)(x3 + 32768)) >> 15;
  240. b7 = ((uint32_t) _raw_pressure - b3) * (50000 >> OVERSAMPLING);
  241. p = b7 < 0x80000000 ? (b7 * 2) / b4 : (b7 / b4) * 2;
  242. x1 = (p >> 8) * (p >> 8);
  243. x1 = (x1 * 3038) >> 16;
  244. x2 = (-7357 * p) >> 16;
  245. p += ((x1 + x2 + 3791) >> 4);
  246. if (!pressure_ok(p)) {
  247. return;
  248. }
  249. WITH_SEMAPHORE(_sem);
  250. _pressure_filter.apply(p);
  251. _has_sample = true;
  252. }
  253. bool AP_Baro_BMP085::_data_ready()
  254. {
  255. if (BMP085_EOC >= 0) {
  256. return _eoc->read();
  257. }
  258. // No EOC pin: use time from last read instead.
  259. if (_state == 0) {
  260. return AP_HAL::millis() > _last_temp_read_command_time + 5;
  261. }
  262. uint32_t conversion_time_msec;
  263. switch (OVERSAMPLING) {
  264. case BMP085_OVERSAMPLING_ULTRALOWPOWER:
  265. conversion_time_msec = 5;
  266. break;
  267. case BMP085_OVERSAMPLING_STANDARD:
  268. conversion_time_msec = 8;
  269. break;
  270. case BMP085_OVERSAMPLING_HIGHRES:
  271. conversion_time_msec = 14;
  272. break;
  273. case BMP085_OVERSAMPLING_ULTRAHIGHRES:
  274. conversion_time_msec = 26;
  275. default:
  276. break;
  277. }
  278. return AP_HAL::millis() > _last_press_read_command_time + conversion_time_msec;
  279. }