While working on the next iteration of AvoBot I wanted to improve the accuracy of odometry and navigation in general.
Instead of using brushed motors I decided to replace them with Nema 17 stepper motors.
This way I can get an amazing precision which is way better that using PID control with brushed motors.
The downside of using stepper motors for a wheeled robot is their reduced power compared to brushed motors, but my apartment has wooden floors, so it's not a concern.
Controlling a stepper motor with A4988
The easiest way to control a stepper motor is with a motor driver like A4988.
It takes care of energizing coils and controls the current flowing through the stepper motor coils.
3 pins are usually used to control a A4988 driver:
enable
- when set tolow
power to the coils is enabled and the motor is going to keep its position (another amazing aspect of stepper motors).dir
- stepper motor directionstep
- when pulse is sent to this pin the driver will energize coils to make a step
There are also pins which control micro stepping, but unless your application calls for a variable micro stepping you can connect the pins in your desirable configuration and forget about it.
For my purposes to enable smoother movement I've configured 1/16 micro stepping. This means that normally I need 400 pulses for a full 360 degree revolution (my motor is 0.9 degree a step, 1.8 is more common). With micro stepping I get 6400 steps for a revolution.
Controlling A4988 from a Raspberry Pi Pico
I've recently switched from Arduino to a raspberry Pi Pico as the main micro controller for my robot because of its support for Micro python and 3.3v operation.
Apart from a language difference (C++ for Arduino and Python for Pico) the basic idea is the same.
There is a loop in the code which checks the power via INA219, displays info to an OLED screen (ssd1306), accepts commands via serial (speed, direction, etc.) and sends telemetry back to the host.
The way to control a normal brushed motor is to adjust a PWM signal on a pin which would control the speed of the motor. It only has to be done when the speed is changed, otherwise it's run in a hardware and doesn't affect the main loop.
Wich stepper motors the situation is different. In order to make it behave like a regular motor you need to send pulses at a certain interval so the next step can occur. With micro stepping I need 6400 steps to make a full circle. At 1000 steps a second a wheel would make a full revolution in 3.2 seconds. This is quite slow, but it already means that I need to send pulses at 1ms interval. Increasing speed means that the interval will become even shorter.
Approach 1. Timer interrupt
I found an existing project which used a timer interrupt to control stepper motors nemastepper.py
The idea is that the speed is configured for a stepper motor and a timer interrupt is calling a do_step
method every 100us. Then do_step
decides whether to actually perform a step or not depending on the configured speed.
This allows for a stable stepper motor signal on a regular interval in depended of whatever else is going on in the main loop. It can have a sleep(1000)
and the motor will still be moving.
This approach looked like it worked for a while before I started talking to I2C and a serial port.
Turns out that even though the timer interrupt is hardware-based it's still competing with the other tasks that need to be scheduled in Micro python.
So if there is other interrupt-related code running like I2C or UART there will be noticeable hiccups in the motor operation.
It is my understanding that this wouldn't happen if the code was in C++, but I liked the ease of iterating in Micro python and didn't want to go back.
Approach 2. Second core
One of the many cool things about Raspberry Pi Pico is that it actually has 2 cores, so I thought that instead of using a timer I would just run a simple loop on the second core, like this:
def steppers_thread(m1, m2):
while True:
m1.do_step()
m2.do_step()
utime.sleep_us(100)
_thread.start_new_thread(steppers_thread, (m1, m2))
This would replicate the timer interrupt loop and avoid the hiccups since it's running on a second core which is free.
This had the exact same result as the previous approach. Not exactly sure why it's happening, but I have a feeling that interrupt-related code might be "stop-the-world" thing in Micro python so all threads are paused when doing I2C or UART.
Approach 3. PIO
When I first got Pico PIO was something that I dismissed with "Sounds cool, but I'm probably not going to use it" attitude.
After exhausting other approaches I had a choice to either switch back to C++ or try to control my motors with PIO.
PIO
PIO or Programmable IO is an extremely cool concept which allows extending Pico functionality way beyond what it has coming out from the factory.
Normally, when there is no dedicated hardware interface like UART, I2C, SPI implemented on a board or there is just not enough of it left it's possible to implement such an interface in software via bit banging. There are libraries for Arduino like SoftwareSerial, Software SPI, etc.
This comes at a cost of reliability and CPU consumption.
PIO allows you to write your own programs which will implement desired protocols and will be executed ona dedicated hardware, so CPU is not involved at all. Not enough UARTs? Just run additional ones on PIO. No VGA support? You can implement one in PIO.
Stepper motors control program
After a lot of research and asking questions on Micro python forum this is what I came up with:
from machine import Pin
import rp2
@rp2.asm_pio(set_init=rp2.PIO.OUT_LOW)
def stepper():
pull(noblock) # pull the latest data into osr or put current x into osr if queue is empty
mov(x, osr) # copy osr into x
mov(y, x) # copy x into y to reset later
jmp(not_x, "end") # if x is empty skip the step
set(pins, 1) [1] # enable pin, A4988 needs 2us pulse, so wait additional 1us here
set(pins, 0) # end the pulse
irq(0) # invoke interrupt
label("delay")
jmp(x_dec, "delay") # loop and decrement x until it's 0
label("end")
mov(x, y) # restore x, which is 0 at this point
# regular nema stepper has 200 steps per revolution, with 32 microstepping mode it's 6400 steps per revolution
class Stepper:
def __init__(self, id, dir_pin, step_pin, step_callback = None):
self.dir_pin = Pin(dir_pin, Pin.OUT)
# at 1_000_000Hz clock a single instruction is 1us
self._sm = rp2.StateMachine(id, stepper, freq=1_000_000, set_base=Pin(step_pin, Pin.OUT))
if step_callback is not None:
self._sm.irq(step_callback)
self._sm.put(0)
self._sm.active(1)
def set_steps_per_second(self, steps_per_second):
if steps_per_second == 0:
self._sm.put(0)
return
if steps_per_second > 0:
self.dir_pin.high()
elif steps_per_second < 0:
self.dir_pin.low()
delay = abs(round(1_000_000 / steps_per_second)) - 10 # there are 10 instructions in the program for each step
self._sm.put(delay)
PIO program is written in an assembly-like language with a limited set of operations, but after getting used to it's possible to express a lot of logic there.
The application is executed in a loop continuously and will get a new delay setting on each iteration, send the pulse to A4988, wait the desired delay and do the next loop iteration.
freq
parameter to a state machine specifies at which frequency the program is running. 1000000Hz means that each step will take exactly 1us, 100000Hz means each step is 10us and so on.
Keeping that in mind we can calculate the length of a loop delay minus the rest of the commands which also take 1us each, so we have to subtract 10 from the calculated value.
irq(0)
allows to attach an interrupt on each step in which you can keep a track of the number of steps made if needed.
With this approach all I have to do is to create a stepper instance:
m1 = Stepper(0, 18, 19)
m2 = Stepper(1, 20, 21)
and set the speed when needed:
m1.set_steps_per_second(2000)
It's going to run independent of CPU or anything else running on Pico, because it's running truly in a dedicated hardware.