Library to drive the Zumo shield from pololu.

Dependents:   Nucleo_Zumo_BLE_IDB04A1

https://www.pololu.com/category/169/zumo-robot-for-arduino

Files at this revision

API Documentation at this revision

Comitter:
bcostm
Date:
Mon Oct 12 11:32:33 2015 +0000
Commit message:
Initial version.

Changed in this revision

ZumoShield.cpp Show annotated file Show diff for this revision Revisions of this file
ZumoShield.h Show annotated file Show diff for this revision Revisions of this file
diff -r 000000000000 -r c69b20870374 ZumoShield.cpp
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/ZumoShield.cpp	Mon Oct 12 11:32:33 2015 +0000
@@ -0,0 +1,122 @@
+#include "ZumoShield.h"
+#include "mbed.h"
+
+ZumoShield::ZumoShield(PinName m1_pwm_pin, PinName m1_dir_pin,
+                       PinName m2_pwm_pin, PinName m2_dir_pin) :
+//                     PinName a0_pin, PinName a1_pin, PinName a2_pin, PinName a3_pin, PinName a4_pin, PinName a5_pin) :
+    m1pwm(m1_pwm_pin),
+    m1dir(m1_dir_pin),
+    m2pwm(m2_pwm_pin),
+    m2dir(m2_dir_pin)
+    /*
+    a0sens(a0_pin),
+    a1sens(a1_pin),
+    a2sens(a2_pin),
+    a3sens(a3_pin),
+    a4sens(a4_pin),
+    a5sens(a5_pin)
+    */
+{
+}
+
+void ZumoShield::left_motor(float speed)
+{
+    if (speed >= 0) {
+        m2pwm = speed;
+        m2dir = 0;
+    } else {
+        m2pwm = -speed;
+        m2dir = 1;
+    }
+}
+
+void ZumoShield::right_motor(float speed)
+{
+    if (speed >= 0) {
+        m1pwm = speed;
+        m1dir = 1;
+    } else {
+        m1pwm = -speed;
+        m1dir = 0;
+    }
+}
+
+void ZumoShield::turn_left(float speed)
+{
+    left_motor(0);
+    right_motor(speed);
+}
+
+void ZumoShield::turn_right(float speed)
+{
+    left_motor(speed);
+    right_motor(0);
+}
+
+void ZumoShield::left(float speed)
+{
+    left_motor(-speed);
+    right_motor(speed);
+}
+
+void ZumoShield::right(float speed)
+{
+    left_motor(speed);
+    right_motor(-speed);
+}
+
+void ZumoShield::forward(float speed)
+{
+    if (speed == 0) {
+        left_motor(0);
+        right_motor(0);
+    } else {
+        left_motor(speed);
+        right_motor(speed);
+    }
+}
+
+void ZumoShield::backward(float speed)
+{
+    if (speed == 0) {
+        left_motor(0);
+        right_motor(0);
+    } else {
+        left_motor(-speed);
+        right_motor(-speed);
+    }
+}
+
+void ZumoShield::stop(int motor)
+{
+    if (motor == 1) {
+        stopLeft();
+    } else if (motor == 2) {
+        stopRight();
+    }
+}
+
+void ZumoShield::stopLeft()
+{
+    m2pwm = 0;
+    m2dir = 0;
+}
+
+void ZumoShield::stopRight()
+{
+    m1pwm = 0;
+    m1dir = 0;
+}
+
+void ZumoShield::stopAll()
+{
+    stopLeft();
+    stopRight();
+}
+
+/* TODO
+float ZumoShield::position()
+{
+    return output;
+}
+*/
diff -r 000000000000 -r c69b20870374 ZumoShield.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/ZumoShield.h	Mon Oct 12 11:32:33 2015 +0000
@@ -0,0 +1,93 @@
+#include "mbed.h"
+
+/** Zumo Shield Control Class
+*/
+class ZumoShield {
+    public:
+    
+        /** Create a Zumo shield object
+         *
+         * @param m1pwm Motor1 pwm pin
+         * @param m1dir Motor1 direction pin
+         * @param m2pwm Motor2 pwm pin
+         * @param m2dir Motor2 direction pin
+         */
+        ZumoShield(PinName m1_pwm_pin, PinName m1_dir_pin,
+                   PinName m2_pwm_pin, PinName m2_dir_pin);
+                   //PinName a0_pin, PinName a1_pin, PinName a2_pin, PinName a3_pin, PinName a4_pin, PinName a5_pin);
+
+        /** Switch on the left motor at the given speed.
+         *  @param speed The speed, from 0.0 to 1.0 at which to spin the motor.
+         */
+        void left_motor(float speed);
+        
+        /** Switch on the right motor at the given speed.
+         *  @param speed The speed, from 0.0 to 1.0 at which to spin the motor.
+         */
+        void right_motor(float speed);
+        
+        /** Switch on both motors, forwards at the given speed.
+         *  @param speed The speed, from 0.0 to 1.0 at which to spin the motor.
+         */
+        void forward(float speed);
+        
+        /** Switch on both motors, backwards at the given speed.
+         *  @param speed The speed, from 0.0 to 1.0 at which to spin the motor.
+         */
+        void backward(float speed);
+        
+        /** Switch on both motors at the given speed, in opposite directions so as to turn left.
+         *  @param speed The speed, from 0.0 to 1.0 at which to spin the motors.
+        */
+        void left(float speed);
+        
+        /** Switch on both motors at the given speed, in opposite directions so as to turn right.
+         *  @param speed The speed, from 0.0 to 1.0 at which to spin the motors.
+         */
+        void right(float speed);
+        
+        /** Turns left.
+         *  @param speed The speed, from 0.0 to 1.0 at which to spin the motor.
+         */
+        void turn_left(float speed);
+        
+        /** Turns right.
+         *  @param speed The speed, from 0.0 to 1.0 at which to spin the motor.
+         */
+        void turn_right(float speed);
+                
+        /** Stop a chosen motor.
+         *  @param motor Number, either 1 or 2 choosing the motor.
+         */
+        void stop(int motor);
+        
+        /** Stop left motor.
+         */
+        void stopLeft();
+        
+        /** Stop right motor.
+         */
+        void stopRight();
+        
+        /** Stop both motors at the same time. Different to disable.
+         */
+        void stopAll();
+                        
+        /** Gives an indication of the data given by the reflectivity sensors.
+         */
+        //float position();
+        
+    private:
+        PwmOut m1pwm;
+        PwmOut m2pwm;
+        DigitalOut m1dir;        
+        DigitalOut m2dir;
+        /*
+        AnalogIn a0sens;
+        AnalogIn a1sens;
+        AnalogIn a2sens;
+        AnalogIn a3sens;
+        AnalogIn a4sens;
+        AnalogIn a5sens;
+        */
+};