offer some APIs to control the movement of motor. Suitable with Seeed motor shield
Fork of MotorDriver by
Revision 0:6bd25809e2e0, committed 2014-02-12
- Comitter:
- lawliet
- Date:
- Wed Feb 12 02:54:52 2014 +0000
- Child:
- 1:9c93f514f369
- Commit message:
- motor driver library, suitable with Seeed motor shield
Changed in this revision
MotorDriver.cpp | Show annotated file Show diff for this revision Revisions of this file |
MotorDriver.h | Show annotated file Show diff for this revision Revisions of this file |
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/MotorDriver.cpp Wed Feb 12 02:54:52 2014 +0000 @@ -0,0 +1,118 @@ +/* + MotorDriver.cpp + 2014 Copyright (c) Seeed Technology Inc. All right reserved. + + Author:lawliet.zou@gmail.com + 2014-02-11 + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#include "MotorDriver.h" + +void MotorDriver::init() +{ + stop(); + /*Configure the motor A to control the wheel at the left side.*/ + configure(MOTOR_POSITION_LEFT,MOTORA); + /*Configure the motor B to control the wheel at the right side.*/ + configure(MOTOR_POSITION_RIGHT,MOTORB); + setSpeed(0,MOTORA); + setSpeed(0,MOTORB); + setDirection(MOTOR_ANTICLOCKWISE,MOTORA); + setDirection(MOTOR_CLOCKWISE,MOTORB); +} +void MotorDriver::configure(uint8_t position, uint8_t motorID) +{ + if(motorID == MOTORA)motorA.position = position; + else motorB.position = position; +} + +void MotorDriver::setSpeed(uint8_t speed, uint8_t motorID) +{ + if(motorID == MOTORA) motorA.speed = speed; + else if(motorID == MOTORB) motorB.speed = speed; +} +void MotorDriver::setDirection(uint8_t direction, uint8_t motorID) +{ + if(motorID == MOTORA)motorA.direction= direction; + else if(motorID == MOTORB)motorB.direction = direction; +} +/**********************************************************************/ +/*Function: Get the motor rotate */ +/*Parameter:-uint8_t direction,Clockwise or anticlockwise; */ +/* -uint8_t motor_position,MOTOR_POSITION_LEFT or */ +/* MOTOR_POSITION_RIGHT; */ +/*Return: void */ +void MotorDriver::rotate(uint8_t direction, uint8_t motor_position) +{ + if(motor_position == motorA.position) { + rotateWithID(direction,MOTORA); + } + if(motor_position == motorB.position) { + rotateWithID(direction,MOTORB); + } +} +/**********************************************************************/ +/*Function: Get the motor rotate */ +/*Parameter:-uint8_t direction,Clockwise or anticlockwise; */ +/* -uint8_t motor_position,MOTORA or MOTORB */ +/*Return: void */ +void MotorDriver::rotateWithID(uint8_t direction, uint8_t motorID) +{ + if(motorID == MOTORA) { + _speedA.Enable(motorA.speed*100,MOTOR_PERIOD); + _int1 = (MOTOR_CLOCKWISE == direction)?LOW:HIGH; + _int2 = !_int1; + } else if(motorID == MOTORB) { + _speedB.Enable(motorB.speed*100,MOTOR_PERIOD); + _int3 = (MOTOR_CLOCKWISE == direction)?LOW:HIGH; + _int4 = !_int3; + } +} + +void MotorDriver::goForward() +{ + rotate(MOTOR_ANTICLOCKWISE,MOTOR_POSITION_LEFT); + rotate(MOTOR_CLOCKWISE,MOTOR_POSITION_RIGHT); +} +void MotorDriver::goBackward() +{ + rotate(MOTOR_ANTICLOCKWISE,MOTOR_POSITION_RIGHT); + rotate(MOTOR_CLOCKWISE,MOTOR_POSITION_LEFT); +} +void MotorDriver::goLeft() +{ + rotate(MOTOR_CLOCKWISE,MOTOR_POSITION_RIGHT); + rotate(MOTOR_CLOCKWISE,MOTOR_POSITION_LEFT); +} +void MotorDriver::goRight() +{ + rotate(MOTOR_ANTICLOCKWISE,MOTOR_POSITION_RIGHT); + rotate(MOTOR_ANTICLOCKWISE,MOTOR_POSITION_LEFT); +} + +void MotorDriver::stop() +{ + _speedA.Disable(); + _speedB.Disable(); +} + +void MotorDriver::stop(uint8_t motorID) +{ + if(motorID == MOTORA)_speedA.Disable(); + else if(motorID == MOTORB)_speedB.Disable(); +} +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/MotorDriver.h Wed Feb 12 02:54:52 2014 +0000 @@ -0,0 +1,166 @@ +/* + MotorDriver.h + 2014 Copyright (c) Seeed Technology Inc. All right reserved. + + Author:lawliet.zou@gmail.com + 2014-02-11 + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA +*/ +#ifndef __MOTORDRIVER_H__ +#define __MOTORDRIVER_H__ + +#include "mbed.h" +#include "SoftwarePWM.h" + +/**************Motor ID**********************/ +#define MOTORA 0 +#define MOTORB 1 + +#define LOW 0 +#define HIGH 1 + +#define MOTOR_POSITION_LEFT 0 +#define MOTOR_POSITION_RIGHT 1 +#define MOTOR_CLOCKWISE 0 +#define MOTOR_ANTICLOCKWISE 1 + +#define USE_DC_MOTOR 0 + +#define MOTOR_PERIOD 10000 //10ms + +struct MotorStruct { + uint8_t speed; + uint8_t direction; + uint8_t position; +}; + +/** Motor Driver class. + * offer API to control the movement of motor + */ +class MotorDriver +{ + +public: + + /** Create Motor Driver instance + * @param int1 pin 1 of motor movement control + * @param int2 pin 2 of motor movement control + * @param int3 pin 3 of motor movement control + * @param int4 pin 4 of motor movement control + @param speedA speed control of motorA + @param speedB speed control of motorB + */ + MotorDriver(PinName int1, PinName int2, PinName int3, PinName int4, PinName speedA, PinName speedB):_int1(int1),_int2(int2),_int3(int3),_int4(int4),_speedA(speedA),_speedB(speedB) { + _int1 = 0; + _int2 = 0; + _int3 = 0; + _int4 = 0; + }; + + /** set motor to initialized state + */ + void init(); + + /** config position of motor + * @param position the position set to motor,MOTOR_POSITION_LEFT or MOTOR_POSITION_RIGHT will be allowed + * @param motorID the ID define which motor will be set, you can choose MOTORA or MOTORB + */ + void configure(uint8_t position, uint8_t motorID); + + /** set speed of motor + * @param speed speed value set to motor, [0,100] will be allowed + * @param motorID the ID define which motor will be set, you can choose MOTORA or MOTORB + */ + void setSpeed(uint8_t speed, uint8_t motorID); + + /** set direction of motor, + * @param direction the direction of motor, MOTOR_CLOCKWISE or MOTOR_ANTICLOCKWISE will be allowed + * @param motorID the ID define which motor will be set, you can choose MOTORA or MOTORB + */ + void setDirection(uint8_t direction, uint8_t motorID); + + /** rotate motor + * @param direction the direction set to motor, MOTOR_CLOCKWISE or MOTOR_ANTICLOCKWISE will be allowed + * @param motor_position the position set to motor,MOTOR_POSITION_LEFT or MOTOR_POSITION_RIGHT will be allowed + */ + void rotate(uint8_t direction, uint8_t motor_position); + + /** rotate motorA or motorB + * @param direction the direction set to motor, MOTOR_CLOCKWISE or MOTOR_ANTICLOCKWISE will be allowed + * @param motorID the ID define which motor will be set, you can choose MOTORA or MOTORB + */ + void rotateWithID(uint8_t direction, uint8_t motorID); + + /** make motor go forward + */ + void goForward(); + + /** make motor go backward + */ + void goBackward(); + + /** make motor go left + */ + void goLeft(); + + /** make motor go right + */ + void goRight(); + + /** make motor stop + */ + void stop(); + + /** make motorA or motorB stop + * @param motorID the ID define which motor will be set, you can choose MOTORA or MOTORB + */ + void stop(uint8_t motorID); + + /** motor A + */ + MotorStruct motorA; + + /** motor B + */ + MotorStruct motorB; + +private: + + /** pin 1 of motor movement control + */ + DigitalOut _int1; + + /** pin 2 of motor movement control + */ + DigitalOut _int2; + + /** pin 3 of motor movement control + */ + DigitalOut _int3; + + /** pin 4 of motor movement control + */ + DigitalOut _int4; + + /** pin to control the speed of motorA + */ + SoftwarePWM _speedA; + + /** pin to control the speed of motorB + */ + SoftwarePWM _speedB; +}; +#endif