AP_BattMonitor_BLHeliESC.cpp 2.4 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990
  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_HAL/AP_HAL.h>
  14. #include <AP_BLHeli/AP_BLHeli.h>
  15. #ifdef HAVE_AP_BLHELI_SUPPORT
  16. #include "AP_BattMonitor_BLHeliESC.h"
  17. extern const AP_HAL::HAL &hal;
  18. void AP_BattMonitor_BLHeliESC::init(void)
  19. {
  20. }
  21. void AP_BattMonitor_BLHeliESC::read(void)
  22. {
  23. AP_BLHeli *blheli = AP_BLHeli::get_singleton();
  24. if (!blheli) {
  25. return;
  26. }
  27. uint8_t num_escs = 0;
  28. float voltage_sum = 0;
  29. float current_sum = 0;
  30. float consumed_sum = 0;
  31. float temperature_sum = 0;
  32. uint32_t now = AP_HAL::millis();
  33. uint32_t highest_ms = 0;
  34. for (uint8_t i=0; i<AP_BLHELI_MAX_ESCS; i++) {
  35. AP_BLHeli::telem_data td;
  36. if (!blheli->get_telem_data(i, td)) {
  37. continue;
  38. }
  39. // accumulate consumed_sum regardless of age, to cope with ESC
  40. // dropping out
  41. consumed_sum += td.consumption;
  42. if (now - td.timestamp_ms > 1000) {
  43. // don't use old data
  44. continue;
  45. }
  46. num_escs++;
  47. voltage_sum += td.voltage;
  48. current_sum += td.current;
  49. temperature_sum += td.temperature;
  50. if (td.timestamp_ms > highest_ms) {
  51. highest_ms = td.timestamp_ms;
  52. }
  53. }
  54. if (num_escs > 0) {
  55. _state.voltage = (voltage_sum / num_escs) * 0.01;
  56. _state.temperature = temperature_sum / num_escs;
  57. _state.healthy = true;
  58. } else {
  59. _state.voltage = 0;
  60. _state.temperature = 0;
  61. _state.healthy = false;
  62. }
  63. _state.current_amps = current_sum * 0.01;
  64. _state.consumed_mah = consumed_sum;
  65. _state.last_time_micros = highest_ms * 1000;
  66. _state.temperature_time = highest_ms;
  67. if (current_sum > 0) {
  68. // if we have ever got a current value then we know we have a
  69. // current sensor
  70. have_current = true;
  71. }
  72. }
  73. #endif // HAVE_AP_BLHELI_SUPPORT