AP_Baro_KellerLD.cpp 7.9 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256
  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_KellerLD.h"
  14. #include <utility>
  15. #include <stdio.h>
  16. #include <AP_Math/AP_Math.h>
  17. #define KELLER_DEBUG 0
  18. #if KELLER_DEBUG
  19. # define Debug(fmt, args ...) do {printf(fmt "\n", ## args);} while(0)
  20. #else
  21. # define Debug(fmt, args ...)
  22. #endif
  23. extern const AP_HAL::HAL &hal;
  24. // Measurement range registers
  25. static const uint8_t CMD_PRANGE_MIN_MSB = 0x13;
  26. static const uint8_t CMD_PRANGE_MIN_LSB = 0x14;
  27. static const uint8_t CMD_PRANGE_MAX_MSB = 0x15;
  28. static const uint8_t CMD_PRANGE_MAX_LSB = 0x16;
  29. // write to this address to start pressure measurement
  30. static const uint8_t CMD_REQUEST_MEASUREMENT = 0xAC;
  31. AP_Baro_KellerLD::AP_Baro_KellerLD(AP_Baro &baro, AP_HAL::OwnPtr<AP_HAL::Device> dev)
  32. : AP_Baro_Backend(baro)
  33. , _dev(std::move(dev))
  34. {
  35. }
  36. // Look for the device on the bus and see if it responds appropriately
  37. AP_Baro_Backend *AP_Baro_KellerLD::probe(AP_Baro &baro, AP_HAL::OwnPtr<AP_HAL::Device> dev)
  38. {
  39. if (!dev) {
  40. return nullptr;
  41. }
  42. AP_Baro_KellerLD *sensor = new AP_Baro_KellerLD(baro, std::move(dev));
  43. if (!sensor || !sensor->_init()) {
  44. delete sensor;
  45. return nullptr;
  46. }
  47. return sensor;
  48. }
  49. // The hardware does not need to be reset/initialized
  50. // We read out the measurement range to be used in raw value conversions
  51. bool AP_Baro_KellerLD::_init()
  52. {
  53. if (!_dev) {
  54. return false;
  55. }
  56. if (!_dev->get_semaphore()->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
  57. AP_HAL::panic("PANIC: AP_Baro_KellerLD: failed to take serial semaphore for init");
  58. }
  59. // high retries for init
  60. _dev->set_retries(10);
  61. bool cal_read_ok = true;
  62. uint8_t data[3];
  63. uint16_t ms_word, ls_word;
  64. // This device has some undocumented finicky quirks and requires delays when reading out the
  65. // measurement range, but for some reason this isn't an issue when requesting measurements.
  66. // This is why we need to split the transfers with delays like this.
  67. // (Using AP_HAL::I2CDevice::set_split_transfers will not work with these sensors)
  68. // Read out pressure measurement range
  69. cal_read_ok &= _dev->transfer(&CMD_PRANGE_MIN_MSB, 1, nullptr, 0);
  70. hal.scheduler->delay(1);
  71. cal_read_ok &= _dev->transfer(nullptr, 0, &data[0], 3);
  72. hal.scheduler->delay(1);
  73. ms_word = (data[1] << 8) | data[2];
  74. Debug("0x13: %d [%d, %d, %d]", ms_word, data[0], data[1], data[2]);
  75. cal_read_ok &= _dev->transfer(&CMD_PRANGE_MIN_LSB, 1, nullptr, 0);
  76. hal.scheduler->delay(1);
  77. cal_read_ok &= _dev->transfer(nullptr, 0, &data[0], 3);
  78. hal.scheduler->delay(1);
  79. ls_word = (data[1] << 8) | data[2];
  80. Debug("0x14: %d [%d, %d, %d]", ls_word, data[0], data[1], data[2]);
  81. uint32_t cal_data = (ms_word << 16) | ls_word;
  82. memcpy(&_p_min, &cal_data, sizeof(_p_min));
  83. Debug("data: %d, p_min: %.2f", cal_data, _p_min);
  84. cal_read_ok &= _dev->transfer(&CMD_PRANGE_MAX_MSB, 1, nullptr, 0);
  85. hal.scheduler->delay(1);
  86. cal_read_ok &= _dev->transfer(nullptr, 0, &data[0], 3);
  87. hal.scheduler->delay(1);
  88. ms_word = (data[1] << 8) | data[2];
  89. Debug("0x15: %d [%d, %d, %d]", ms_word, data[0], data[1], data[2]);
  90. cal_read_ok &= _dev->transfer(&CMD_PRANGE_MAX_LSB, 1, nullptr, 0);
  91. hal.scheduler->delay(1);
  92. cal_read_ok &= _dev->transfer(nullptr, 0, &data[0], 3);
  93. hal.scheduler->delay(1);
  94. ls_word = (data[1] << 8) | data[2];
  95. Debug("0x16: %d [%d, %d, %d]", ls_word, data[0], data[1], data[2]);
  96. cal_data = (ms_word << 16) | ls_word;
  97. memcpy(&_p_max, &cal_data, sizeof(_p_max));
  98. Debug("data: %d, p_max: %.2f", cal_data, _p_max);
  99. cal_read_ok &= !isnan(_p_min) && !isinf(_p_min) && !isnan(_p_max) && !isinf(_p_max);
  100. cal_read_ok &= _p_max > _p_min;
  101. if (!cal_read_ok) {
  102. printf("Cal read bad!\n");
  103. _dev->get_semaphore()->give();
  104. return false;
  105. }
  106. printf("Keller LD found on bus %u address 0x%02x\n", _dev->bus_num(), _dev->get_bus_address());
  107. // Send a command to take a measurement
  108. _dev->transfer(&CMD_REQUEST_MEASUREMENT, 1, nullptr, 0);
  109. memset(&_accum, 0, sizeof(_accum));
  110. _instance = _frontend.register_sensor();
  111. _frontend.set_type(_instance, AP_Baro::BARO_TYPE_WATER);
  112. // lower retries for run
  113. _dev->set_retries(3);
  114. _dev->get_semaphore()->give();
  115. // The sensor needs time to take a deep breath after reading out the calibration...
  116. hal.scheduler->delay(150);
  117. // Request 50Hz update
  118. // The sensor really struggles with any jitter in timing at 100Hz, and will sometimes start reading out all zeros
  119. _dev->register_periodic_callback(20 * AP_USEC_PER_MSEC,
  120. FUNCTOR_BIND_MEMBER(&AP_Baro_KellerLD::_timer, void));
  121. return true;
  122. }
  123. // Read out most recent measurement from sensor hw
  124. bool AP_Baro_KellerLD::_read()
  125. {
  126. uint8_t data[5];
  127. if (!_dev->transfer(0x0, 1, data, sizeof(data))) {
  128. Debug("Keller LD read failed!");
  129. return false;
  130. }
  131. //uint8_t status = data[0];
  132. uint16_t pressure_raw = (data[1] << 8) | data[2];
  133. uint16_t temperature_raw = (data[3] << 8) | data[4];
  134. #if KELLER_DEBUG
  135. static uint8_t samples = 0;
  136. if (samples < 3) {
  137. samples++;
  138. Debug("data: [%d, %d, %d, %d, %d]", data[0], data[1], data[2], data[3], data[4]);
  139. Debug("pressure_raw: %d\ttemperature_raw: %d", pressure_raw, temperature_raw);
  140. }
  141. #endif
  142. if (pressure_raw == 0 || temperature_raw == 0) {
  143. Debug("Keller: bad read");
  144. return false;
  145. }
  146. if (!pressure_ok(pressure_raw)) {
  147. return false;
  148. }
  149. WITH_SEMAPHORE(_sem);
  150. _update_and_wrap_accumulator(pressure_raw, temperature_raw, 128);
  151. return true;
  152. }
  153. // Periodic callback, regular update at 50Hz
  154. // Read out most recent measurement, and request another
  155. // Max conversion time according to datasheet is ~8ms, so
  156. // max update rate is ~125Hz, yet we struggle to get consistent
  157. // performance/data at 100Hz
  158. void AP_Baro_KellerLD::_timer(void)
  159. {
  160. _read();
  161. _dev->transfer(&CMD_REQUEST_MEASUREMENT, 1, nullptr, 0);
  162. }
  163. // Accumulate a reading, shrink if necessary to prevent overflow
  164. void AP_Baro_KellerLD::_update_and_wrap_accumulator(uint16_t pressure, uint16_t temperature, uint8_t max_count)
  165. {
  166. _accum.sum_pressure += pressure;
  167. _accum.sum_temperature += temperature;
  168. _accum.num_samples += 1;
  169. if (_accum.num_samples == max_count) {
  170. _accum.sum_pressure /= 2;
  171. _accum.sum_temperature /= 2;
  172. _accum.num_samples /= 2;
  173. }
  174. }
  175. // Take the average of accumulated values and push to frontend
  176. void AP_Baro_KellerLD::update()
  177. {
  178. float sum_pressure, sum_temperature;
  179. float num_samples;
  180. {
  181. WITH_SEMAPHORE(_sem);
  182. if (_accum.num_samples == 0) {
  183. return;
  184. }
  185. sum_pressure = _accum.sum_pressure;
  186. sum_temperature = _accum.sum_temperature;
  187. num_samples = _accum.num_samples;
  188. memset(&_accum, 0, sizeof(_accum));
  189. }
  190. uint16_t raw_pressure_avg = sum_pressure / num_samples;
  191. uint16_t raw_temperature_avg = sum_temperature / num_samples;
  192. // per datasheet
  193. float pressure = (raw_pressure_avg - 16384) * (_p_max - _p_min) / 32768 + _p_min;
  194. pressure *= 100000; // bar -> Pascal
  195. // pressure += 101300; // MSL pressure offset
  196. float temperature = ((raw_temperature_avg >> 4) - 24) * 0.05f - 50;
  197. _copy_to_frontend(_instance, pressure, temperature);
  198. }