motor_driver.ino 2.6 KB

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