Class library for a L298 H-Bridge to be used for motor control.
Diff: L298HBridge.h
- Revision:
- 2:1c000b6cf863
- Parent:
- 1:6d242bb216d6
--- a/L298HBridge.h Thu Jan 19 12:34:48 2017 +0000 +++ b/L298HBridge.h Fri Jan 20 09:10:05 2017 +0000 @@ -27,11 +27,50 @@ #include "mbed.h" -/** Class library for a L298 H-Bridge. +/** 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 */ @@ -39,19 +78,19 @@ 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" direction (neither forward or reverse). - * @param ENPin PwmOut compatible pin used to connect to L298's En pin associated with enabling the H-Bridge. - * @param FWDPin GPIO pin used to connect to L298's In pin associated with forward direction. - * @param REVPin GPIO pin used to connect to L298's In pin associated with reverse direction. + * 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); - /** Switch the H-Bridge to run the motor in the forward direction. + /** Configure the H-Bridge to run the motor in the forward direction. * @param None */ void Fwd(); - /** Switch the H-Bridge to run the motor in the reverse direction. + /** Configure the H-Bridge to run the motor in the reverse direction. * @param None */ void Rev(); @@ -61,10 +100,12 @@ */ void Stop(); - /** Change the motor's speed by adjusting the PWM signal. - * @param int DutyPercent + /** 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(int DutyPercent); + void Speed(float DutyPercent); private: PwmOut _ENPin;