encoder_driver.ino 1.8 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576777879808182838485868788899091929394
  1. /**************************************************************
  2. Encoder definitions
  3. Encoder A: connect interrupt 0, 1--[pin 2, 3];
  4. Encoder B: connect interrupt 2, 3--[pin 21, 20];
  5. Encoder C: connect intterupt 4, 5--[pin 19, 18]
  6. ************************************************************ */
  7. static volatile long A_enc_pos = 0L;
  8. static volatile long B_enc_pos = 0L;
  9. static volatile long C_enc_pos = 0L;
  10. /*init encoder connect pin*/
  11. void initEncoders()
  12. {
  13. pinMode(ENC_A_PIN_A, INPUT);
  14. pinMode(ENC_A_PIN_B, INPUT);
  15. attachInterrupt(0, encoderA_ISR, CHANGE);
  16. attachInterrupt(1, encoderA_ISR, CHANGE);
  17. pinMode(ENC_B_PIN_A, INPUT);
  18. pinMode(ENC_B_PIN_B, INPUT);
  19. attachInterrupt(2, encoderB_ISR, CHANGE);
  20. attachInterrupt(3, encoderB_ISR, CHANGE);
  21. pinMode(ENC_C_PIN_A, INPUT);
  22. pinMode(ENC_C_PIN_B, INPUT);
  23. attachInterrupt(4, encoderC_ISR, CHANGE);
  24. attachInterrupt(5, encoderC_ISR, CHANGE);
  25. }
  26. /* Interrupt routine for A encoder, taking care of actual counting */
  27. void encoderA_ISR ()
  28. {
  29. if (directionWheel(A_WHEEL) == BACKWARDS)
  30. {
  31. A_enc_pos--;
  32. }
  33. else
  34. {
  35. A_enc_pos++;
  36. }
  37. }
  38. /* Interrupt routine for B encoder, taking care of actual counting */
  39. void encoderB_ISR ()
  40. {
  41. if (directionWheel(B_WHEEL) == BACKWARDS)
  42. {
  43. B_enc_pos--;
  44. }
  45. else
  46. {
  47. B_enc_pos++;
  48. }
  49. }
  50. /* Interrupt routine for C encoder, taking care of actual counting */
  51. void encoderC_ISR ()
  52. {
  53. if (directionWheel(C_WHEEL) == BACKWARDS)
  54. {
  55. C_enc_pos--;
  56. }
  57. else
  58. {
  59. C_enc_pos++;
  60. }
  61. }
  62. /* Wrap the encoder reading function */
  63. long readEncoder(int i)
  64. {
  65. if (i == A_WHEEL)
  66. {
  67. return A_enc_pos;
  68. }
  69. else if (i == B_WHEEL)
  70. {
  71. return B_enc_pos;
  72. }
  73. else
  74. {
  75. return C_enc_pos;
  76. }
  77. }
  78. /* Wrap the encoder reset function */
  79. void resetEncoders() {
  80. A_enc_pos = 0L;
  81. B_enc_pos = 0L;
  82. C_enc_pos = 0L;
  83. }