AP_BattMonitor_SMBus_Maxell.cpp 5.7 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175
  1. #include <AP_HAL/AP_HAL.h>
  2. #include <AP_Common/AP_Common.h>
  3. #include <AP_Math/AP_Math.h>
  4. #include "AP_BattMonitor.h"
  5. #include "AP_BattMonitor_SMBus_Maxell.h"
  6. #include <utility>
  7. #define BATTMONITOR_SMBUS_MAXELL_NUM_CELLS 6
  8. uint8_t maxell_cell_ids[] = { 0x3f, // cell 1
  9. 0x3e, // cell 2
  10. 0x3d, // cell 3
  11. 0x3c, // cell 4
  12. 0x3b, // cell 5
  13. 0x3a}; // cell 6
  14. #define SMBUS_READ_BLOCK_MAXIMUM_TRANSFER 0x20 // A Block Read or Write is allowed to transfer a maximum of 32 data bytes.
  15. /*
  16. * Other potentially useful registers, listed here for future use
  17. * #define BATTMONITOR_SMBUS_MAXELL_CHARGE_STATUS 0x0d // relative state of charge
  18. * #define BATTMONITOR_SMBUS_MAXELL_BATTERY_STATUS 0x16 // battery status register including alarms
  19. * #define BATTMONITOR_SMBUS_MAXELL_BATTERY_CYCLE_COUNT 0x17 // cycle count
  20. * #define BATTMONITOR_SMBUS_MAXELL_DESIGN_VOLTAGE 0x19 // design voltage register
  21. * #define BATTMONITOR_SMBUS_MAXELL_MANUFACTURE_DATE 0x1b // manufacturer date
  22. * #define BATTMONITOR_SMBUS_MAXELL_SERIALNUM 0x1c // serial number register
  23. * #define BATTMONITOR_SMBUS_MAXELL_HEALTH_STATUS 0x4f // state of health
  24. * #define BATTMONITOR_SMBUS_MAXELL_SAFETY_ALERT 0x50 // safety alert
  25. * #define BATTMONITOR_SMBUS_MAXELL_SAFETY_STATUS 0x51 // safety status
  26. * #define BATTMONITOR_SMBUS_MAXELL_PF_ALERT 0x52 // safety status
  27. * #define BATTMONITOR_SMBUS_MAXELL_PF_STATUS 0x53 // safety status
  28. */
  29. // Constructor
  30. AP_BattMonitor_SMBus_Maxell::AP_BattMonitor_SMBus_Maxell(AP_BattMonitor &mon,
  31. AP_BattMonitor::BattMonitor_State &mon_state,
  32. AP_BattMonitor_Params &params,
  33. AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev)
  34. : AP_BattMonitor_SMBus(mon, mon_state, params, std::move(dev))
  35. {}
  36. void AP_BattMonitor_SMBus_Maxell::timer()
  37. {
  38. // check if PEC is supported
  39. if (!check_pec_support()) {
  40. return;
  41. }
  42. uint16_t data;
  43. uint32_t tnow = AP_HAL::micros();
  44. // read voltage (V)
  45. if (read_word(BATTMONITOR_SMBUS_VOLTAGE, data)) {
  46. _state.voltage = (float)data / 1000.0f;
  47. _state.last_time_micros = tnow;
  48. _state.healthy = true;
  49. }
  50. // read cell voltages
  51. for (uint8_t i = 0; i < BATTMONITOR_SMBUS_MAXELL_NUM_CELLS; i++) {
  52. if (read_word(maxell_cell_ids[i], data)) {
  53. _has_cell_voltages = true;
  54. _state.cell_voltages.cells[i] = data;
  55. } else {
  56. _state.cell_voltages.cells[i] = UINT16_MAX;
  57. }
  58. }
  59. // timeout after 5 seconds
  60. if ((tnow - _state.last_time_micros) > AP_BATTMONITOR_SMBUS_TIMEOUT_MICROS) {
  61. _state.healthy = false;
  62. return;
  63. }
  64. // read current (A)
  65. if (read_word(BATTMONITOR_SMBUS_CURRENT, data)) {
  66. _state.current_amps = -(float)((int16_t)data) / 1000.0f;
  67. _state.last_time_micros = tnow;
  68. }
  69. read_full_charge_capacity();
  70. // FIXME: Perform current integration if the remaining capacity can't be requested
  71. read_remaining_capacity();
  72. read_temp();
  73. read_serial_number();
  74. }
  75. // read_block - returns number of characters read if successful, zero if unsuccessful
  76. uint8_t AP_BattMonitor_SMBus_Maxell::read_block(uint8_t reg, uint8_t* data, bool append_zero) const
  77. {
  78. // get length
  79. uint8_t bufflen;
  80. // read byte (first byte indicates the number of bytes in the block)
  81. if (!_dev->read_registers(reg, &bufflen, 1)) {
  82. return 0;
  83. }
  84. // sanity check length returned by smbus
  85. if (bufflen == 0 || bufflen > SMBUS_READ_BLOCK_MAXIMUM_TRANSFER) {
  86. return 0;
  87. }
  88. // buffer to hold results (2 extra byte returned holding length and PEC)
  89. const uint8_t read_size = bufflen + 1 + (_pec_supported ? 1 : 0);
  90. uint8_t buff[read_size];
  91. // read bytes
  92. if (!_dev->read_registers(reg, buff, read_size)) {
  93. return 0;
  94. }
  95. // check PEC
  96. if (_pec_supported) {
  97. uint8_t pec = get_PEC(AP_BATTMONITOR_SMBUS_I2C_ADDR, reg, true, buff, bufflen+1);
  98. if (pec != buff[bufflen+1]) {
  99. return 0;
  100. }
  101. }
  102. // copy data (excluding PEC)
  103. memcpy(data, &buff[1], bufflen);
  104. // optionally add zero to end
  105. if (append_zero) {
  106. data[bufflen] = '\0';
  107. }
  108. // return success
  109. return bufflen;
  110. }
  111. // check if PEC supported with the version value in SpecificationInfo() function
  112. // returns true once PEC is confirmed as working or not working
  113. bool AP_BattMonitor_SMBus_Maxell::check_pec_support()
  114. {
  115. // exit immediately if we have already confirmed pec support
  116. if (_pec_confirmed) {
  117. return true;
  118. }
  119. // specification info
  120. uint16_t data;
  121. if (!read_word(BATTMONITOR_SMBUS_SPECIFICATION_INFO, data)) {
  122. return false;
  123. }
  124. // extract version
  125. uint8_t version = (data & 0xF0) >> 4;
  126. // version less than 0011b (i.e. 3) do not support PEC
  127. if (version < 3) {
  128. _pec_supported = false;
  129. _pec_confirmed = true;
  130. return true;
  131. }
  132. // check manufacturer name
  133. uint8_t buff[SMBUS_READ_BLOCK_MAXIMUM_TRANSFER + 1];
  134. if (read_block(BATTMONITOR_SMBUS_MANUFACTURE_NAME, buff, true)) {
  135. // Hitachi maxell batteries do not support PEC
  136. if (strcmp((char*)buff, "Hitachi maxell") == 0) {
  137. _pec_supported = false;
  138. _pec_confirmed = true;
  139. return true;
  140. }
  141. }
  142. // assume all other batteries support PEC
  143. _pec_supported = true;
  144. _pec_confirmed = true;
  145. return true;
  146. }