Wednesday, December 9, 2015

Parallax HB-25 Motor Control Library for Arduino

Moving AVA


We are using the Arlo robotics platform from Parallax to build up AVA. As you can see in the schematic below, this incorporates two HB-25 motor controllers (Part Number: #29144) which look after the left and right wheels.


After an exhaustive search we were not able to find an existing Arduino library for the HB25, so we were forced to write our own. This involved delving into the incomplete version of C++ which Arduino uses. Before getting to this, let's look at how you can control the HB25 just treating it as a servo, which will be fine for most folks.

Wiring the HB-25




If you are using the Parallax Motor Mount and wheel kits (part numbers #28962 - aluminium or #28963 - plastic) then the red cable should be connected to M1 on the HB-25 and the blue cable should be connected to M2. If these are reversed then the FORWARD and REVERSE commands will be reversed.



Make sure that the jumper is in place for mode 1 operation. In this mode, you need a separate digital output on your Arduino for each HB-25 that you want to control.

Controlling the HB-25


From the HB-25 data sheet, we can establish the following:

  1. The HB-25 operates like a servo. You only need to send a single pulse (in mode 1) to change direction or speed. Pulse width determines the HB-25 output.
  2. Valid pulse widths are 0.8 ms to 2.2 ms. If the HB-25 receives a pulse width which is outside this range, the motor will be stopped until it receives a valid pulse.
  3. The minimum time between pulses (HOLD_OFF_TIME) is 5.25 ms + pulse time (max 2.2 ms). Thus the worst case hold off time needs to be 7.45 ms. We have used 8 ms.
  4. The maximum time between pulses is unlimited, since a single pulse will be latched by the HB-25. An exception to this would be if the Communication Timeout feature of the HB-25 has been enabled. You can read more about this on the HB-25 data sheet (https://www.parallax.com/downloads/hb-25-motor-controller-product-documentation).
  5. Regardless of the mode, the HB-25 signal pin should be brought low immediately upon power up. The Library does this when you instantiate a HB25MotorControl object.
  6. Pulse width (1 ms = 1000 microseconds) will control the HB-25 as follows:

                        - 1.0 ms Full Reverse
                        - 1.5 ms Neutral (STOP)
                        - 2.0 ms Full Forward

Arduino Code


So making use of the above, we can control a HB-25 using the following Arduino code. Note that you will need to set controlPin to whatever digital output pin is connected to your HB-25. After you have initialised your HB-25 you can control it by writing a value between 1000 and 2000 to it using the servo.writeMicroseconds() method. You need to ensure that two commands are not sent within the minimum hold off time. This is taken care of for you in the library below.

#include <Servo.h>

#define REVERSE       1000
#define STOP          1500
#define FORWARD       2000
#define HOLD_OFF_TIME 8

Servo servo;

// HB-25 initialisation time (5ms)
delay(5);                                           
pinMode(controlPin, OUTPUT);
// Set control pin low on power up
digitalWrite(controlPin, LOW);  
// Attach HB-25 to the control pin & set valid range                    
servo.attach(controlPin, 800, 2200);
servo.writeMicroseconds(STOP);

Arduino Library


To make using the HB-25 a bit easier and to hide some of the complexity we wrote an Arduino library for it. This consists of four files (click to download):

1. HB25MotorControl.h;
2. HB25MotorControl.cpp;
3. Keywords.txt; and
4. HB-25_Test.ino

To use this library, you need to create a new folder in your Arduino libraries folder called HB25MotorControl. Copy HB25MotorControl.h, HB25MotorControl.cpp and keywords.txt into this folder. Then create a sub-folder called examples and place HB-25_Test.ino into that.

You need to restart the Arduino IDE (if it is already open) to be able to see and use this library.

The example sketch should demonstrate how you use the library, but at its simplest:

#include <Servo.h>
#include <HB25MotorControl.h>

const byte controlPin = 9;              //  Pin Definition

HB25MotorControl motorControl(controlPin);

void setup() {
  motorControl.begin();
  motorControl.moveAtSpeed(500);
}

void loop() {
  
}

Valid speed ranges for the forwardAtSpeed and reverseAtSpeed methods are 0 (stop) to 500 (maximum speed). For rampToSpeed and moveAtSpeed you can use from -500 (full reverse) to 500 (full forward). As before, a speed of 0 will stop the motor.

Feel free to modify and reuse the library as you like. If you do improve it, then let us know. Attribution is nice but not necessary, and as usual this library comes with no warranties, so use at your own risk.

8 comments:

  1. How would you use this with 2 HB25s ?

    1 for each wheel.

    ReplyDelete
    Replies
    1. I think I have my answer..

      Call as:

      HB25MotorControl motorControl(controlPin);

      and then for the 2nd HB25:

      HB25MotorControl motorControl1(controlPin1);

      ?

      Delete
    2. Hi Unknown, this library is for using the HB-25 in mode 1, which requires a separate digital output to control each motor controller. Your answer should work. My code looks like this:

      HB25MotorControl leftMotor, rightMotor;

      Then in my Robot class initiator:

      leftMotor(pin_LW_Servo), rightMotor(pin_RW_Servo)

      then in the Robot.begin() method:

      leftMotor.begin();
      rightMotor.begin();

      Finally, I define a Robot move method:

      /*
      * @brief Move both motors at speed (-500 to 500).
      */
      void move(int speed) {
      leftMotor.moveAtSpeed(speed);
      rightMotor.moveAtSpeed(speed);
      state = stateMoving;
      }

      I will do a separate blog on the entire robot code at some stage. Let me know if you are still stuck.

      Delete
  2. Hi David, thanks for a great post. I wonder, do you know if it is possible to control the fan on the HB-25?

    ReplyDelete
    Replies
    1. Thanks for the comment Erik - no not to my knowledge. I believe the fan speed is based on the temperature of the H-Bridge but I don't have a circuit diagram of the HB-25 to confirm it.

      Delete
  3. Got an answer here: Erik,
    The fan is soldered directly to the HB25's power bus. There is no way to disable it in software; you would have to modify it by desoldering or cutting the wires to the fan.

    ― David Carrier
    Parallax Inc.

    ReplyDelete