Waveshare Motor Driver HAT

Has anyone gotten the Jetbot to work with the Waveshare Motor Driver HAT? (https://www.waveshare.com/motor-driver-hat.htm)

It seems similar to the Adafruit motor driver. I’m trying it and getting the following errors when creating an instance of the Robot object when running the basic_motion notebook in Jupyter Lab.

---------------------------------------------------------------------------
OSError                                   Traceback


 (most recent call last)
<ipython-input-3-b418ad9f6ab3> in <module>
----> 1 robot = Robot()

/usr/local/lib/python3.6/dist-packages/jetbot-0.4.0-py3.6.egg/jetbot/robot.py in __init__(self, *args, **kwargs)
     20     def __init__(self, *args, **kwargs):
     21         super(Robot, self).__init__(*args, **kwargs)
---> 22         self.motor_driver = Adafruit_MotorHAT(i2c_bus=self.i2c_bus)
     23         self.left_motor = Motor(self.motor_driver, channel=self.left_motor_channel, alpha=self.left_motor_alpha)
     24         self.right_motor = Motor(self.motor_driver, channel=self.right_motor_channel, alpha=self.right_motor_alpha)

/usr/local/lib/python3.6/dist-packages/Adafruit_MotorHAT-1.4.0-py3.6.egg/Adafruit_MotorHAT/Adafruit_MotorHAT_Motors.py in __init__(self, addr, freq, i2c, i2c_bus)
    229         self.motors = [ Adafruit_DCMotor(self, m) for m in range(4) ]
    230         self.steppers = [ Adafruit_StepperMotor(self, 1), Adafruit_StepperMotor(self, 2) ]
--> 231         self._pwm = PWM(addr, debug=False, i2c=i2c, i2c_bus=i2c_bus)
    232         self._pwm.setPWMFreq(self._frequency)
    233 

/usr/local/lib/python3.6/dist-packages/Adafruit_MotorHAT-1.4.0-py3.6.egg/Adafruit_MotorHAT/Adafruit_PWM_Servo_Driver.py in __init__(self, address, debug, i2c, i2c_bus)
     57         self.i2c = get_i2c_device(address, i2c, i2c_bus)
     58         logger.debug("Reseting PCA9685 MODE1 (without SLEEP) and MODE2")
---> 59         self.setAllPWM(0, 0)
     60         self.i2c.write8(self.__MODE2, self.__OUTDRV)
     61         self.i2c.write8(self.__MODE1, self.__ALLCALL)

/usr/local/lib/python3.6/dist-packages/Adafruit_MotorHAT-1.4.0-py3.6.egg/Adafruit_MotorHAT/Adafruit_PWM_Servo_Driver.py in setAllPWM(self, on, off)
     93     def setAllPWM(self, on, off):
     94         "Sets a all PWM channels"
---> 95         self.i2c.write8(self.__ALL_LED_ON_L, on & 0xFF)
     96         self.i2c.write8(self.__ALL_LED_ON_H, on >> 8)
     97         self.i2c.write8(self.__ALL_LED_OFF_L, off & 0xFF)

/usr/local/lib/python3.6/dist-packages/Adafruit_GPIO-1.0.4-py3.6.egg/Adafruit_GPIO/I2C.py in write8(self, register, value)
    114         """Write an 8-bit value to the specified register."""
    115         value = value & 0xFF
--> 116         self._bus.write_byte_data(self._address, register, value)
    117         self._logger.debug("Wrote 0x%02X to register 0x%02X",
    118                      value, register)

/usr/local/lib/python3.6/dist-packages/Adafruit_PureIO-1.0.4-py3.6.egg/Adafruit_PureIO/smbus.py in write_byte_data(self, addr, cmd, val)
    266         # Send the data to the device.
    267         self._select_device(addr)
--> 268         self._device.write(data)
    269 
    270     def write_word_data(self, addr, cmd, val):

OSError: [Errno 121] Remote I/O error

Any help is greatly appreciated!

Well, I got it working. I basically combined the Waveshare motor driver HAT code with the Jetbot code in robot.py. So I created the following file and placed it in the /usr/local/lib/python3.6/dist-packages/jetbot-0.4.0-py3.6.egg directory which is in the Python sys/path. The file PCA9685.py must be placed in the same directory. I also added 2 entries in the /etc/modules file: i2c-dev
i2c-bcm2708

Check the link https://www.waveshare.com/w/upload/8/81/Motor_Driver_HAT_User_Manual_EN.pdf for instructions, code and files.

motor_driver.py file:

#!/usr/bin/python

# ----------------------------------------------
# Motor Driver class for the Waveshare Motor HAT
# (placed here and modified  by D.L. Feb. 2020)
# ----------------------------------------------
from PCA9685 import PCA9685

Dir = [
    'forward',
    'backward',
]
pwm = PCA9685(0x40, debug=False)
pwm.setPWMFreq(50)
class MotorDriver():
    def __init__(self):
        self.PWMA = 0
        self.AIN1 = 1
        self.AIN2 = 2
        self.PWMB = 5
        self.BIN1 = 3
        self.BIN2 = 4

    def MotorRun(self, motor, index, speed):
        if speed > 100:
            return
        if(motor == 0):
            pwm.setDutycycle(self.PWMA, speed)
            if(index == Dir[0]):
                pwm.setLevel(self.AIN1, 0)
                pwm.setLevel(self.AIN2, 1)
            else:
                pwm.setLevel(self.AIN1, 1)
                pwm.setLevel(self.AIN2, 0)
        else:
            pwm.setDutycycle(self.PWMB, speed)
            if(index == Dir[0]):
                pwm.setLevel(self.BIN1, 0)
                pwm.setLevel(self.BIN2, 1)
            else:
                pwm.setLevel(self.BIN1, 1)
                pwm.setLevel(self.BIN2, 0)

    def MotorStop(self, motor):
        if (motor == 0):
            pwm.setDutycycle(self.PWMA, 0)
        else:
            pwm.setDutycycle(self.PWMB, 0)

class Robot():
    def __init__(self):
        self.left_motor = MotorDriver()
        self.right_motor = MotorDriver()

    def set_motors(self, left_speed, right_speed):
        self.left_motor.MotorRun(0,left_speed)
        self.right_motor.MotorRun(1, right_speed)

    def forward(self, speed=100, duration=None):
        self.left_motor.MotorRun(0, "forward", speed)
        self.right_motor.MotorRun(1,"forward", speed)

    def backward(self, speed=100):
        self.left_motor.MotorRun(0, "backward", speed)
        self.right_motor.MotorRun(1,"backward", speed)

    def left(self, speed=100):
        self.left_motor.MotorRun(0, "backward", speed)
        self.right_motor.MotorRun(1, "forward", speed)

    def right(self, speed=100):
        self.left_motor.MotorRun(0, "forward", speed)
        self.right_motor.MotorRun(1, "backward", speed)

    def stop(self):
        self.left_motor.MotorStop(0)
        self.right_motor.MotorStop(1)

This way, we can use the basic_motion.ipynb just changing one line:
change

from jetbot import Robot

to

from motor_driver import Robot

Also, the speed parameter in the motion commands (forward, backward, left, right) should be between 0-100 rather than 0-0.1.

Perhaps a crude solution and I hope to improve the code for better Jetbot integration. But in the meantime this should allow folks to use the Waveshare motor driver hat, which seems to work very well, btw.

1 Like

First a big ‘Thank you’ for the solved problem!

There is a bug by using basic_motion.ipy. If you try to " Controlling motors individually"

You can solve this by editing te following line:

class Robot():
def init(self):
self.left_motor = MotorDriver()
self.right_motor = MotorDriver()

def set_motors(self, left_speed, right_speed):
    self.left_motor.MotorRun(0, left_speed)
    self.right_motor.MotorRun(1, right_speed)

Edit to:

class Robot():
def init(self):
self.left_motor = MotorDriver()
self.right_motor = MotorDriver()

def set_motors(self, left_speed, right_speed):
    self.left_motor.MotorRun(0, "forward", left_speed)
    self.right_motor.MotorRun(1, "forward", right_speed)