Simple Interface for Toshiba's TB6612FNG H-Bridge Motor Driver

Revision:
1:3dd9137a5cec
Parent:
0:30d6828516f5
Child:
2:73d5d7514e4c
--- a/TB6612FNG.h	Mon Mar 04 21:58:45 2013 +0000
+++ b/TB6612FNG.h	Wed Mar 06 19:59:50 2013 +0000
@@ -12,28 +12,32 @@
     PwmOut m_pwm;
     DigitalOut m_ctrl1;
     DigitalOut m_ctrl2;
-    int m_dc;
+    int m_pw;
     bool m_on;
+    bool m_brakeOnZeroDC;
+    int m_period;
 
 public:
     /** Create TB6612FNG object connected to the specified mbed pins
     * @param pwm PwmOut pin
     * @param ctrl1/ctrl2 DigitalOut control pin
+    * @param pwmPeriod is the PWM period setting in µs
+    * @param brakeOnZeroDC if true the motor brakes on zero pulse width setting
     */
-    TB6612FNG(PinName pwm, PinName ctrl1, PinName ctrl2);
+    TB6612FNG(PinName pwm, PinName ctrl1, PinName ctrl2, int pwmPeriod=1000, bool brakeOnZeroDC=true);
     /// Set the duty cycle
-    /// @param dc in permille [-1000,1000]
-    void setDC(int dc);
-    /// activate the motor at given duty cycle
+    /// @param pw is the PWM pulse width setting in µs
+    void setPulseWidth(int pw);
+    /// activates the motor at duty cycle adjusted with setPulseWidth
     void on();
-    /// deactivate the motor
+    /// deactivates the motor (sets the motor output to high impedance, no short brake)
     void off();
-    /// break the motor by shorting it 
+    /// brakes the motor by shorting it 
     void brake();
-    /// duty cycle assignment
-    /// @param dc in permille [-1000,1000]
-    void operator=(int dc) {
-        setDC(dc);
+    /// pulse width assignment
+    /// @param pw is the PWM pulse width setting in µs
+    void operator=(int pw) {
+        setPulseWidth(pw);
     }
 };