Class library for a L298 H-Bridge
Dependents: inverted_pendulum_system
Fork of L298HBridge by
L298HBridge.h
- Committer:
- dudu941014
- Date:
- 2017-08-25
- Revision:
- 3:dabd8b6b2bff
- Parent:
- 2:1c000b6cf863
File content as of revision 3:dabd8b6b2bff:
////////////////////////////////////////////////////////////////////////////////// // Company: edinburgh of university // Engineer: ZEjun DU // // Create Date: 2017/08/20 13:06:52 // Design Name: Inverted Pendulum Balancer // Module Name: motor driver // Tool Versions: “Keil 5” or “Mbed Complie Online” // Description: this part is to control the motor according to PWM // // ////////////////////////////////////////////////////////////////////////////////// #ifndef L298HBridge_H #define L298HBridge_H #include "mbed.h" /** Class library for a L298 H-Bridge. The class is written for one H-Bridge of * the L298. Constructing the class twice will enable you to use both H-bridges. * * Example: * @code * #include "mbed.h" * #include "L298HBridge.h" * L298HBridge Motor(PB_4, PC_4, PC_5); * int main() * { * float i; * while(1) * { * Motor.Fwd(); * * for(i=0;i<100;i++) * { * Motor.Speed(i); * wait(0.1); * } * * for(i=100;i>25;i--) * { * Motor.Speed(i); * wait(0.1); * } * * Motor.Rev(); * * for(i=0;i<100;i++) * { * Motor.Speed(i); * wait(0.1); * } * * for(i=100;i>25;i--) * { * Motor.Speed(i); * wait(0.1); * } * } * } * @endcode */ class L298HBridge { public: /** Create a L298HBridge object connected to the specified pins. * Once created, the motor speed will be set to 0 (PWM signal will be 0%) and * the motor will be in the stop mode (neither forward or reverse). * @param ENPin PwmOut compatible pin used to connect to L298's En(x) pin associated with enabling the H-Bridge. * @param FWDPin GPIO pin used to connect to L298's In(x) pin associated with forward direction. * @param REVPin GPIO pin used to connect to L298's In(x) pin associated with reverse direction. */ L298HBridge(PinName ENPin, PinName FWDPin, PinName REVPin); /** Configure the H-Bridge to run the motor in the forward direction. * @param None */ void Fwd(); /** Configure the H-Bridge to run the motor in the reverse direction. * @param None */ void Rev(); /** Switch the H-Bridge off. The H-Bridge is not set to forward or reverse. * @param None */ void Stop(); /** Change the motor's speed by adjusting the PWM signal. * The value passed to the function can be any value from 0 to 100. * Where 0 = 0% and 100 = 100%. * @param DutyPercent */ void Speed(float DutyPercent); private: PwmOut _ENPin; DigitalOut _FWDPin, _REVPin; }; #endif