Library for the VNH5019 Motor Driver, with a helper class for the Pololu Dual VNH5019 Dual Motor Driver Shield http://www.pololu.com/product/2502

Dependents:   VNH5019_second VNH5019_second1

Embed: (wiki syntax)

« Back to documentation index

Show/hide line numbers VNH5019Accel.h Source File

VNH5019Accel.h

00001 // VNH5015 driver with acceleration control
00002 // A drop-in replacement for the basic VNH5019
00003 
00004 #if !defined(VNH5019ACCEL_H)
00005 #define VNH5019ACCEL_H
00006 
00007 #include "VNH5019.h"
00008 #include <Ticker.h>
00009 
00010 // The maximum acceleration, in fractions of full speed per second
00011 float const VNH5019MaxAccel = 4;
00012 
00013 // Tick period in microseconds for updating the speed
00014 int const VNH5019Tick_us = 20000;
00015 
00016 float const VNH5019ChangePerTick = VNH5019MaxAccel * VNH5019Tick_us / 1000000;
00017 
00018 // allow braking to come on faster
00019 float const VNH5019BrakeChangePerTick = VNH5019ChangePerTick*10;
00020 
00021 class VNH5019Accel
00022 {
00023     public:
00024         VNH5019Accel(PinName INA_, PinName INB_, PinName ENDIAG_, PinName CS_, PinName PWM_)
00025             : Driver(INA_, INB_, ENDIAG_, CS_, PWM_),
00026               CurrentSpeed(0.0),
00027               CurrentBrake(0.0),
00028               RequestedSpeed(0.0),
00029               RequestedBrake(0.0)
00030         {
00031             timer.attach_us(this, &VNH5019Accel::Interrupt, VNH5019Tick_us);
00032         }
00033         
00034         // set motor speed from -1.0 to +1.0
00035         void speed(float Speed)
00036         {
00037             if (Speed < -1.0)
00038                 Speed = 1.0;
00039             else if (Speed > 1.0)
00040                 Speed = 1.0;
00041             RequestedSpeed = Speed;
00042         }
00043 
00044         // stop (no current to the motors)
00045         void stop()
00046         {
00047             RequestedSpeed = 0.0;
00048         }
00049     
00050         // Brake, with strength 0..1
00051         void brake(float Brake)
00052         {
00053             if (Brake < 0.0)
00054                 Brake = 0;
00055             else if (Brake > 1.0)
00056                 Brake = 1.0;
00057             RequestedBrake = Brake;
00058             RequestedSpeed = 0.0;
00059         }
00060 
00061         // returns the current through the motor, in mA
00062         float get_current_mA()
00063         {
00064             return Driver.get_current_mA();
00065         }
00066 
00067         // returns true if there has been a fault
00068         bool is_fault()
00069         {
00070             return Driver.is_fault();
00071         }
00072 
00073         // Clears the fault condition
00074         // PRECONDITION: is_fault()
00075         void clear_fault()
00076         {
00077             timer.detach();
00078             Driver.clear_fault();
00079             timer.attach_us(this, &VNH5019Accel::Interrupt, VNH5019Tick_us);
00080         }
00081 
00082         // disable the motor, and set outputs to zero.  This is a low power mode.
00083         void disable()
00084         {
00085             timer.detach();
00086             Driver.disable();
00087         }
00088 
00089         // enable the motor.        
00090         void enable()
00091         {
00092             timer.detach();
00093             Driver.enable();
00094             timer.attach_us(this, &VNH5019Accel::Interrupt, VNH5019Tick_us);
00095         }
00096         
00097         // set the PWM period of oscillation in seconds
00098         void set_pwm_period(float p)
00099         {
00100             Driver.set_pwm_period(p);
00101         }
00102 
00103     private:
00104         VNH5019 Driver;
00105         Ticker timer;
00106         float CurrentSpeed;  // this is only ever accessed from the ISR, so no need for volatile
00107         float CurrentBrake;
00108         volatile float RequestedSpeed;
00109         volatile float RequestedBrake;
00110         void Interrupt();
00111 };        
00112 
00113 // Helper class for the Pololu dual VNH5019 motor shield.
00114 // The default constructor uses the default arduino pins.
00115 // The motors can be accessed either by .m1 or .m2, or by operator()(i) where i is 1 or 2.
00116 class DualVNH5019AccelMotorShield
00117 {
00118     public:
00119         // default pin selection
00120         DualVNH5019AccelMotorShield(); // Default pin selection.
00121 
00122                               // User-defined pin selection. 
00123         DualVNH5019AccelMotorShield(PinName INA1_, PinName INB1_, PinName ENDIAG1_, PinName CS1_, PinName PWM1_,
00124                                     PinName INA2_, PinName INB2_, PinName ENDIAG2_, PinName CS2_, PinName PWM2_)
00125          : m1(INA1_, INB1_, ENDIAG1_, CS1_, PWM1_),
00126            m2(INA2_, INB2_, ENDIAG2_, CS2_, PWM2_)
00127         {
00128         }
00129         
00130         // returns the given motor object, 1 or 2.
00131         VNH5019Accel& operator()(int m)
00132         {
00133             return m == 1 ? m1 : m2;
00134         }
00135 
00136       VNH5019Accel m1;
00137       VNH5019Accel m2;
00138 };
00139 
00140 #endif