1
0

encoder_driver.ino 2.0 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899
  1. /**************************************************************
  2. Description: Encoder definitions需要连接到arduinoMega2560的正确引脚上:
  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. Author: www.corvin.cn
  7. History: 20180209:init this file;
  8. **************************************************************/
  9. #include "motor_driver.h"
  10. #include "encoder_driver.h"
  11. static volatile long A_enc_cnt = 0L;
  12. static volatile long B_enc_cnt = 0L;
  13. static volatile long C_enc_cnt = 0L;
  14. /*init encoder connect pin, config ISR functions*/
  15. void initEncoders(void)
  16. {
  17. pinMode(ENC_A_PIN_A, INPUT);
  18. pinMode(ENC_A_PIN_B, INPUT);
  19. attachInterrupt(3, encoderA_ISR, CHANGE);
  20. attachInterrupt(2, encoderA_ISR, CHANGE);
  21. pinMode(ENC_B_PIN_A, INPUT);
  22. pinMode(ENC_B_PIN_B, INPUT);
  23. attachInterrupt(0, encoderB_ISR, CHANGE);
  24. attachInterrupt(1, encoderB_ISR, CHANGE);
  25. pinMode(ENC_C_PIN_A, INPUT);
  26. pinMode(ENC_C_PIN_B, INPUT);
  27. attachInterrupt(5, encoderC_ISR, CHANGE);
  28. attachInterrupt(4, encoderC_ISR, CHANGE);
  29. }
  30. /* Interrupt routine for A encoder, taking care of actual counting */
  31. void encoderA_ISR (void)
  32. {
  33. if (directionWheel(A_WHEEL) == BACKWARDS)
  34. {
  35. A_enc_cnt--;
  36. }
  37. else
  38. {
  39. A_enc_cnt++;
  40. }
  41. }
  42. /* Interrupt routine for B encoder, taking care of actual counting */
  43. void encoderB_ISR (void)
  44. {
  45. if (directionWheel(B_WHEEL) == BACKWARDS)
  46. {
  47. B_enc_cnt--;
  48. }
  49. else
  50. {
  51. B_enc_cnt++;
  52. }
  53. }
  54. /* Interrupt routine for C encoder, taking care of actual counting */
  55. void encoderC_ISR (void)
  56. {
  57. if (directionWheel(C_WHEEL) == BACKWARDS)
  58. {
  59. C_enc_cnt--;
  60. }
  61. else
  62. {
  63. C_enc_cnt++;
  64. }
  65. }
  66. /* Wrap the encoder reading function */
  67. long readEncoder(int i)
  68. {
  69. if (i == A_WHEEL)
  70. {
  71. return A_enc_cnt;
  72. }
  73. else if (i == B_WHEEL)
  74. {
  75. return B_enc_cnt;
  76. }
  77. else
  78. {
  79. return C_enc_cnt;
  80. }
  81. }
  82. /* Wrap the encoder count reset function */
  83. void resetEncoders(void)
  84. {
  85. A_enc_cnt = 0L;
  86. B_enc_cnt = 0L;
  87. C_enc_cnt = 0L;
  88. }