motor_driver.ino 2.7 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139
  1. /***************************************************************
  2. Description: Motor driver definitions;
  3. Author: www.corvin.cn
  4. Hisotry: 20180209: init this file;
  5. *************************************************************/
  6. #include "motor_driver.h"
  7. /* Maximum PWM signal */
  8. #define MAX_PWM 255
  9. //three motors control pin define
  10. static const int A_IN1 = 26;
  11. static const int A_IN2 = 28;
  12. static const int A_PWM = 4; //A wheel pwm pin
  13. static const int B_IN1 = 30;
  14. static const int B_IN2 = 32;
  15. static const int B_PWM = 6; //B wheel pwm pin
  16. static const int C_IN1 = 24;
  17. static const int C_IN2 = 22;
  18. static const int C_PWM = 5; //C wheel pwm pin
  19. static boolean direcA = FORWARDS;
  20. static boolean direcB = FORWARDS;
  21. static boolean direcC = FORWARDS;
  22. /* Wrap the motor driver initialization,
  23. set all the motor control pins to outputs **/
  24. void initMotorsPinMode(void)
  25. {
  26. pinMode(A_IN1, OUTPUT);
  27. pinMode(A_IN2, OUTPUT);
  28. pinMode(A_PWM, OUTPUT);
  29. pinMode(B_IN1, OUTPUT);
  30. pinMode(B_IN2, OUTPUT);
  31. pinMode(B_PWM, OUTPUT);
  32. pinMode(C_IN1, OUTPUT);
  33. pinMode(C_IN2, OUTPUT);
  34. pinMode(C_PWM, OUTPUT);
  35. }
  36. /*
  37. get wheel run direction
  38. */
  39. boolean directionWheel(int wheel)
  40. {
  41. if (wheel == A_WHEEL)
  42. {
  43. return direcA;
  44. }
  45. else if (wheel == B_WHEEL)
  46. {
  47. return direcB;
  48. }
  49. else
  50. {
  51. return direcC;
  52. }
  53. }
  54. // A convenience function for setting both motor speeds
  55. void setMotorSpeeds(int ASpeed, int BSpeed, int CSpeed)
  56. {
  57. if (ASpeed > MAX_PWM)
  58. {
  59. ASpeed = MAX_PWM;
  60. }
  61. else if (ASpeed < -MAX_PWM)
  62. {
  63. ASpeed = -1 * MAX_PWM;
  64. }
  65. if (BSpeed > MAX_PWM)
  66. {
  67. BSpeed = MAX_PWM;
  68. }
  69. else if (BSpeed < -MAX_PWM)
  70. {
  71. BSpeed = -1 * MAX_PWM;
  72. }
  73. if (CSpeed > MAX_PWM)
  74. {
  75. CSpeed = MAX_PWM;
  76. }
  77. else if (CSpeed < -MAX_PWM)
  78. {
  79. CSpeed = -1 * MAX_PWM;
  80. }
  81. if (ASpeed >= 0) //drive motor A
  82. {
  83. direcA = FORWARDS;
  84. digitalWrite(A_IN1, LOW);
  85. digitalWrite(A_IN2, HIGH);
  86. analogWrite(A_PWM, ASpeed);
  87. }
  88. else if (ASpeed < 0)
  89. {
  90. direcA = BACKWARDS;
  91. digitalWrite(A_IN1, HIGH);
  92. digitalWrite(A_IN2, LOW);
  93. analogWrite(A_PWM, -ASpeed);
  94. }
  95. if (BSpeed >= 0) //drive motor B
  96. {
  97. direcB = FORWARDS;
  98. digitalWrite(B_IN1, LOW);
  99. digitalWrite(B_IN2, HIGH);
  100. analogWrite(B_PWM, BSpeed);
  101. }
  102. else if (BSpeed < 0)
  103. {
  104. direcB = BACKWARDS;
  105. digitalWrite(B_IN1, HIGH);
  106. digitalWrite(B_IN2, LOW);
  107. analogWrite(B_PWM, -BSpeed);
  108. }
  109. if (CSpeed >= 0) //drive motor C
  110. {
  111. direcC = FORWARDS;
  112. digitalWrite(C_IN1, LOW);
  113. digitalWrite(C_IN2, HIGH);
  114. analogWrite(C_PWM, CSpeed);
  115. }
  116. else if (CSpeed < 0)
  117. {
  118. direcC = BACKWARDS;
  119. digitalWrite(C_IN1, HIGH);
  120. digitalWrite(C_IN2, LOW);
  121. analogWrite(C_PWM, -CSpeed);
  122. }
  123. }