AP_BattMonitor_FuelLevel_PWM.cpp 2.9 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576777879808182838485868788899091929394
  1. #include <AP_HAL/AP_HAL.h>
  2. #include "AP_BattMonitor_FuelLevel_PWM.h"
  3. #include <GCS_MAVLink/GCS.h>
  4. /*
  5. "battery" monitor for liquid fuel level systems that give a PWM value indicating quantity of remaining fuel.
  6. Output is:
  7. - mAh remaining is fuel level in millilitres
  8. - consumed mAh is in consumed millilitres
  9. - fixed 1.0v voltage
  10. */
  11. extern const AP_HAL::HAL& hal;
  12. /// Constructor
  13. AP_BattMonitor_FuelLevel_PWM::AP_BattMonitor_FuelLevel_PWM(AP_BattMonitor &mon, AP_BattMonitor::BattMonitor_State &mon_state, AP_BattMonitor_Params &params) :
  14. AP_BattMonitor_Backend(mon, mon_state, params)
  15. {
  16. _state.voltage = 1.0; // show a fixed voltage of 1v
  17. // need to add check
  18. _state.healthy = false;
  19. }
  20. /*
  21. handle interrupt on an instance
  22. */
  23. void AP_BattMonitor_FuelLevel_PWM::irq_handler(uint8_t pin, bool pin_state, uint32_t timestamp)
  24. {
  25. if (pin_state == 1) {
  26. irq_state.last_pulse_us = timestamp;
  27. } else if (irq_state.last_pulse_us != 0) {
  28. irq_state.pulse_width_us = timestamp - irq_state.last_pulse_us;
  29. irq_state.pulse_count1 ++;
  30. }
  31. }
  32. /*
  33. read - read the "voltage" and "current"
  34. */
  35. void AP_BattMonitor_FuelLevel_PWM::read()
  36. {
  37. int8_t pin = _params._curr_pin;
  38. if (last_pin != pin) {
  39. // detach from last pin
  40. if (last_pin != -1) {
  41. hal.gpio->detach_interrupt(last_pin);
  42. }
  43. // attach to new pin
  44. last_pin = pin;
  45. if (last_pin > 0) {
  46. hal.gpio->pinMode(last_pin, HAL_GPIO_INPUT);
  47. if (!hal.gpio->attach_interrupt(
  48. last_pin,
  49. FUNCTOR_BIND_MEMBER(&AP_BattMonitor_FuelLevel_PWM::irq_handler, void, uint8_t, bool, uint32_t),
  50. AP_HAL::GPIO::INTERRUPT_BOTH)) {
  51. gcs().send_text(MAV_SEVERITY_WARNING, "FuelLevelPWM: Failed to attach to pin %u", unsigned(last_pin));
  52. }
  53. }
  54. }
  55. uint32_t now_us = AP_HAL::micros();
  56. if (pulse_count2 == irq_state.pulse_count1) {
  57. _state.healthy = (now_us - _state.last_time_micros) < 250000U;
  58. return;
  59. }
  60. uint32_t pulse_width = irq_state.pulse_width_us;
  61. pulse_count2 = irq_state.pulse_count1;
  62. /*
  63. this driver assumes that CAPACITY is set to tank volume in millilitres.
  64. */
  65. const uint16_t pwm_empty = 1100;
  66. const uint16_t pwm_full = 1900;
  67. const uint16_t pwm_buffer = 20;
  68. // check for invalid pulse
  69. if (pulse_width <= (pwm_empty - pwm_buffer)|| pulse_width >= (pwm_full + pwm_buffer)) {
  70. return;
  71. }
  72. pulse_width = constrain_int16(pulse_width, pwm_empty, pwm_full);
  73. float proportion_full = (pulse_width - pwm_empty) / float(pwm_full - pwm_empty);
  74. float proportion_used = 1.0 - proportion_full;
  75. _state.last_time_micros = now_us;
  76. _state.healthy = true;
  77. // map consumed_mah to consumed millilitres
  78. _state.consumed_mah = proportion_used * _params._pack_capacity;
  79. // map consumed_wh using fixed voltage of 1
  80. _state.consumed_wh = _state.consumed_mah;
  81. }