├── DRV8835DualDriver ├── keywords.txt ├── DRV8835DualDriver.h ├── examples │ └── DRV8835DualDriverDemo │ │ └── DRV8835DualDriverDemo.ino └── DRV8835DualDriver.cpp ├── LICENSE.txt └── README.textile /DRV8835DualDriver/keywords.txt: -------------------------------------------------------------------------------- 1 | DRV8835DualDriver KEYWORD1 2 | 3 | flipM1 KEYWORD2 4 | flipM2 KEYWORD2 5 | setM1Speed KEYWORD2 6 | setM2Speed KEYWORD2 7 | setSpeeds KEYWORD2 -------------------------------------------------------------------------------- /LICENSE.txt: -------------------------------------------------------------------------------- 1 | 2 | Permission is hereby granted, free of charge, to any person 3 | obtaining a copy of this software and associated documentation 4 | files (the "Software"), to deal in the Software without 5 | restriction, including without limitation the rights to use, 6 | copy, modify, merge, publish, distribute, sublicense, and/or sell 7 | copies of the Software, and to permit persons to whom the 8 | Software is furnished to do so, subject to the following 9 | conditions: 10 | 11 | The above copyright notice and this permission notice shall be 12 | included in all copies or substantial portions of the Software. 13 | 14 | THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, 15 | EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES 16 | OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND 17 | NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT 18 | HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, 19 | WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING 20 | FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR 21 | OTHER DEALINGS IN THE SOFTWARE. 22 | -------------------------------------------------------------------------------- /DRV8835DualDriver/DRV8835DualDriver.h: -------------------------------------------------------------------------------- 1 | #ifndef DRV8835DualDriver_h 2 | #define DRV8835DualDriver_h 3 | 4 | #if defined(__AVR_ATmega168__) || defined(__AVR_ATmega328P__) || defined (__AVR_ATmega32U4__) 5 | #define DRV8835DUALDRIVER_USE_20KHZ_PWM 6 | #endif 7 | 8 | #include 9 | 10 | class DRV8835DualDriver 11 | { 12 | public: 13 | static void setM1Speed(int speed); 14 | static void setM2Speed(int speed); 15 | static void setSpeeds(int m1Speed, int m2Speed); 16 | static void flipM1(boolean flip); 17 | static void flipM2(boolean flip); 18 | 19 | private: 20 | static void initPinsAndMaybeTimer(); 21 | static const unsigned char _M1DIR; 22 | static const unsigned char _M2DIR; 23 | static const unsigned char _M1PWM; 24 | static const unsigned char _M2PWM; 25 | static boolean _flipM1; 26 | static boolean _flipM2; 27 | 28 | static inline void init() 29 | { 30 | static boolean initialized = false; 31 | 32 | if (!initialized) 33 | { 34 | initialized = true; 35 | initPinsAndMaybeTimer(); 36 | } 37 | } 38 | }; 39 | #endif -------------------------------------------------------------------------------- /README.textile: -------------------------------------------------------------------------------- 1 | h1. Arduino library for the Pololu DRV8835 Dual Motor Driver Carrier 2 | 3 | Version: 1.0.0 4 | Release Date: 2015-05-16 5 | 6 | h2. Summary 7 | 8 | This is a library for the Arduino that interfaces with the "Pololu DRV8835 Dual Motor Driver Carrier":https://www.pololu.com/product/2135. It makes it simple to drive two brushed, DC motors. 9 | 10 | 11 | h3. Hardware 12 | 13 | The Pololu DRV8835 Dual Motor Driver Carrier can be purchased on "Pololu's website":http://www.pololu.com/catalog/product/2135. 14 | 15 | h3. Compatible Arduino boards 16 | 17 | This shield should work with all Arduino boards and clones that behave like a standard Arduino board. 18 | 19 | h2. Example program 20 | 21 | h3. Demo 22 | 23 | Open this example code sketch by selecting File->Examples->DRV8835DualDriverDemo->DRV8835DualDriverDemo.ino 24 | 25 | 26 | h2. Library reference 27 | 28 | - @void setM1Speed(int speed)@ := Set speed and direction for motor 1. Speed should be between -400 and 400. The motors brake at 0 speed. Positive speeds correspond to motor current flowing from M1A to M1B. Negative speeds correspond to motor current flowing from M1B to M1A. 29 | - @void setM2Speed(int speed)@ := Set speed and direction for motor 2. Speed should be between -400 and 400. The motors brake at 0 speed. Positive speeds correspond to motor current flowing from M2A to M2B. Negative speeds correspond to motor current flowing from M2B to M2A. 30 | - @void setSpeeds(int m1Speed, int m2Speed)@ := Set speed and direction for motor 1 and 2. 31 | - @void flipM1(bool flip)@ := Flip the direction meaning of the speed passed to the setSpeeds function for motor 1. The default direction corresponds to flipM1(false) having been called. 32 | - @void flipM2(bool flip)@ := Flip the direction meaning of the speed passed to the setSpeeds function for motor 2. The default direction corresponds to flipM2(false) having been called. 33 | 34 | h2. Version history 35 | 36 | * 1.0.0 (2015-05-15): Original release. -------------------------------------------------------------------------------- /DRV8835DualDriver/examples/DRV8835DualDriverDemo/DRV8835DualDriverDemo.ino: -------------------------------------------------------------------------------- 1 | #include 2 | 3 | /* 4 | * This example uses the DRV8835DualDriver library to drive each motor with the 5 | * Pololu DRV8835 Dual Motor Driver Shield for Arduino forward, then backward. 6 | * The yellow user LED is on when a motor is set to a positive speed and off when 7 | * a motor is set to a negative speed. 8 | */ 9 | 10 | /* 11 | * const unsigned char DRV8835DualDriver::_M1DIR = 7; DIR / PHASE 12 | * const unsigned char DRV8835DualDriver::_M2DIR = 8; 13 | * const unsigned char DRV8835DualDriver::_M1PWM = 9; PWM / PWM 14 | * const unsigned char DRV8835DualDriver::_M2PWM = 10; 15 | */ 16 | 17 | #define LED_PIN 13 18 | 19 | DRV8835DualDriver motors; 20 | 21 | void setup() 22 | { 23 | pinMode(LED_PIN, OUTPUT); 24 | 25 | // uncomment one or both of the following lines if your motors' directions need to be flipped 26 | //motors.flipM1(true); 27 | //motors.flipM2(true); 28 | } 29 | 30 | void loop() 31 | { 32 | // run M1 motor with positive speed 33 | 34 | digitalWrite(LED_PIN, HIGH); 35 | 36 | for (int speed = 0; speed <= 400; speed++) 37 | { 38 | motors.setM1Speed(speed); 39 | delay(2); 40 | } 41 | 42 | for (int speed = 400; speed >= 0; speed--) 43 | { 44 | motors.setM1Speed(speed); 45 | delay(2); 46 | } 47 | 48 | // run M1 motor with negative speed 49 | 50 | digitalWrite(LED_PIN, LOW); 51 | 52 | for (int speed = 0; speed >= -400; speed--) 53 | { 54 | motors.setM1Speed(speed); 55 | delay(2); 56 | } 57 | 58 | for (int speed = -400; speed <= 0; speed++) 59 | { 60 | motors.setM1Speed(speed); 61 | delay(2); 62 | } 63 | 64 | // run M2 motor with positive speed 65 | 66 | digitalWrite(LED_PIN, HIGH); 67 | 68 | for (int speed = 0; speed <= 400; speed++) 69 | { 70 | motors.setM2Speed(speed); 71 | delay(2); 72 | } 73 | 74 | for (int speed = 400; speed >= 0; speed--) 75 | { 76 | motors.setM2Speed(speed); 77 | delay(2); 78 | } 79 | 80 | // run M2 motor with negative speed 81 | 82 | digitalWrite(LED_PIN, LOW); 83 | 84 | for (int speed = 0; speed >= -400; speed--) 85 | { 86 | motors.setM2Speed(speed); 87 | delay(2); 88 | } 89 | 90 | for (int speed = -400; speed <= 0; speed++) 91 | { 92 | motors.setM2Speed(speed); 93 | delay(2); 94 | } 95 | 96 | delay(500); 97 | } -------------------------------------------------------------------------------- /DRV8835DualDriver/DRV8835DualDriver.cpp: -------------------------------------------------------------------------------- 1 | #include "DRV8835DualDriver.h" 2 | const unsigned char DRV8835DualDriver::_M1DIR = 7; //not used 3 | const unsigned char DRV8835DualDriver::_M2DIR = 8; 4 | const unsigned char DRV8835DualDriver::_M1PWM = 6; // not used 5 | const unsigned char DRV8835DualDriver::_M2PWM = 10; 6 | boolean DRV8835DualDriver::_flipM1 = false; 7 | boolean DRV8835DualDriver::_flipM2 = false; 8 | 9 | void DRV8835DualDriver::initPinsAndMaybeTimer() 10 | { 11 | // Initialize the pin states used by the motor driver 12 | // digitalWrite is called before and after setting pinMode. 13 | // It called before pinMode to handle the case where the board 14 | // is using an ATmega AVR to avoid ever driving the pin high, 15 | // even for a short time. 16 | // It is called after pinMode to handle the case where the board 17 | // is based on the Atmel SAM3X8E ARM Cortex-M3 CPU, like the Arduino 18 | // Due. This is necessary because when pinMode is called for the Due 19 | // it sets the output to high (or 3.3V) regardless of previous 20 | // digitalWrite calls. 21 | digitalWrite(_M1PWM, LOW); 22 | pinMode(_M1PWM, OUTPUT); 23 | digitalWrite(_M1PWM, LOW); 24 | digitalWrite(_M2PWM, LOW); 25 | pinMode(_M2PWM, OUTPUT); 26 | digitalWrite(_M2PWM, LOW); 27 | digitalWrite(_M1DIR, LOW); 28 | pinMode(_M1DIR, OUTPUT); 29 | digitalWrite(_M1DIR, LOW); 30 | digitalWrite(_M2DIR, LOW); 31 | pinMode(_M2DIR, OUTPUT); 32 | digitalWrite(_M2DIR, LOW); 33 | #ifdef DRV8835DUALDRIVER_USE_20KHZ_PWM 34 | // timer 1 configuration 35 | // prescaler: clockI/O / 1 36 | // outputs enabled 37 | // phase-correct PWM 38 | // top of 400 39 | // 40 | // PWM frequency calculation 41 | // 16MHz / 1 (prescaler) / 2 (phase-correct) / 400 (top) = 20kHz 42 | TCCR1A = 0b10100000; 43 | TCCR1B = 0b00010001; 44 | ICR1 = 400; 45 | #endif 46 | } 47 | 48 | // speed should be a number between -400 and 400 49 | void DRV8835DualDriver::setM1Speed(int speed) 50 | { 51 | init(); // initialize if necessary 52 | 53 | boolean reverse = 0; 54 | 55 | if (speed < 0) 56 | { 57 | speed = -speed; // make speed a positive quantity 58 | reverse = 1; // preserve the direction 59 | } 60 | if (speed > 400) // max 61 | speed = 400; 62 | 63 | #ifdef DRV8835DUALDRIVER_USE_20KHZ_PWM 64 | OCR1A = speed; 65 | #else 66 | analogWrite(_M1PWM, speed * 51 / 80); // default to using analogWrite, mapping 400 to 255 67 | #endif 68 | 69 | if (reverse ^ _flipM1) // flip if speed was negative or _flipM1 setting is active, but not both 70 | digitalWrite(_M1DIR, HIGH); 71 | else 72 | digitalWrite(_M1DIR, LOW); 73 | } 74 | 75 | // speed should be a number between -400 and 400 76 | void DRV8835DualDriver::setM2Speed(int speed) 77 | { 78 | init(); // initialize if necessary 79 | 80 | boolean reverse = 0; 81 | 82 | if (speed < 0) 83 | { 84 | speed = -speed; // make speed a positive quantity 85 | reverse = 1; // preserve the direction 86 | } 87 | if (speed > 400) // max PWM duty cycle 88 | speed = 400; 89 | 90 | #ifdef DRV8835DUALDRIVER_USE_20KHZ_PWM 91 | OCR1B = speed; 92 | #else 93 | analogWrite(_M2PWM, speed * 51 / 80); // default to using analogWrite, mapping 400 to 255 94 | #endif 95 | 96 | if (reverse ^ _flipM2) // flip if speed was negative or _flipM2 setting is active, but not both 97 | digitalWrite(_M2DIR, HIGH); 98 | else 99 | digitalWrite(_M2DIR, LOW); 100 | } 101 | 102 | // set speed for both motors 103 | // speed should be a number between -400 and 400 104 | void DRV8835DualDriver::setSpeeds(int m1Speed, int m2Speed){ 105 | setM1Speed(m1Speed); 106 | setM2Speed(m2Speed); 107 | } 108 | 109 | void DRV8835DualDriver::flipM1(boolean flip) 110 | { 111 | _flipM1 = flip; 112 | } 113 | 114 | void DRV8835DualDriver::flipM2(boolean flip) 115 | { 116 | _flipM2 = flip; 117 | } --------------------------------------------------------------------------------