RPM_Pin.cpp 4.0 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111
  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 "RPM_Pin.h"
  15. #include <AP_HAL/GPIO.h>
  16. #include <GCS_MAVLink/GCS.h>
  17. extern const AP_HAL::HAL& hal;
  18. AP_RPM_Pin::IrqState AP_RPM_Pin::irq_state[RPM_MAX_INSTANCES];
  19. /*
  20. open the sensor in constructor
  21. */
  22. AP_RPM_Pin::AP_RPM_Pin(AP_RPM &_ap_rpm, uint8_t instance, AP_RPM::RPM_State &_state) :
  23. AP_RPM_Backend(_ap_rpm, instance, _state)
  24. {
  25. }
  26. /*
  27. handle interrupt on an instance
  28. */
  29. void AP_RPM_Pin::irq_handler(uint8_t pin, bool pin_state, uint32_t timestamp)
  30. {
  31. const uint32_t dt = timestamp - irq_state[state.instance].last_pulse_us;
  32. irq_state[state.instance].last_pulse_us = timestamp;
  33. // we don't accept pulses less than 100us. Using an irq for such
  34. // high RPM is too inaccurate, and it is probably just bounce of
  35. // the signal which we should ignore
  36. if (dt > 100 && dt < 1000*1000) {
  37. irq_state[state.instance].dt_sum += dt;
  38. irq_state[state.instance].dt_count++;
  39. }
  40. }
  41. void AP_RPM_Pin::update(void)
  42. {
  43. if (last_pin != get_pin()) {
  44. // detach from last pin
  45. if (last_pin != (uint8_t)-1 &&
  46. !hal.gpio->detach_interrupt(last_pin)) {
  47. gcs().send_text(MAV_SEVERITY_WARNING, "RPM: Failed to detach from pin %u", last_pin);
  48. // ignore this failure or the user may be stuck
  49. }
  50. irq_state[state.instance].dt_count = 0;
  51. irq_state[state.instance].dt_sum = 0;
  52. // attach to new pin
  53. last_pin = get_pin();
  54. if (last_pin) {
  55. hal.gpio->pinMode(last_pin, HAL_GPIO_INPUT);
  56. if (!hal.gpio->attach_interrupt(
  57. last_pin,
  58. FUNCTOR_BIND_MEMBER(&AP_RPM_Pin::irq_handler, void, uint8_t, bool, uint32_t),
  59. AP_HAL::GPIO::INTERRUPT_RISING)) {
  60. gcs().send_text(MAV_SEVERITY_WARNING, "RPM: Failed to attach to pin %u", last_pin);
  61. }
  62. }
  63. }
  64. if (irq_state[state.instance].dt_count > 0) {
  65. float dt_avg;
  66. // disable interrupts to prevent race with irq_handler
  67. void *irqstate = hal.scheduler->disable_interrupts_save();
  68. dt_avg = irq_state[state.instance].dt_sum / irq_state[state.instance].dt_count;
  69. irq_state[state.instance].dt_count = 0;
  70. irq_state[state.instance].dt_sum = 0;
  71. hal.scheduler->restore_interrupts(irqstate);
  72. const float scaling = ap_rpm._scaling[state.instance];
  73. float maximum = ap_rpm._maximum[state.instance];
  74. float minimum = ap_rpm._minimum[state.instance];
  75. float quality = 0;
  76. float rpm = scaling * (1.0e6 / dt_avg) * 60;
  77. float filter_value = signal_quality_filter.get();
  78. state.rate_rpm = signal_quality_filter.apply(rpm);
  79. if ((maximum <= 0 || rpm <= maximum) && (rpm >= minimum)) {
  80. if (is_zero(filter_value)){
  81. quality = 0;
  82. } else {
  83. quality = 1 - constrain_float((fabsf(rpm-filter_value))/filter_value, 0.0, 1.0);
  84. quality = powf(quality, 2.0);
  85. }
  86. state.last_reading_ms = AP_HAL::millis();
  87. } else {
  88. quality = 0;
  89. }
  90. state.signal_quality = (0.1 * quality) + (0.9 * state.signal_quality);
  91. }
  92. // assume we get readings at at least 1Hz, otherwise reset quality to zero
  93. if (AP_HAL::millis() - state.last_reading_ms > 1000) {
  94. state.signal_quality = 0;
  95. state.rate_rpm = 0;
  96. }
  97. }