Rover Motor Control
Table of Contents
- 1. Introduction & Idea
- 2. Plan
- 3. ROS
- 4. Getting started with the MAX40080
- 5. Current sense ROS node
- 6. Data logging node
- 7. GUI for the MAX40080
- 8. Experimenting with DC motors
- 9. Humming DC motor
- 10. Soft starting a motor
- 11. L298N motor driver issues
- 12. Constant current motor driver
- 13. Motor controller ROS node
- 14. Torque test stand
- 15. Rover motor testing
- 16. Summary
1. Introduction & Idea
Hi! This will be my second and final blog for the Experimenting with Current Sense Amplifiers Design Challenge. In the first blog, I covered my initial plan and idea for this design challenge. I haven’t managed to complete all of the things I initially thought, but on the other side, I’ve done a lot of things I didn’t plan on doing that came from me working with the sensor, turning it into a real experimenting type of project!
To summarize the first blog, my idea is to use the MAX40080 to work on better control of the motors on my Orb-Weaver rover. The rover currently uses a rubber band-based gearbox for driving the wheels on the rover.
I went for this approach instead of using gears because I didn’t have any overcurrent protection for the motor or the motor controllers, so I could have easily burnt them out if the wheel was blocked with a geared gearbox. With a rubber band gearbox like this, the rubber bands could either slip or break as shown in the picture above. This gearbox of course had its limitations, like the maximum torque it could transfer, and also, because of the rubber band slipping, I couldn’t use the encoders on the motors to have more precise rover movements. This is why I decided to upgrade to this style of a gearbox
Using the MAX40080 I can essentially protect the motor and the motor driver from high currents as well as play around with torque control. Another thing that can be easily implemented with the MAX40080 is predictive maintenance, where I can look at all 4 motor currents and if a single motor is drawing more current than all other motors constantly, it probably means there is some sort of an issue that can be anything from degrading bearings to grass or something else stuck in the wheel.
2. Plan
With my idea laid out, now I’ll go through some key points that I plan on hitting with a plan on a few more things that I plan to design/build along the way.
Challenger Kit
Let’s begin with the challenger kit that has been provided for this Design Challenge. The challenger kit is made out of 3 things:
- Raspberry Pi 3 Model B
- Raspberry Pi Click Shield
- MikroE Current 6 Click with the MAX40080 Current Sense Amplifier
As described in the first section of this blog, the ultimate goal is to have current sensors for each motor, but for testing purposes, I will be using this setup to test one of the motors with the MAX40080 current sense amplifier.
ROS
Since I will be using a Raspberry for all of this testing, I thought it would be appropriate to go with ROS for this project since I already had a plan on upgrading the rover to ROS. ROS stands for Robot Operating System, and I’ll give a brief overview of it in this blog.
Things I will be making
There are a couple of things I plan on prototyping and making for this design challenge. These things range from mechanical and electrical to software sub-projects. Here is a short list:
- Torque testing stand
- DC motor soft starter
- Constant current DC motor driver
- GUI for the MAX40080
3. ROS
As mentioned above ROS stands for Robot Operating System. To quote:
“ROS is an open-source robotics middleware suite. Although ROS is not an operating system (OS) but a set of software frameworks for robot software development, it provides services designed for a heterogeneous computer cluster such as hardware abstraction, low-level device control, implementation of commonly-used functionality, message-passing between processes, and package management.”
ROS has become the standard for robotics, and since it’s open-source, there are a lot of resources available for it online. I won’t get into any details too much, but I will explain the basic functionality of ROS.
ROS structure
These are the key points that are needed to understand the basic functionality of ROS:
- Nodes
- Topics
- Services
There are other important things like parameters and so on, but these things will give a clear picture. To begin, you can look at nodes as small individual chunks of programs that exist for themselves and perform a specific function. Topics our like message channels through which nodes communicate with each other. Each node can either subscribe or publish data to a topic.
Besides topics we also have services. Services are an easy way to request data from a node or to give instructions to a node. We can write a service call through a terminal or we can have a service call in a node.
Installing ROS
In all honesty, there are a lot of things to do and get right for installing ROS, so a much easier solution is to find an already compiled image of ROS for the Raspberry. I’ve done the same thing, here’s the link to the image I’ve found.
Hackster: https://www.hackster.io/dmitrywat/ros-melodic-on-raspberry-pi-4-debian-buster-rplidar-a1m8-0d63d1
Ubiquity: https://learn.ubiquityrobotics.com/noetic_pi_image_downloads
4. Getting started with the MAX40080
To begin, I’ll explain my goal of using the MAX40080. While the sensor can read both the current and voltage in various different modes with various different I2C configurations and so on, I’ll be concentrating on the specific use of the sensor. I want to do continuous current readings using the sensor and be able to adjust the relevant parameters. My goal is to create a ROS package that would make it easy to integrate into robotic projects.
Communicating with MAX40080
For working with the sensor I will be using Python and the SMBUS library since it’s an I2C sensor. The first thing we need to do is check the address of the sensor. The address of the sensor is defined with an external resistor on the click board.
We need to look at the resistor R4, and looking at its value we can see that the address for our sensor is 0x21. Looking at the datasheet, the default state on the sensor is standby mode.
Configuring the MAX40080
The first thing we need to do is change it to active mode and we can update some parameters along the way. To do that, we need to write to the configuration register
Here is an example of a configuration that we want to write to the configuration register:
- 128 filter size
- 120ksps ADC sample rate
- 5A input range
- Active mode
Looking at the datasheet and the values we’ve selected, we would end up with this register value
0101100001100011
The register is 2 bytes, we need to split it into bytes and calculate the LSB & MSB.
LSB, in this case, would be: 01100011 → 0x63
MSB, in this case, would be: 01011000 → 0x58
Using those, we need to calculate the CRC8 which we can, for now, do use an online calculator where we get the value:
CRC8 → 0xA9
Now we can write to the register using this command:
bus.write_i2c_block_data(max_address, 0x00, [LSB, MSB, int('0x' + CRCB, base = 16)])
Reading current data from the MAX40080
We need to read the register in multiple bytes, we can do that with this command:
reading = bus.read_i2c_block_data(max40080_addr[0], 0x0C, 3)
This is the raw value that we get when we read from the sensor. The data is contained within the first 2 bytes of the reading. To actually get usable data, we need to convert that into mA. Here is a function I wrote in Python for doing just that:
def convert_to_ma(reading): # Getting the needed bytes from the reading first_byte_dec = reading[0] second_byte_dec = reading[1] # Converting them to binary first_byte_bin = dec_to_binary(first_byte_dec) second_byte_bin = dec_to_binary(second_byte_dec) # Combining them into the register value register_value = second_byte_bin + first_byte_bin # Extracting the data from the register value data_valid_flag = register_value[0] sign = register_value[3] reg_val = register_value[4:] if data_valid_flag != '1': # If this is the case, we have a bad reading print('Error reading from sensor') return -10000.00 # Value of this multiplier depends on how the current flows multiplier = 1 # If the value of sign is '1' that means that the current flow is negative if sign == '1': multiplier = -1 cur_mag = 4096 - int(reg_val, 2) else: cur_mag = int(reg_val, 2) # Now we need to convert that data into mA global range_multiplier current_value = multiplier * 1000 * cur_mag * range_multiplier / (4095 * 25 * 0.01) # We return the converted value return current_value
Reading the configuration of the MAX40080
Just as we've written to the configuration register, we can also read the current configuration to see what parameters are currently set on our sensor. One case where that's highly useful is when we need to update the range multiplier that we're using for reading the current value since it changes depending on the range that is set on the sensor. Here is a function for reading the configuration.
# Function for reading the current configuration of the MAX40080 def current_config(max_address): # Reading the register value reg_data = bus.read_i2c_block_data(max_address, 0x00, 3) # Extracting the LSB & MSB LSB = reg_data[0] MSB = reg_data[1] # Generating the register value from LSB & MSB reg_value = str(format(MSB, '08b')) + str(format(LSB, '08b')) # Loading the data arrays global adc_sample_rate, digital_filter, range_multiplier # Reading the data filter_val = digital_filter[int(reg_value[1:4], 2)] adc_val = adc_sample_rate[int(reg_value[4:8], 2)] range = 5 range_multiplier = 1.25 if reg_value[9] == '1': range = 1 range_multiplier = 0.25 return filter_val, adc_val, range
For this code to work, we are using global variables which are arrays containing all of the possible values which I've copied from the datasheet.
adc_sample_rate = [15, 99999999, 23.45, 30, 37.5, 47.1, 60, 93.5, 120, 150, 234.5, 375, 468.5, 750, 1000] digital_filter = [0, 8, 16, 32, 64, 128] range_multiplier = 1.25
5. Current sense ROS node
In this section, I will go over the structure and code for the current sense ROS node which will be the backbone for the rest of the project and blog.
Node structure
In a previous section above, I've given a short explanation of what ROS is and what nodes, services, and topics are. So for working with the sensor, there will be a node called current_sense_node which will be the only node that's communicating with the MAX40080, and by publishing that data to a topic it will send it to other nodes later on. The node will publish data to the /sensor/motor_current topic that has a special motor_currents message. Each topic needs to have a message type, it can be anything from a String or Float32 to custom messages as I've done in this case. The message contains an array of float variables, this is so that the node can be used with multiple MAX40080 with different addresses.
# Message for the motor current measurements
float32[] motor_current
Besides the node being a publisher to the mentioned topic, the node will also have a service called /sensor/max40080. Through this service, we will be able to check the current configuration of the MAX40080 or update it to a new configuration. Here is what an example call and read look like for this ROS service.
Code
#!/usr/bin/env python3
# Libraries
import rospy
import smbus
import time
import crc8
# Messages
from current_sense_node.msg import motor_currents
from std_msgs.msg import Float32
# Services
from current_sense_node.srv import max40080_service
# Parameters
NUM_MOTORS = 1
AVG_SIZE = 10
#max40080_addr = 0x21
max40080_addr = [0x21, 0x21, 0x21, 0x21, 0x21, 0x21]
bus = smbus.SMBus(1)
adc_sample_rate = [15, 99999999, 23.45, 30, 37.5, 47.1, 60, 93.5, 120, 150, 234.5, 375, 468.5, 750, 1000]
digital_filter = [0, 8, 16, 32, 64, 128]
range_multiplier = 1.25
def dec_to_binary(num):
bin_num = str(bin(num).replace('0b',''))
while True:
if len(bin_num) < 8:
bin_num = '0' + bin_num
else:
return bin_num
def convert_to_ma(reading):
# Getting the needed bytes from the reading
first_byte_dec = reading[0]
second_byte_dec = reading[1]
# Converting them to binary
first_byte_bin = dec_to_binary(first_byte_dec)
second_byte_bin = dec_to_binary(second_byte_dec)
# Combining them into the register value
register_value = second_byte_bin + first_byte_bin
# Extracting the data from the register value
data_valid_flag = register_value[0]
sign = register_value[3]
reg_val = register_value[4:]
if data_valid_flag != '1':
# If this is the case, we have a bad reading
print('Error reading from sensor')
return -10000.00
# Value of this multiplier depends on how the current flows
multiplier = 1
# If the value of sign is '1' that means that the current flow is negative
if sign == '1':
multiplier = -1
cur_mag = 4096 - int(reg_val, 2)
else:
cur_mag = int(reg_val, 2)
# Now we need to convert that data into mA
global range_multiplier
current_value = multiplier * 1000 * cur_mag * range_multiplier / (4095 * 25 * 0.01)
# We return the converted value
return current_value
def calc_crc8(max_address, config_reg, LSB, MSB):
new_hash = crc8.crc8()
new_hash.update(bytes.fromhex(str(format(2 * max_address, '#04x'))[2:]))
new_hash.update(bytes.fromhex(str(format(config_reg, '#04x'))[2:]))
new_hash.update(bytes.fromhex(str(format(LSB, '#04x'))[2:]))
new_hash.update(bytes.fromhex(str(format(MSB, '#04x'))[2:]))
return new_hash.hexdigest()
# Function for getting the adc sample rate code
def adc_code(sample_rate):
# Loading our list of available frequencies
global adc_sample_rate
# Checking if we can find the frequency in our list, if not, we return an error
try:
adc_sample_rate.index(sample_rate)
except:
print('Error')
return False, '2222'
# Returning the value as a 4 digit binary code that we need for configuring the MAX40080
return True, format(adc_sample_rate.index(sample_rate), '04b')
# Function for getting the digital filter code
def filter_code(filter):
# Loading our list of available filters
global digital_filter
# Checking if we can find the filter in our list, if not, we return an error
try:
digital_filter.index(filter)
except:
print('Error')
return False, '2222'
# Returning the value as a 3 digit binary code that we need for configuring the MAX40080
return True, format(digital_filter.index(filter), '03b')
# Function for getting the current range bit
def range_code(range):
# Checking if the user selected the right range
if range != 5 and range != 1:
print('Error')
return False, '2'
# We also need to load and update the multiplier
global range_multiplier
# If the user selected the range of 5A
if range == 5:
range_multiplier = 1.25
return True, '0'
# If the user selected the range of 1A
if range == 1:
range_multiplier = 0.25
return True, '1'
# Function for generating the LSB and MSB for updating the configuration of the MAX40080
def configuration_bytes(filter, adc, range):
# Generating the codes that we need for the I2C message
flag1, filter_val = filter_code(filter)
flag2, adc_val = adc_code(adc)
flag3, range_val = range_code(range)
# Checking if any of flags are Flase
if flag1 == False or flag2 == False or flag3 == False:
return 0x00, 0x00, False
# Generating the LSB & MSB
LSB = '0' + range_val + '100011'
MSB = '0' + filter_val + adc_val
# After generating the values, we need to convert them to hex
LSB_hex = int(LSB, 2)
MSB_hex = int(MSB, 2)
# Now we return the values
return MSB_hex, LSB_hex, True
# Function for reading the current configuration of the MAX40080
def current_config(max_address):
# Reading the register value
reg_data = bus.read_i2c_block_data(max_address, 0x00, 3)
# Extracting the LSB & MSB
LSB = reg_data[0]
MSB = reg_data[1]
# Generating the register value from LSB & MSB
reg_value = str(format(MSB, '08b')) + str(format(LSB, '08b'))
# Loading the data arrays
global adc_sample_rate, digital_filter, range_multiplier
# Reading the data
filter_val = digital_filter[int(reg_value[1:4], 2)]
adc_val = adc_sample_rate[int(reg_value[4:8], 2)]
range = 5
range_multiplier = 1.25
if reg_value[9] == '1':
range = 1
range_multiplier = 0.25
return filter_val, adc_val, range
# Function for changing the configuration of a single MAX40080
def configure_max40080(max_address, filter, adc, range):
MSB, LSB, flag = configuration_bytes(filter, adc, range)
if flag == True:
print('MSB: ' + hex(MSB) + '(' + str(MSB) + ')')
print('LSB: ' + hex(LSB) + '(' + str(LSB) + ')')
CRCB = calc_crc8(max_address, 0x00, LSB, MSB)
print('CRC8: 0x', CRCB)
# Updating the configuration
bus.write_i2c_block_data(max_address, 0x00, [LSB, MSB, int('0x' + CRCB, base = 16)])
time.sleep(0.1)
print(current_config(max_address))
return True
return False
# Service callback function
def max_srv_callback(req):
# Loading up the number of sensors and their addresses
global max40080_addr, NUM_MOTORS
# First checking what kind of command we're dealing with
if req.command == 'read':
# This is the case where we only print out the data
if req.sensor > NUM_MOTORS:
# This is an error because we requested info about a device that isn't activated
print('This device is out of range for the defined number of sensors')
return False, 0, 0, 0
# This is the case where we go through all of the devices and print the data out for all of them
if req.sensor == 0:
print('Number of sensors configured: ', NUM_MOTORS)
for i in range(NUM_MOTORS):
print('Sensor ' + str(i + 1) + ' configuration:')
flt, adc, rng = current_config(max40080_addr[i])
print('Filter: ' + str(flt))
print('ADC: ' + str(adc) + 'ksps')
print('Range: ' + str(rng) + 'A')
return True, 0, 0, 0
# This is the case where we ask for the data of only one sensor
print('Sensor ' + str(req.sensor) + ' configuration:')
flt, adc, rng = current_config(max40080_addr[req.sensor + 1])
print('Filter: ' + str(flt))
print('ADC: ' + str(adc) + 'ksps')
print('Range: ' + str(rng) + 'A')
return True, flt, adc, rng
# This is the case where we want to configure a sensor or all at the same time
elif req.command == 'config' or req.command == 'configure':
# In this case, we want to configure all of the sensors at once
if req.sensor == 0:
for i in range(NUM_MOTORS):
# First we need to read the old configuration
flt, adc, rng = current_config(max40080_addr[i])
# Now we can work on updating the configuration
# We check for every param if it's -1, because if it is, we keep the old config
if req.param1 != -1:
flt = req.param1
if req.param2 != -1:
adc = req.param2
if req.param3 != -1:
rng = req.param3
# Now that we have the latest param we want, we can update the sensor
resp = configure_max40080(max40080_addr[i], flt, adc, rng)
# If the response is False, we stop trying to update configuration
if resp == False:
print('Error trying to update the configuration of device ', i + 1)
return False, 0, 0, 0
# If we've gotten out of the loop successfully, the update was successfull
return True, 0, 0, 0
# This is the case where we update only a single sensor
# Before we get to the sensor we need to check if the sensor is in range
if req.sensor > NUM_MOTORS:
print('Sensor out of range of defined sensors')
return False, 0, 0, 0
# First we need to read the old configuration
flt, adc, rng = current_config(max40080_addr[req.sensor])
# Now we can work on updating the configuration
# We check for every param if it's -1, because if it is, we keep the old config
if req.param1 != 255:
flt = req.param1
if req.param2 != 255:
adc = req.param2
if req.param3 != 255:
rng = req.param3
# Now that we have the latest param we want, we can update the sensor
resp = configure_max40080(max40080_addr[req.sensor], flt, adc, rng)
# If the response is False, we stop trying to update configuration
if resp == False:
print('Error trying to update the configuration of device ', req.sensor)
return False, 0, 0, 0
# Now we can check the config and return the latest values
flt, adc, rng = current_config(max40080_addr[req.sensor])
return True, flt, adc, rng
# Node startup configuration
print('Starting configuration of MAX40080')
for i in range(NUM_MOTORS):
flag = configure_max40080(max40080_addr[i], 128, 120, 5)
if flag == True:
time.sleep(0.1)
flt, adc, rng = current_config(max40080_addr[i])
print('Filter: ' + str(flt))
print('ADC Sample Rate: ' + str(adc) + 'ksps')
print('Current range: ' + str(rng) + 'A')
print('Configuration done')
# Initializing the ROS Node and publisher
rospy.init_node('current_sense_node', anonymous = False)
pub = rospy.Publisher('/sensor/motor_current', motor_currents, queue_size=10)
max_srv = rospy.Service('/sensor/max40080', max40080_service, max_srv_callback)
r = rospy.Rate(100)
# This is the main loop of our node
while not rospy.is_shutdown():
pub_msg = []
for i in range(NUM_MOTORS):
milliamps = 0.00
for j in range(AVG_SIZE):
reading = bus.read_i2c_block_data(max40080_addr[0], 0x0C, 3)
milliamps += convert_to_ma(reading)
time.sleep(0.001)
pub_msg.append(milliamps / 10)
pub.publish(pub_msg)
r.sleep()
I've covered most of the functions used in this code in the section above where I've talked about interfacing with the MAX40080. To explain how the node functions internally, it has an infinite loop essentially that is constantly trying to read current data from the MAX40080 at a set rate:
# Initializing the ROS Node and publisher
rospy.init_node('current_sense_node', anonymous = False)
pub = rospy.Publisher('/sensor/motor_current', motor_currents, queue_size=10)
max_srv = rospy.Service('/sensor/max40080', max40080_service, max_srv_callback)
r = rospy.Rate(100)
# This is the main loop of our node
while not rospy.is_shutdown():
pub_msg = []
for i in range(NUM_MOTORS):
milliamps = 0.00
for j in range(AVG_SIZE):
reading = bus.read_i2c_block_data(max40080_addr[0], 0x0C, 3)
milliamps += convert_to_ma(reading)
time.sleep(0.001)
pub_msg.append(milliamps / 10)
pub.publish(pub_msg)
r.sleep()
Besides that loop running, we have some simple functions, most of which I've covered above, and we have the function for the service. How it works with ROS and python is that a service call acts as an interrupt and calls that function.
# Service callback function
def max_srv_callback(req):
# Loading up the number of sensors and their addresses
global max40080_addr, NUM_MOTORS
# First checking what kind of command we're dealing with
if req.command == 'read':
# This is the case where we only print out the data
if req.sensor > NUM_MOTORS:
# This is an error because we requested info about a device that isn't activated
print('This device is out of range for the defined number of sensors')
return False, 0, 0, 0
# This is the case where we go through all of the devices and print the data out for all of them
if req.sensor == 0:
print('Number of sensors configured: ', NUM_MOTORS)
for i in range(NUM_MOTORS):
print('Sensor ' + str(i + 1) + ' configuration:')
flt, adc, rng = current_config(max40080_addr[i])
print('Filter: ' + str(flt))
print('ADC: ' + str(adc) + 'ksps')
print('Range: ' + str(rng) + 'A')
return True, 0, 0, 0
# This is the case where we ask for the data of only one sensor
print('Sensor ' + str(req.sensor) + ' configuration:')
flt, adc, rng = current_config(max40080_addr[req.sensor + 1])
print('Filter: ' + str(flt))
print('ADC: ' + str(adc) + 'ksps')
print('Range: ' + str(rng) + 'A')
return True, flt, adc, rng
# This is the case where we want to configure a sensor or all at the same time
elif req.command == 'config' or req.command == 'configure':
# In this case, we want to configure all of the sensors at once
if req.sensor == 0:
for i in range(NUM_MOTORS):
# First we need to read the old configuration
flt, adc, rng = current_config(max40080_addr[i])
# Now we can work on updating the configuration
# We check for every param if it's -1, because if it is, we keep the old config
if req.param1 != -1:
flt = req.param1
if req.param2 != -1:
adc = req.param2
if req.param3 != -1:
rng = req.param3
# Now that we have the latest param we want, we can update the sensor
resp = configure_max40080(max40080_addr[i], flt, adc, rng)
# If the response is False, we stop trying to update configuration
if resp == False:
print('Error trying to update the configuration of device ', i + 1)
return False, 0, 0, 0
# If we've gotten out of the loop successfully, the update was successfull
return True, 0, 0, 0
# This is the case where we update only a single sensor
# Before we get to the sensor we need to check if the sensor is in range
if req.sensor > NUM_MOTORS:
print('Sensor out of range of defined sensors')
return False, 0, 0, 0
# First we need to read the old configuration
flt, adc, rng = current_config(max40080_addr[req.sensor])
# Now we can work on updating the configuration
# We check for every param if it's -1, because if it is, we keep the old config
if req.param1 != 255:
flt = req.param1
if req.param2 != 255:
adc = req.param2
if req.param3 != 255:
rng = req.param3
# Now that we have the latest param we want, we can update the sensor
resp = configure_max40080(max40080_addr[req.sensor], flt, adc, rng)
# If the response is False, we stop trying to update configuration
if resp == False:
print('Error trying to update the configuration of device ', req.sensor)
return False, 0, 0, 0
# Now we can check the config and return the latest values
flt, adc, rng = current_config(max40080_addr[req.sensor])
return True, flt, adc, rng
The service allows us to do one of 2 things. To either read the configuration register data or to configure something on the MAX40080. To make it a bit easier to configure, I've copied all of the data from the datasheet, so the user only needs to enter 15 for the ADC sample rate for example. That would cover the essential code for the topic that makes it work, there are a few more things that need to be done for the node to work, to properly configure the package.xml and CMakeLists.txt files for example. There are a lot of great tutorials covering that, I will be attaching an image for the Pi at the end of the blog.
First test
I've connected the constant current load in series with my multimeter and the MAX40080 so I can compare the readings to make sure everything was working fine, and it was! The readings on the constant load are off, but the multimeter and the MAX40080 are within a few mA of each other which is great.
6. Data logging node
Before I get to testing and playing around with the sensor more. I wanted to create an easy way to log all of the data during testing. The current sense node is constantly publishing the data to the topic, so what we can do is make another node that will subscribe to the topic and save all of the data into a CSV file. This will allow us to run that CSV data through a script to plot it out.
Code
#!/usr/bin/env python3
# Libraries
import rospy
import csv
import os
import sys
import time
# Messages
from current_sense_node.msg import motor_currents
data_dir = '/home/pi/orbweaver_ws/src/data_logging_node/data'
data_file = ''
generated_file = False
def data_callback(req):
global data_dir, data_file, generated_file
motor_data = req.motor_current
num_motors = len(motor_data)
if generated_file == False:
flag = True
counter = 0
while flag == True:
if os.path.exists(data_dir + '/data' + str(counter) + '.csv') == False:
flag = False
generated_file = True
data_file = data_dir + '/data' + str(counter) + '.csv'
else:
counter += 1
with open(data_file, 'w') as csv_file:
csv_writer = csv.writer(csv_file)
header_row = []
for i in range(num_motors):
header_row.append('Motor' + str(i + 1))
csv_writer.writerow(header_row)
print('Created data file and header row written')
else:
with open(data_file, 'a') as csv_file:
csv_writer = csv.writer(csv_file)
csv_writer.writerow(motor_data)
# Initializing the ROS Node and subscriber
rospy.init_node('data_logging_node', anonymous = False)
sub = rospy.Subscriber('/sensor/motor_current', motor_currents, data_callback)
r = rospy.Rate(100)
while not rospy.is_shutdown():
continue
So that we don't overwrite any data, the code checks if we've already made a file with the same name, and continues increasing the number in the name until it gets to the one that we haven't made. It saves all of the data files into a folder.
Plotting the data
The only thing left to do is visualize the data by plotting it. To do this, I would transfer the CSV files using VNC to my laptop and then run a small Python scripting for plotting the data.
import csv
import matplotlib.pyplot as plt
data_file = 'data19.csv'
measurements = []
with open(data_file, 'r') as csv_file:
reader = csv.reader(csv_file)
flag = False
for row in reader:
if flag == False:
flag = True
else:
measurements.append(float(row[0]))
# plot
fig, ax = plt.subplots()
ax.grid(axis = 'both', color = 'black', linestyle = '-', linewidth = 0.2)
ax.set_title('Current measurement')
ax.set_xlabel('Reading number')
ax.set_ylabel('Current [mA]')
ax.plot(measurements, linewidth = 0.8, color = 'b')
ax.legend()
#ax.set(xlim = (10, 30), ylim = (30, 70))
fig.savefig('HummingTest5DoubleCap.png', dpi = 200)
plt.show()
Data logging test
Here is another video of testing the sensor with the logged data on the plot.
The setup was the same as in the first video, just this time, besides running the current sense node, I've also run the data logging node as well. Here are the results of that:
7. GUI for the MAX40080
While the data logging node is a great tool for post-experiment analysis, it would be great if we could take a look at the current data live while we're performing an experiment. In ROS there is a thing called rqt_plot which does a live plot of the data on a topic, but it just doesn't work too well enough for what I want. So I decided to make my own GUI for the MAX40080 to make doing all sorts of experiments much easier.
Requirements
I'll begin with the requirements that I wanted this GUI to fulfill. I don't need it to do too many things, but I wanted to have the ability to see live readings on a graph and be able to see the configuration of the MAX40080 as well as update it with new parameters. I decided to stick with 3 parameters:
- ADC sample rate
- Digital filter size
- Input range
To summarize I'll need to read the data from the topic as well as make service calls to the node to read the configuration as well as service calls to update the configuration of the MAX40080.
Design
Here is the design for the finished GUI
On the right of the window is the graph that is constantly updated with new data from the topic while on the left we have the configuration of the sensor as well as the controls for adjusting the parameters on the MAX40080.
Code
#!/usr/bin/env python3
# PYQT Stuff
from PyQt5.QtWidgets import QApplication, QPushButton, QLineEdit, QLabel, QWidget, QSlider, QSpinBox, QComboBox, QMainWindow
from PyQt5.QtGui import QPainter, QColor, QPen, QFont, QBrush
from PyQt5.QtCore import Qt, QTimer
from PyQt5 import QtWidgets
from pyqtgraph.Qt import QtGui, QtCore
from pyqtgraph import PlotWidget, plot
import pyqtgraph as pg
# Libraries
import rospy
import threading
import os
import sys
# Messages
from current_sense_node.msg import motor_currents
# Services
from current_sense_node.srv import max40080_service
adc_sample_rate_arr = [15, 23.45, 30, 37.5, 47.1, 60, 93.5, 120, 150, 234.5, 375, 468.5, 750, 1000]
digital_filter_arr = [0, 8, 16, 32, 64, 128]
x_points_current = []
current_data = []
batch_size = 500
counter = 0
filter_size = 0
adc_sample_rate = 0
input_range = 0
filter_set = 0
adc_set = 15.0
range_set = 1
# Design Variables
borderColor = QColor(180, 180, 180)
borderWidth = 2
class GUIWindow(QWidget):
def __init__(self):
super().__init__()
self.title = 'MAX40080 Live Data'
self.left = 200
self.top = 200
self.width = 1920
self.height = 1000
self.qTimer = QTimer()
self.qTimer.setInterval(50)
self.qTimer.start()
self.qTimer.timeout.connect(self.update_plot_data)
self.qTimer.timeout.connect(self.updateEvent)
self.initUI()
def initUI(self):
global x_points_current, current_data, filter_size, adc_sample_rate, input_range
self.setWindowTitle(self.title)
self.setGeometry(self.left, self.top, self.width, self.height)
self.setAutoFillBackground(True)
p = self.palette()
p.setColor(self.backgroundRole(), QColor(20, 30, 35))
self.setPalette(p)
# Graph Widger
self.current_graph = pg.PlotWidget(self)
self.current_graph.setGeometry(600, 20, 1300, 960)
self.current_graph.setBackground(None)
self.current_graph.setYRange(0, 1500, padding=0.04)
data_pen = pg.mkPen(color = (255, 7, 58), width = 2)
self.current_dataline = self.current_graph.plot(x_points_current, current_data, pen = data_pen)
# Labels for the current configuration [cc]
self.label_cc_title = QLabel(self)
self.label_cc_title.setText('Current configuration')
self.label_cc_title.setGeometry(20, 20, 560, 60)
self.label_cc_title.setFont(QFont("Arial", 28))
self.label_cc_title.setStyleSheet("QLabel {color : rgb(150, 150, 150)}")
self.label_cc_title.setAlignment(QtCore.Qt.AlignCenter)
self.label_ccn_filter = QLabel(self)
self.label_ccn_filter.setText('Filter Size')
self.label_ccn_filter.setGeometry(20, 80, 280, 60)
self.label_ccn_filter.setFont(QFont("Arial", 20))
self.label_ccn_filter.setStyleSheet("QLabel {color : rgb(150, 150, 150)}")
self.label_ccn_filter.setAlignment(QtCore.Qt.AlignCenter)
self.label_ccn_adc = QLabel(self)
self.label_ccn_adc.setText('ADC Sample Rate')
self.label_ccn_adc.setGeometry(20, 140, 280, 60)
self.label_ccn_adc.setFont(QFont("Arial", 20))
self.label_ccn_adc.setStyleSheet("QLabel {color : rgb(150, 150, 150)}")
self.label_ccn_adc.setAlignment(QtCore.Qt.AlignCenter)
self.label_ccn_range = QLabel(self)
self.label_ccn_range.setText('Input Range')
self.label_ccn_range.setGeometry(20, 200, 280, 60)
self.label_ccn_range.setFont(QFont("Arial", 20))
self.label_ccn_range.setStyleSheet("QLabel {color : rgb(150, 150, 150)}")
self.label_ccn_range.setAlignment(QtCore.Qt.AlignCenter)
# Labels containing the data
self.label_cc_filter = QLabel(self)
self.label_cc_filter.setText(str(filter_size))
self.label_cc_filter.setGeometry(300, 80, 280, 60)
self.label_cc_filter.setFont(QFont("Arial", 20))
self.label_cc_filter.setStyleSheet("QLabel {color : rgb(150, 150, 150)}")
self.label_cc_filter.setAlignment(QtCore.Qt.AlignCenter)
self.label_cc_adc = QLabel(self)
self.label_cc_adc.setText(str(adc_sample_rate) + 'ksps')
self.label_cc_adc.setGeometry(300, 140, 280, 60)
self.label_cc_adc.setFont(QFont("Arial", 20))
self.label_cc_adc.setStyleSheet("QLabel {color : rgb(150, 150, 150)}")
self.label_cc_adc.setAlignment(QtCore.Qt.AlignCenter)
self.label_cc_range = QLabel(self)
self.label_cc_range.setText(str(input_range) + 'A')
self.label_cc_range.setGeometry(300, 200, 280, 60)
self.label_cc_range.setFont(QFont("Arial", 20))
self.label_cc_range.setStyleSheet("QLabel {color : rgb(150, 150, 150)}")
self.label_cc_range.setAlignment(QtCore.Qt.AlignCenter)
#
# Labels for the update configuration [uc]
#
self.label_uc_title = QLabel(self)
self.label_uc_title.setText('Set New Configuration')
self.label_uc_title.setGeometry(20, 280, 560, 60)
self.label_uc_title.setFont(QFont("Arial", 28))
self.label_uc_title.setStyleSheet("QLabel {color : rgb(150, 150, 150)}")
self.label_uc_title.setAlignment(QtCore.Qt.AlignCenter)
self.label_ucn_filter = QLabel(self)
self.label_ucn_filter.setText('Filter')
self.label_ucn_filter.setGeometry(20, 340, 160, 90)
self.label_ucn_filter.setFont(QFont("Arial", 24))
self.label_ucn_filter.setStyleSheet("QLabel {color : rgb(150, 150, 150)}")
self.label_ucn_filter.setAlignment(QtCore.Qt.AlignCenter)
self.label_ucn_adc = QLabel(self)
self.label_ucn_adc.setText('ADC')
self.label_ucn_adc.setGeometry(20, 430, 160, 90)
self.label_ucn_adc.setFont(QFont("Arial", 24))
self.label_ucn_adc.setStyleSheet("QLabel {color : rgb(150, 150, 150)}")
self.label_ucn_adc.setAlignment(QtCore.Qt.AlignCenter)
self.label_ucn_range = QLabel(self)
self.label_ucn_range.setText('Range')
self.label_ucn_range.setGeometry(20, 520, 160, 90)
self.label_ucn_range.setFont(QFont("Arial", 24))
self.label_ucn_range.setStyleSheet("QLabel {color : rgb(150, 150, 150)}")
self.label_ucn_range.setAlignment(QtCore.Qt.AlignCenter)
# Filter value slider and label
self.slider_uc_filter = QSlider(Qt.Horizontal, self)
self.slider_uc_filter.setGeometry(190, 350, 300, 70)
self.slider_uc_filter.setRange(0,5)
self.slider_uc_filter.valueChanged[int].connect(self.changeFilterSlider)
self.label_uc_filter = QLabel(self)
self.label_uc_filter.setText('0')
self.label_uc_filter.setGeometry(490, 340, 100, 90)
self.label_uc_filter.setFont(QFont("Arial", 20))
self.label_uc_filter.setStyleSheet("QLabel {color : rgb(150, 150, 150)}")
self.label_uc_filter.setAlignment(QtCore.Qt.AlignCenter)
# ADC value slider and label
self.slider_uc_adc = QSlider(Qt.Horizontal, self)
self.slider_uc_adc.setGeometry(190, 440, 300, 70)
self.slider_uc_adc.setRange(0,13)
self.slider_uc_adc.valueChanged[int].connect(self.changeADCSlider)
self.label_uc_adc = QLabel(self)
self.label_uc_adc.setText('15')
self.label_uc_adc.setGeometry(490, 430, 100, 90)
self.label_uc_adc.setFont(QFont("Arial", 20))
self.label_uc_adc.setStyleSheet("QLabel {color : rgb(150, 150, 150)}")
self.label_uc_adc.setAlignment(QtCore.Qt.AlignCenter)
# Range value slider and label
self.slider_uc_range = QSlider(Qt.Horizontal, self)
self.slider_uc_range.setGeometry(190, 530, 300, 70)
self.slider_uc_range.setRange(0,1)
self.slider_uc_range.valueChanged[int].connect(self.changeRangeSlider)
self.label_uc_range = QLabel(self)
self.label_uc_range.setText('1')
self.label_uc_range.setGeometry(490, 520, 100, 90)
self.label_uc_range.setFont(QFont("Arial", 20))
self.label_uc_range.setStyleSheet("QLabel {color : rgb(150, 150, 150)}")
self.label_uc_range.setAlignment(QtCore.Qt.AlignCenter)
# Update Config button
self.button_uc = QPushButton("Update Configuration", self)
self.button_uc.resize(360, 50)
self.button_uc.move(120, 620)
self.button_uc.clicked.connect(self.buttonUpdateFunction)
self.button_uc.setFont(QFont("Arial", 20))
self.button_uc.setStyleSheet("QPushButton {background-color : rgb(35, 45, 55); color : rgb(150, 150, 150); font-weight: bold}")
self.show()
def updateEvent(self):
global filter_size, adc_sample_rate, input_range
self.label_cc_filter.setText(str(filter_size))
self.label_cc_adc.setText(str(adc_sample_rate) + 'ksps')
self.label_cc_range.setText(str(input_range) + 'A')
self.update()
def update_plot_data(self):
global x_points_current, current_data, batch_size
if len(x_points_current) > batch_size:
self.current_dataline.setData(x_points_current[len(x_points_current) - batch_size:], current_data[len(x_points_current) - batch_size:])
else:
self.current_dataline.setData(x_points_current, current_data)
def paintEvent(self, event):
global borderColor, borderWidth
painter = QPainter()
painter.begin(self)
painter.setRenderHint(QPainter.Antialiasing)
painter.setPen(QPen(borderColor, borderWidth))
# Current configuration rectnagle
painter.drawRect(20, 20, 560, 240)
painter.drawLine(20, 80, 580, 80)
painter.drawRect(20, 280, 560, 400)
painter.drawLine(20, 340, 580, 340)
painter.drawLine(180, 340, 180, 610)
painter.drawLine(20, 610, 580, 610)
# Lines
painter.setPen(QPen(borderColor, borderWidth - 1))
painter.drawLine(20, 140, 580, 140)
painter.drawLine(20, 200, 580, 200)
painter.drawLine(290, 80, 290, 260)
painter.drawLine(20, 430, 580, 430)
painter.drawLine(20, 520, 580, 520)
def changeFilterSlider(self, value):
global filter_set, digital_filter_arr
filter_set = digital_filter_arr[value]
self.label_uc_filter.setText(str(filter_set))
def changeADCSlider(self, value):
global adc_set, adc_sample_rate_arr
adc_set = adc_sample_rate_arr[value]
self.label_uc_adc.setText(str(adc_set))
def changeRangeSlider(self, value):
global range_set
if value == 0:
range_set = 1
else:
range_set = 5
self.label_uc_range.setText(str(range_set))
def buttonUpdateFunction(self):
global filter_set, adc_set, range_set, filter_size, adc_sample_rate, input_range
resp = srv('config', 1, filter_set, adc_set, range_set)
if resp.response == True:
filter_size = resp.filter_size
adc_sample_rate = resp.adc_sample_rate
input_range = resp.range
class Controller:
def __init__(self):
pass
def show_gui_window(self):
self.gui_window = GUIWindow()
self.gui_window.show()
def sub_callback(req):
global x_points_current, current_data, counter
new_measurement = req.motor_current[0]
current_data.append(new_measurement)
x_points_current.append(counter)
counter += 1
# Main function
if __name__ == "__main__":
# Configuring the ROS Node
rospy.init_node('MAX40080_GUI', anonymous = False)
sub = rospy.Subscriber('/sensor/motor_current', motor_currents, sub_callback)
srv = rospy.ServiceProxy('/sensor/max40080', max40080_service)
# On startup, we need to read the current sensor configuration
resp = srv('read', 1, 0, 0, 0)
# If the response of the reading was True, we can update the data
if resp.response == True:
filter_size = resp.filter_size
adc_sample_rate = resp.adc_sample_rate
input_range = resp.range
# Turning on the GUI
app = QApplication(sys.argv)
controller = Controller()
controller.show_gui_window()
sys.exit(app.exec_())
For the GUI I used python and PyQt5. It's a really easy way of making all sorts of graphical interfaces. The only major problem I had was getting everything to work together as I'm using Python3 and most of the ROS is on Python2, but managed to get it all working by downgrading some PyQt libraries.
GUI test
The only thing left to do is test out the GUI with the MAX40080.
The Raspberry Pi 3 is struggling a bit with the GUI, but it's managing to make it work. Using the same setup as the last 2 times, we can see that the GUI performs as expected! Now we can get into playing with some motors.
8. Experimenting with DC motors
My initial plan was to only work on the motor controller for the Rover, but while playing around and experimenting with different motors and the sensor, I found some things that I thought I would take a closer look at. Let's take a look at some of the data I've recorded in those tests.
On the first graph, you can see the current of the motor when I started and let it spin up then disconnected it, and then did that again, while on the second graph you can see the current when I let the motor spin up and then try and slow it down a bit using my hand. One thing that is clearly obvious from the graph is the almost 2A high current peak at the motor startup. This is something I was expecting but didn't know what kind of magnitude to expect, and this is using a really small motor. There is a way of tackling this, soft starting, and this is something I decided to take on and will show later in this blog.
While trying out a different motor, I noticed a very strong sound at lower RPM (lower PWM on the driver), that seemed to almost completely disappear when going to 100% duty cycle on the PWM. I decided to investigate that and connect the MAX40080 sensor to the motor to see what was happening.
As you can see from the graph, at lower throttle (RPM) the current is all over the place, while it almost completely stabilizes when we increase the throttle to 100%. This humming sound that came from the motor is something I wanted to play around with first before I continue with other things.
9. Humming DC motor
This noise was the loudest at lower throttles and when using a single MOSFET as a driver instead of the off-the-shelf L298N-based motor driver. I haven't gone too deep into this topic, but what I managed to find out and what I found out working the best for me was adding a capacitor to the motor terminals. Here is a video that shows the difference in sound that adding a capacitor makes to the motor sound and speed quite surprisingly.
I wired up a capacitor to the switch so I can connect it and disconnect it quickly. I tried recording the current with the capacitor attached and here are some of the measurements I managed to get.
I just used a big electrolytic capacitor that I had and you can see the current calm down as soon I would connect it but then it would start going everywhere again. I was holding it up to the motor with my hands, so the contact is questionable and I should probably be using a different kind of a capacitor for this. This is something I will try testing out more at the end if I have enough time, though, as you can hear from the video, the sound was greatly reduced compared to the no capacitor situation.
10. Soft starting a motor
Experimenting
Let's talk about soft starting DC motors. To begin, let's take a look at the simple DC motor. When we're powering up a DC motor, we're essentially powering up a motor coil which acts as a short circuit in the transient period. In that period, there will be a huge current spike until the motor starts spinning and it will settle down again. To investigate this further, I set my lab bench power supply to the max current of 3.1A and set the voltage to 10V. Let's first take a look at what the current graph looks like for that case.
You can see that the current jumps up to 1.4A before settling down to around 530mA during normal spinning. In this case, with the components I'm using, this could be looked at as tolerable, but things can get out of hand pretty quickly if we want to try using bigger motors at higher voltages and so on. To combat this, we can soft start a DC motor. One way of soft starting the motor is through smarter software control where we would ramp up the power slowly and therefore avoid any current spikes, this is something I will be using when testing the constant current motor driver that you will see later on. Another way is making a soft starter circuit for the motor. Since the theme of this design challenge is Experimenting, I thought I would give it a try and see what I could make using some simple components.
To begin, we need a way of limiting the current, the easiest way of doing that would be by adding a resistor in series with the motor. So that's exactly what I did and here are the results.
I took some ceramic 11W resistors I had and tied them up to get 22Ohm. As you can see from the picture above, we still have a small peak, which is to be expected but instead of the peak being at 1.4A, this time it's at around 480mA, which is a great improvement. But we can't leave it at this, if you look at the current when the system calms down, you can see that it's sitting at 400mA, instead of the 530mA from last time, in other words, we're wasting a lot of energy on the resistor. Ideally, we would have the resistor connected during startup and then short circuit it so the motor could run at full power without wasting energy on the resistor.
To do this, in parallel with the resistor, I put an N-MOS (IRF560) MOSFET, so that we could power the gate on it to essentially shortcircuit the resistor.
This design and test were all conducted with having only unidirectional soft starting in mind, since having it bidirectional would require another MOSFET as well as a different way of driving the MOSFET-s (bootstrapping), since the source of the MOSFET wouldn't be connected to the ground. For this design to work, the order of connections should be, 12V, motor, soft starter, and then ground.
To drive the IRF530, I took the signal coming from the motor driver into the motor (the one switched HIGH) and filtered it with an RC filter (possible PWM), and then used a comparator to trigger an RC circuit that gradually powered on the IRF530. I tried a couple of different values for the RC timing but ended up with a 47K resistor and 100uF capacitor.
You can see from the graph that we've reduced the current peak at the start drastically to 500mA from 1.4A and how we're turning on the MOSFET after that where we have another peak that goes up to 600mA, but the current settles down to above 500mA, which is what we are expecting, much better than the 400mA we had when we had the resistor constantly connected. If we wanted to get rid of the second current peak, we can just increase the resistance to 100K and this is what we get.
Now we can see that the initial current peak stayed the same, but by turning on the MOSFET more slowly, we've reduced the size of the second peak to under 550mA, but of course, at the cost of getting more slowly to the stationary state. I am extremely happy with how it works, so it was time to make the final schematic for it and solder it to a perfboard.
Schematic & soldering
I decided to go with a 4.7Ohm resistor for the final build and replace the resistor with potentiometers so that I can easily adjust anything that I wanted. I also wanted to leave a few extra connectors so I can easily short out the resistor if I wanted to during testing. After a bit of soldering and one 3D-printed mount later, this is what I ended up with.
I managed to keep all of the wires underneath the board for a surprisingly clean look. On the left side is the connector for 12V, while on the right side we have the connector for the motor pins as well as the connector for the motor controller input, which can also just be a 12V signal. At the back, we have the 2 connectors for shorting out the power resistor for testing.
Testing
With all of that done, it's time to test out the soldered version on a motor with the MAX40080 GUI running in the background. Here are 2 videos of the test. In the first video of the test, I shorted the power resistor with a jumper wire so that the whole thing acts like there's no soft starter at all.
You can see that the current spike goes to around 1.3A. Now, let's see how the soft starter actually performs.
As you can see the peak is now under 900mA which is significantly lower than when we just shorted the resistor. This is using a 4.7Ohm resistor, but of course, by adding a bigger resistor, as shown above, we can decrease that value even more. This will conclude my investigation of soft starting a DC motor. This is something I didn't plan on doing, but it came naturally as I was experimenting with the current sensor, which I love about this kind of challenge as it is pretty open with doing such investigations that stray a bit from the original project.
11. L298N motor driver issues
Before I get into the design of my motor controller, I'll begin by talking about my initial idea for this challenge. My initial idea was to keep it simple and to use the L298N off-the-shelf motor driver for the controller, but to adjust the input to that driver based on the readings I got from the MAX40080. This is the driver in question:
It's a widely available motor driver that is also low cost and at the first look has great sounding specifications for the continuous and peak max current. But while working on this competition I constantly noticed the sheer difference in motor power when the driver is at 100% versus just connecting the motor directly. I expected some power loss, but not that much. so I measured the voltage on the motor when the driver is at 100%. It was almost 3V under the power supply voltage, and that's when the motor was free spinning.
So I went and looked around about this and turns out this is within spec for the L298N. It's a fairly old motor driver that utilizes BJT-s instead of MOSFET-s. So I thought I would see how would a simple single MOSFET driver compare to the L298N.
At full power, the MOSFET performed much better than the L298N as can be seen from the video. Instead of dropping to 9.2V, the drop was to 11.4V. I decided to do a bit more testing to see how the temperatures would compare between the 2. They both ran pretty warmly when not using full power, especially the MOSFET as it was driven by PWM. But when I went full power on both the MOSFET and the L298N things got much more different, especially if I applied load to the motor. The MOSFET functions as a short circuit with its low Rds at that point so it barely got warm, but the L298N on the other hand got pretty toasty.
I managed to get this after running it at a higher current for just a few seconds (motor under load), while the MOSFET went on and on with a higher current and got to around 70C with no heatsink. That's why I've decided to try and make a rough version of a motor controller instead of using the L298N.
12. Constant current motor driver
Now we get to designing the constant current motor driver. My main goal was to be able to switch to a geared gearbox instead of the one with rubber bands so I can transfer more torque, but looking at it now, the motors would have been safe, but the controllers on the other hand not so much. A thing I wanted to experiment with and try making was a constant current controller. The torque of a DC motor is directly proportional to the current drawn by the motor, which would mean that if we can control the current of the motor we can control the torque of the motor.
How would it work?
Let's first take a look at how a driver like this could work. As I've shown in the soft starting section above, we can limit the current of a motor by adding a resistor in series with the motor. If we could somehow adjust that resistance on the go, we could also change the current that would go through the motor. This is how things like constant current loads work, this is something I've made to help me better understand the problem and help me with testing a few weeks back.
This is an analog version of an adjustable load where we have a precision OpAmp with negative feedback from a power resistor controlling the gate voltage of a MOSFET to keep the current at a set level. The feedback we get from the resistor is essentially the current flowing through the system, and we are using the MOSFET as a variable resistor to either add resistance and lower the current, or lower resistance and boost the current. We can use the same principle for the motor driver, but instead of having a bulky energy-wasting power resistor for the feedback, we can use the MAX40080 and using a PID controller to adjust the gate voltage of the MOSFET.
This kind of MOSFET driving would of course cause a lot of heat energy at certain currents where the MOSFET would have to suck in a lot of energy to keep the current smaller at the motor, but also we would achieve our goal of torque control. On the other hand, since I'll be mostly running the rover at full motor speed for most of the time except for precise motor movements, the driver will be highly efficient at those levels, with the MOSFET Rds being in milliohms.
Electronics design
Let's now get to the electronics design. Time was running out so I had to resort to using the components I had laying around. Motor drivers usually have what's called an H bridge configuration of transistors, either MOSFET or BJT. Here is how the dual H bridge looks on the L298.
As mentioned above, the L298N uses BJT-s but this configuration can be achieved using MOSFET-s as well. While this was the approach I wanted to go with, I didn't have enough time to figure out the MOSFET driving circuitry. This is a problem with H bridges because, one of the sources won't be connected to the ground, so we need to use bootstrapping to properly drive the MOSFET-s. Youtuber GreatScott did a great video about driving MOSFET-s which I highly recommend to anyone interested more in this topic.
To avoid this, I went with a bit of a hacky route (that proved out to work pretty well!) by using 2 MOSFET-s both with sources connected to the ground and a relay for switching the power supply from one to the other MOSFET so we can get both directions working on the motor driver.
This way I had sources of both MOSFETS connected to the ground, but by activating/deactivating the relay, I could spin the motor in one direction or the other. The only thing that I had to get right was when to drive what MOSFET because if the relay is in position as shown on the picture and we try driving the top MOSFET, we will just run current through it and waste energy without driving the motor at all. To overcome all of this, I made the controller smart by using an Arduino as the brain of the controller so I can easily switch the relay and choose what relay to drive. I only had an MKR WAN1300 laying around with a built-in DAC (I had a few more where I could have used PWM with a filter, but the PWM resolution is 8bit while here I already have a 10bit DAC built-in). Here is the full schematic.
Because there is only one DAC on the Arduino I had to find a way to choose which MOSFET to drive, so I used a CD4053BE analog multiplexer which worked great. One idea I had later on which I could have easily implemented is by using one more of the multiplexers on the chip, besides choosing whether I want to drive MOSFET one or two, I could have also made the choice if I wanted to use an analog voltage from the DAC or use it in a standard mode with PWM. When I first tested this circuit (technically a previous version) it didn't drive the motor. I could measure the voltage across the motor connector pins, but the motor wouldn't spin. After troubleshooting the whole day, I came to the simple conclusion that the voltage at the gate was too low for driving the MOSFET properly. Something I wasn't used to with the IRLZ4NN. To remedy this, I added a non-inverting OpAmp stage between the multiplexer and the DAC so now I can adjust the max voltage I wanted at the gate and it turned out to work great like that.
Soldering
With the schematic done and all of the parts of the circuits tested to make sure everything works, it was time to get to soldering the board. I first found a suitable-sized perf board and heatsink for the motor controller and also 3D printed a base for it.
After a few hours of soldering and a few more chasing cold solder joints, I managed to finish the motor controller!
I love how it turned out in the end, the only thing I has to fix was the power connector on the right. The screw terminal sheered off when I was trying to tighten a wire, so I just soldered some wires to the pins that were left sticking out.
Software
The only thing left for the motor driver itself is the software. For now, it's just a simple piece of code that listens to the data coming over Serial from the Raspberry which tells it how high it should be driving the MOSFET-s.
#define RELAY_PIN 0 #define MUX_PIN 1 #define PWR_PIN A0 String inputString = ""; bool stringComplete = false; int motor_power = 0; void setup() { // put your setup code here, to run once: Serial.begin(9600); pinMode(RELAY_PIN, OUTPUT); pinMode(MUX_PIN, OUTPUT); pinMode(PWR_PIN, OUTPUT); analogWrite(PWR_PIN, 0); } void loop() { // put your main code here, to run repeatedly: if(stringComplete == false) { char c = 'a'; if(Serial.available() != 0) { c = (char)Serial.read(); inputString += c; } if(c == '\n') { stringComplete = true; } } else { motor_power = inputString.toInt(); analogWrite(PWR_PIN, motor_power); inputString = ""; stringComplete = false; Serial.println(motor_power + 1); } }
The MKR board doesn't support SerialEvent() as ordinary Arduinos do like the Nano or Uno, so I had to check every loop iteration if Serial was available and read the data from it.
13. Motor controller ROS node
The only thing left now is to make a ROS node for communicating with the motor controller. This node needs to read the current data from the /sensor/motor_current topic and then using a simple PI controller determine the value for the Arduino to use with the DAC. So we could more easily change values during the experiment, I will add a ROS service that will let us change the set current value. Here is the code for the ROS node.
Code
#!/usr/bin/env python3 from socket import timeout import rospy import serial import time # Messages from current_sense_node.msg import motor_currents # Services from motor_controller.srv import driver_msg set_current = 0 # mA current_reading = 0 # mA new_reading = False last_reading = -1 kp = 0.008 ki = 0.001 e = 0 e_sum = 0 max_val = 1023 min_val = 0 power = 0 current_threshold = 15 #mA motor_controller = serial.Serial("/dev/ttyACM0", 9600, timeout = 0.1) # Function for the subscriber def data_callback(req): global current_reading, new_reading current_reading = req.motor_current[0] new_reading = True # Function for sending the duty cycle to the motor_controller def send_command(dc): global motor_controller msg = str(dc) + '\n' motor_controller.write(msg.encode('utf-8')) # Function for the service callback def srv_callback(req): global set_current if req.command == 'cc': set_current = req.value else: return False return True # Initializing the ROS Node and subscriber rospy.init_node('motor_controller', anonymous = False) sub = rospy.Subscriber('/sensor/motor_current', motor_currents, data_callback) srv = rospy.Service('/control/motor', driver_msg, srv_callback) r = rospy.Rate(100) send_command(0) time.sleep(1) while not rospy.is_shutdown(): if new_reading == True: new_reading = False e = set_current - current_reading if abs(e) > current_threshold: e_sum += e power = e * kp + e_sum * ki if power > max_val: e_sum -= e power = max_val if power < min_val: e_sum -= e power = min_val print(power) send_command(int(power)) r.sleep()
As explained above, the code uses a simple PI controller to adjust the DAC value compared to the current that the MAX40080 is reading. Some additional features I implemented are a ramp limiter to limit how fast the values can change so we don't get any high current peaks as well as an error threshold so we don't jump around between 2 values when the controller is close to the set current, and lastly, I've implemented overflow protection for the integrator.
Service call
Here is how an example service call looks for changing the set current of the controller.
Testing the motor controller
And the last thing left to do is to test the motor controller. Here is a video of me changing the set current value of the motor through the ROS service.
I was impressed at how smooth the current seemed. It was a free-spinning motor, the only thing I added was a 10uF tantalum capacitor to the pins of the motor directly, which seemed to work wonderfully.
Here is another test video where I used a different motor, but this time, instead of just letting spin freely, I tried slowing down the motor with my finger and also stopped it a few times, because I wanted to see how the controller would react to changing conditions in which the motor was working, which is more close to how the motor would perform on the rover.
As you can see from the video, the controller functioned as expected which I am really pleased about. I know that it's a bit of a hacky solution with the relay, but I'm genuinely happy with how the controller turned out and with how it performs. This was my idea for this design from the beginning with using the rover motors. I will cover that too at the end, but before that, there is one more thing I made along the way for this design challenge.
14. Torque test stand
The last thing I've built is the torque test stand. The torque test stand (TTS for short) is a small contraption I've designed and made for working and testing small electric motors.
How it works
I've already talked about the torque of the motor is proportional to the current of the motor, so I thought I'd make a stand to measure motor torque. My idea for measuring torque was to spin a small axle with a break from an RC car on it and to measure the moment using a load cell. To explain how this works, there is a screw that can be tightened to activate the brake harder and harder. The goal of the break isn't to lock the axle, but to slip on it and cause friction. By adjusting that screw we can adjust how hard it is to spin that axle and the harder it is, the more moment will be transferred through the brake caliper onto the load cell which is measuring torque at a precise distance from the axle. In that way, we can measure the moment of the motor.
3D model
I think the image will clear up my explanation from above. In the first picture on the left, you can see the rover motor in black, while further on the right you can see the RC break with the adjustment screw. On the other aluminum extrusion, you can see a load cell attached with a small PCB next to it that's used for reading the values from that load cell.
Finished build
The construction consists of 2 aluminum extrusions and 3D printed parts. I printed everything using PLA which was more than good enough for the job. Besides that, I've used standard hardware for working with these extrusions. The only out-of-the-ordinary thing I used was the adjustment screw because it had a really fine thread, which meant I could get better accuracy when doing adjustments to the brake. Here are some pictures of what the finished version looks like.
Besides the main structure that you can see in the pictures, I printed out a couple of motor mounts and adapters for different kinds of motors that I was planning on testing but didn't have enough time to get around to.
ROS node
The Arduino code just reads the data from the load cell using the standard hx711 library and sends that data to the Serial port. The ROS node is simple as well, it listens for data on the serial bus and as new data comes along, it publishes it to a topic where we can later plot that data, put it on a live graph, or something else.
#!/usr/bin/env python3 import rospy import serial from std_msgs.msg import Float32 tt_arduino = serial.Serial("/dev/ttyUSB0", 9600) rospy.init_node('torque_test_stand', anonymous = False) pub = rospy.Publisher('/test_equipment/measured_torque', Float32, queue_size=10) r = rospy.Rate(10) print('Torque Test Stand Node Started!') while not rospy.is_shutdown(): raw_data = str(tt_arduino.readline()) extracted_data = raw_data[2:raw_data.find('\\r')] converted_data = float(extracted_data) pub.publish(converted_data) r.sleep()
Testing
Here is a short video showing how adjusting the screw we can adjust how much we're trying to break the motor.
15. Rover motor testing
And for the end, I've tried the constant current motor control in combination with the torque test stand on the rover motor. Before using the rover motor, I made a new stronger 3D-printed gearbox so I can test it. Here is the picture of the gears inside.
Unfortunately, there seems to be some kind of mechanical problem with the motor, probably being that the screw rod that I'm using as an axle is bent. I went with a screw axle because it was easier to work with, but now I see that I'll have to switch to something stronger than actually fits the bearings I'm trying to use. If you play the last or one of the next videos with sound, you will be able to hear how something oscillates at every turn. Either way, I tried playing around with it and the TTS to see how they act together. Here are 2 videos of me just trying out the setup.
While the last 2 videos didn't have an experiment in mind, there are a few things I've noticed that I need to address.
- The controller is too slow
- This is something I've done on purpose to make sure there aren't any current peaks that would throw the controller into oscillations
- Controller resolution
- This is something I can actually adjust a bit by using the potentiometer on the board and getting the max value as low as possible so I have all of the 1023 points to use for actual control. A starting offset voltage would be of great help as well
- Mechanical oscillations
- Needing to "jump-start" the motor
- One thing I noticed is when trying to start the motor under load, it is really difficult to do without saturating the controller and then having to wait for it to slow down. This could maybe be done by software where we would detect that the motor is under load on start and instead of gradually slowly raising the power filling up the integrator, having a start-up routine where we would put a burst of power into the motor and then turn on the controller to keep it at the set current.
16. Summary
This was an extremely fun design challenge for me. Because the name of the challenge itself has the word experiment I let myself try out stuff with the sensor as it came naturally instead of just focusing on the task that I've set in the beginning. It was a really fun process investigating things like the humming sound or the current during the soft starting of the motor. To summarize all that I've managed to:
- Setting up the MAX40080 to work with ROS and make a ROS node that makes the sensor integration into robotics projects easy (node supports up to 6 sensors at once)
- GUI for the MAX40080 where the user can adjust some parameters of the sensor and have a live data view of the current as the experiment goes
- Data logging and plotting of the current data
- Humming sound investigation
- Soft starting DC motors
- Constant current motor driver using the MAX40080 for feedback
- The torque tester stand for measuring the electric motor torque
While I'm extremely proud of the things that I've done, there are a couple more things that I wish I had the time to finish, like using the encoder on the rover motor to make a speed/position servo system assisted by the MAX40080, making the GUI that combines the MAX40080 with the torque tester stand and so on.
Thanks to the sponsors of this design challenge and element14 for hosting it, it was a really fun challenge where I've learned a lot through testing and experimenting with this sensor. In the comments below, I will be shortly posting links to GitHub for this project where you will be able to find all of the codes that I've used in this project, the ROS image with all of the codes as well as all of the 3D models that you've seen through the blog.
Thanks for reading the blog and following my journey with the MAX40080, I hope you liked it!
Milos
Top Comments