Initial draft of Arduino Sparkfun port for TB6612 Motor driver
Sparkfun_TB6612.h
- Committer:
- ateyercheese
- Date:
- 2018-10-02
- Revision:
- 0:2d64a320d78f
File content as of revision 0:2d64a320d78f:
/****************************************************************************** SparkFun_TB6612.h TB6612FNG H-Bridge Motor Driver Example code Michelle @ SparkFun Electronics 8/20/16 https://github.com/sparkfun/SparkFun_TB6612FNG_Arduino_Library Uses 2 motors to show examples of the functions in the library. This causes a robot to do a little 'jig'. Each movement has an equal and opposite movement so assuming your motors are balanced the bot should end up at the same place it started. Resources: TB6612 SparkFun Library Development environment specifics: Developed on Arduino 1.6.4 Developed with ROB-9457 ******************************************************************************/ #ifndef SPARKFUN_TB6612_h #define SPARKFUN_TB6612_h #include "mbed.h" //used in some functions so you don't have to send a speed #define DEFAULTSPEED 255 class Motor { public: // Constructor. Mainly sets up pins. Motor(PinName pwm, PinName dir1, PinName dir2, PinName standby, int offset = 1); // Drive in direction given by sign, at speed given by magnitude of the //parameter. void drive(int speed); // drive(), but with a delay(duration) void drive(int speed, int duration); //currently not implemented //void stop(); // Stop motors, but allow them to coast to a halt. //void coast(); // Stop motors, but allow them to coast to a halt. //Stops motor by setting both input pins high void brake(); //set the chip to standby mode. The drive function takes it out of standby //(forward, back, left, and right all call drive) void standby(); // Turn off Standby void enable_motor(); private: //variables for the 2 inputs, PWM input, Offset value, and the Standby pin PwmOut _pwm; DigitalOut _dir1, _dir2, _standby; int _offset; //private functions that spin the motor CC and CCW void fwd(int speed); void rev(int speed); }; //Takes 2 motors and goes forward, if it does not go forward adjust offset //values until it does. These will also take a negative number and go backwards //There is also an optional speed input, if speed is not used, the function will //use the DEFAULTSPEED constant. void forward(Motor motor1, Motor motor2, int speed); void forward(Motor motor1, Motor motor2); //Similar to forward, will take 2 motors and go backwards. This will take either //a positive or negative number and will go backwards either way. Once again the //speed input is optional and will use DEFAULTSPEED if it is not defined. void back(Motor motor1, Motor motor2, int speed); void back(Motor motor1, Motor motor2); //Left and right take 2 motors, and it is important the order they are sent. //The left motor should be on the left side of the bot. These functions //also take a speed value void left(Motor left, Motor right, int speed); void right(Motor left, Motor right, int speed); //This function takes 2 motors and and brakes them void brake(Motor motor1, Motor motor2); #endif