TSYS01.cpp 3.1 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134
  1. #include "TSYS01.h"
  2. #include <utility>
  3. #include <stdio.h>
  4. #include <AP_HAL/AP_HAL.h>
  5. #include <AP_HAL/I2CDevice.h>
  6. #include <AP_Math/AP_Math.h>
  7. extern const AP_HAL::HAL &hal;
  8. static const uint8_t TSYS01_CMD_RESET = 0x1E;
  9. static const uint8_t TSYS01_CMD_READ_PROM = 0xA0;
  10. static const uint8_t TSYS01_CMD_CONVERT = 0x40;
  11. static const uint8_t TSYS01_CMD_READ_ADC = 0x00;
  12. bool TSYS01::init(uint8_t bus)
  13. {
  14. _dev = std::move(hal.i2c_mgr->get_device(bus, TSYS01_ADDR));
  15. if (!_dev) {
  16. printf("TSYS01 device is null!");
  17. return false;
  18. }
  19. if (!_dev->get_semaphore()->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
  20. AP_HAL::panic("PANIC: TSYS01: failed to take serial semaphore for init");
  21. }
  22. _dev->set_retries(10);
  23. if (!_reset()) {
  24. printf("TSYS01 reset failed");
  25. _dev->get_semaphore()->give();
  26. return false;
  27. }
  28. hal.scheduler->delay(4);
  29. if (!_read_prom()) {
  30. printf("TSYS01 prom read failed");
  31. _dev->get_semaphore()->give();
  32. return false;
  33. }
  34. _convert();
  35. // lower retries for run
  36. _dev->set_retries(3);
  37. _dev->get_semaphore()->give();
  38. /* Request 20Hz update */
  39. // Max conversion time is 9.04 ms
  40. _dev->register_periodic_callback(50 * AP_USEC_PER_MSEC,
  41. FUNCTOR_BIND_MEMBER(&TSYS01::_timer, void));
  42. return true;
  43. }
  44. bool TSYS01::_reset()
  45. {
  46. return _dev->transfer(&TSYS01_CMD_RESET, 1, nullptr, 0);
  47. }
  48. // Register map
  49. // prom word Address
  50. // 0 0xA0 -> unused
  51. // 1 0xA2 -> _k[4]
  52. // 2 0xA4 -> _k[3]
  53. // 3 0xA6 -> _k[2]
  54. // 4 0xA8 -> _k[1]
  55. // 5 0xAA -> _k[0]
  56. // 6 0xAC -> unused
  57. // 7 0xAE -> unused
  58. bool TSYS01::_read_prom()
  59. {
  60. bool success = false;
  61. for (int i = 0; i < 5; i++) {
  62. // Read only the prom values that we use
  63. _k[i] = _read_prom_word(5-i);
  64. success |= _k[i] != 0;
  65. }
  66. return success;
  67. }
  68. // Borrowed from MS Baro driver
  69. uint16_t TSYS01::_read_prom_word(uint8_t word)
  70. {
  71. const uint8_t reg = TSYS01_CMD_READ_PROM + (word << 1);
  72. uint8_t val[2];
  73. if (!_dev->transfer(&reg, 1, val, 2)) {
  74. return 0;
  75. }
  76. return (val[0] << 8) | val[1];
  77. }
  78. bool TSYS01::_convert()
  79. {
  80. return _dev->transfer(&TSYS01_CMD_CONVERT, 1, nullptr, 0);
  81. }
  82. uint32_t TSYS01::_read_adc()
  83. {
  84. uint8_t val[3];
  85. if (!_dev->transfer(&TSYS01_CMD_READ_ADC, 1, val, 3)) {
  86. return 0;
  87. }
  88. return (val[0] << 16) | (val[1] << 8) | val[2];
  89. }
  90. void TSYS01::_timer(void)
  91. {
  92. uint32_t adc = _read_adc();
  93. _healthy = adc != 0;
  94. if (_healthy) {
  95. _calculate(adc);
  96. } else {
  97. _temperature = 0;
  98. }
  99. //printf("\nTemperature: %.2lf C", _temperature);
  100. _convert();
  101. }
  102. void TSYS01::_calculate(uint32_t adc)
  103. {
  104. float adc16 = adc/256;
  105. _temperature =
  106. -2 * _k[4] * powf(10, -21) * powf(adc16, 4) +
  107. 4 * _k[3] * powf(10, -16) * powf(adc16, 3) +
  108. -2 * _k[2] * powf(10, -11) * powf(adc16, 2) +
  109. 1 * _k[1] * powf(10, -6) * adc16 +
  110. -1.5 * _k[0] * powf(10, -2);
  111. }