WheelEncoder_Quadrature.cpp 4.6 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148
  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 "WheelEncoder_Quadrature.h"
  15. #include <GCS_MAVLink/GCS.h>
  16. extern const AP_HAL::HAL& hal;
  17. // constructor
  18. AP_WheelEncoder_Quadrature::AP_WheelEncoder_Quadrature(AP_WheelEncoder &frontend, uint8_t instance, AP_WheelEncoder::WheelEncoder_State &state) :
  19. AP_WheelEncoder_Backend(frontend, instance, state)
  20. {
  21. }
  22. // check if pin has changed and initialise gpio event callback
  23. void AP_WheelEncoder_Quadrature::update_pin(uint8_t &pin,
  24. uint8_t new_pin,
  25. uint8_t &pin_value)
  26. {
  27. if (new_pin == pin) {
  28. // no change
  29. return;
  30. }
  31. // remove old gpio event callback if present
  32. if (pin != (uint8_t)-1 &&
  33. !hal.gpio->detach_interrupt(pin)) {
  34. gcs().send_text(MAV_SEVERITY_WARNING, "WEnc: Failed to detach from pin %u", pin);
  35. // ignore this failure or the user may be stuck
  36. }
  37. pin = new_pin;
  38. // install interrupt handler on rising or falling edge of gpio for pin a
  39. if (new_pin != (uint8_t)-1) {
  40. hal.gpio->pinMode(pin, HAL_GPIO_INPUT);
  41. if (!hal.gpio->attach_interrupt(
  42. pin,
  43. FUNCTOR_BIND_MEMBER(&AP_WheelEncoder_Quadrature::irq_handler,
  44. void,
  45. uint8_t,
  46. bool,
  47. uint32_t),
  48. AP_HAL::GPIO::INTERRUPT_BOTH)) {
  49. gcs().send_text(MAV_SEVERITY_WARNING, "WEnc: Failed to attach to pin %u", pin);
  50. }
  51. pin_value = hal.gpio->read(pin);
  52. }
  53. }
  54. void AP_WheelEncoder_Quadrature::update(void)
  55. {
  56. update_pin(last_pin_a, get_pin_a(), last_pin_a_value);
  57. update_pin(last_pin_b, get_pin_b(), last_pin_b_value);
  58. // disable interrupts to prevent race with irq_handler
  59. void *irqstate = hal.scheduler->disable_interrupts_save();
  60. // copy distance and error count so it is accessible to front end
  61. copy_state_to_frontend(irq_state.distance_count,
  62. irq_state.total_count,
  63. irq_state.error_count,
  64. irq_state.last_reading_ms);
  65. // restore interrupts
  66. hal.scheduler->restore_interrupts(irqstate);
  67. }
  68. // convert pin a and pin b state to a wheel encoder phase
  69. uint8_t AP_WheelEncoder_Quadrature::pin_ab_to_phase(bool pin_a, bool pin_b)
  70. {
  71. if (!pin_a) {
  72. if (!pin_b) {
  73. // A = 0, B = 0
  74. return 0;
  75. } else {
  76. // A = 0, B = 1
  77. return 1;
  78. }
  79. } else {
  80. if (!pin_b) {
  81. // A = 1, B = 0
  82. return 3;
  83. } else {
  84. // A = 1, B = 1
  85. return 2;
  86. }
  87. }
  88. return (uint8_t)pin_a << 1 | (uint8_t)pin_b;
  89. }
  90. void AP_WheelEncoder_Quadrature::update_phase_and_error_count()
  91. {
  92. // convert pin state before and after to phases
  93. uint8_t phase_after = pin_ab_to_phase(last_pin_a_value, last_pin_b_value);
  94. // look for invalid changes
  95. uint8_t step_forward = irq_state.phase < 3 ? irq_state.phase+1 : 0;
  96. uint8_t step_back = irq_state.phase > 0 ? irq_state.phase-1 : 3;
  97. if (phase_after == step_forward) {
  98. irq_state.phase = phase_after;
  99. irq_state.distance_count++;
  100. } else if (phase_after == step_back) {
  101. irq_state.phase = phase_after;
  102. irq_state.distance_count--;
  103. } else {
  104. irq_state.error_count++;
  105. }
  106. irq_state.total_count++;
  107. }
  108. void AP_WheelEncoder_Quadrature::irq_handler(uint8_t pin,
  109. bool pin_value,
  110. uint32_t timestamp)
  111. {
  112. // sanity check
  113. if (last_pin_a == 0 || last_pin_b == 0) {
  114. return;
  115. }
  116. // update distance and error counts
  117. if (pin == last_pin_a) {
  118. last_pin_a_value = pin_value;
  119. } else if (pin == last_pin_b) {
  120. last_pin_b_value = pin_value;
  121. } else {
  122. return;
  123. };
  124. update_phase_and_error_count();
  125. // record update time
  126. irq_state.last_reading_ms = timestamp;
  127. }