▶️Week 15: Interfaces and Application Programming
Project Hero
An application on a Pi4 sending commands via UART to a Pico, controlling motors via a milled breakout board:
Group Assignment
In this weeks group assignment we compared different frameworks to develop applications and interfaces for projects. One of the things that stood out to me was that every major tech company had their own framework and unique language to it, all vying to become and industry standard. And while those ones were often used in industry, the maker community moreso favoured the open-source options - and with good cause. I also wasn't even aware of tkinter which comes standard with python. Its not the best and looks a little outdated UI wise, but from what I've seen its incredibly easy to use and the convenience of having it come with python really makes me want to use it in future projects. And this one which is what we will be doing!
The Plan
We are going to control the motors of my final project through an application. Right now the motors are connected to a Pico via a breakout board we milled in week8 and the Pico is connected to the Pi 4 via UART. The Pico is set up to receive UART commands containing the desired RPM for each wheel (code will be at the bottom of the page), which the Pi 4 will send. So we will be using that existing system to create an application that sends those commands via UART. I just want to write something simple to help me debug the motors, a stop button, a slider to control the desired speed, and a button to send that speed command.
For this we will be using tkinter which is nice because it comes standard with Python and I used this tutorial to help me write much of it. Starting off importing tkinter and other libraries I needed, and set up my UART connection and defined a function that sends commands in the format Im using.
import tkinter as tk
from tkinter import ttk
import serial
import time
# Serial communication setup
ser = serial.Serial('/dev/serial0', 9600, timeout=1)
# Command sending function
def send_command(device, RL_rpm, RR_rpm, FL_rpm, FR_rpm, RLdeg, RRdeg, FLdeg, FRdeg):
command = f"{device} {RL_rpm} {RR_rpm} {FL_rpm} {FR_rpm} {RLdeg} {RRdeg} {FLdeg} {FRdeg}"
ser.write(command.encode()) # Encode the string to bytes
print(f"Sent: {command}")
And the next few steps were a lot easier than I thought they would be. I don't know why but coming into this I had inflated this process to be far more difficult than it would be. But tkinter was very intuitive to use. I started by creating the application, setting the name and resolution. I chose this small resolution for now because my screen was really low resolution.
class Application(tk.Tk):
def __init__(self):
super().__init__()
self.title("Pi Pico Controller")
self.geometry("400x200")
Then I added a button labeled "stop", and made it call a function stop_command. And then we pack it into the app and padd it 10 pixels from the last element above it. And that stop command just calls the send_command with a target RPM of 0.
self.stop_button = tk.Button(self, text="Stop", command=self.stop_command)
self.stop_button.pack(pady=10)
def stop_command(self):
send_command("m", 0, 0, 0, 0, 0, 0, 0, 0)
Then I created a slider element which al;tered a variable ranging from -200 to 200 which will be the target RPM the other button sends. I made it horizontal and packed it the same as I did the last button
self.slider_value = tk.IntVar()
# Slider
self.slider = tk.Scale(self, from_=-200, to=200, orient=tk.HORIZONTAL, variable=self.slider_value)
self.slider.pack(pady=10)
And finally I created another button to send the command, exactly the same as the other one except it would call a function which calls the send_command functions with the slider value.
# Send Button
self.send_button = tk.Button(self, text="Send Command", command=self.send_command_with_slider)
self.send_button.pack(pady=10)
def send_command_with_slider(self):
value = self.slider_value.get()
send_command("m", value, value, value, value, 0, 0, 0, 0)
And that was it! I was pleasantly suprised with how easy that was to use, I now had some buttons that were working and appeared to be sending the correct commands via UART.
However I didn't like this and so I tweaked the code a little bit to change the elements a little, I made the slider wider, the buttons a diffferent colour, and I changed the window size (final code for this at the bottom). I then had an issue that I didn't think about till now - this was running it out of thonny and I wanted it to run as a stand alone application. The tutorial didn't really work for me so I consulted chatgpt with this prompt
I have some code here for a pi 4 to send commands through a UI using tkinter, but I want it to be a stand alone application, how can I do so? I want to be able to click on an application on my desktop and run this.
*the code was then pasted here but i dont want to bloat the documentation
I started by opening terminal and creating a .desktop file with:
nano /home/pi/Desktop/pi_pico_controller.desktop
Then adding the following content to the file:
[Desktop Entry]
Name=Pi Pico Controller
Comment=Run Pi Pico Controller Script
Exec=python3 /home/pi/pi_pico_controller.py
Icon=utilities-terminal
Terminal=false
Type=Application
then you make the .desktop file executable with:
chmod +x /home/pi/Desktop/pi_pico_controller.desktop
And now I could double click it and run the program! I plugged all of my systems together and tested it. To my suprise it had no issuse and appeared to be working, and now I had an easy to use debugging tool for my project!
Final Code
Here is the python script that the application is built off:
import tkinter as tk
from tkinter import ttk
import serial
import time
# Serial communication setup
ser = serial.Serial('/dev/serial0', 9600, timeout=1)
# Command sending function
def send_command(device, RL_rpm, RR_rpm, FL_rpm, FR_rpm, RLdeg, RRdeg, FLdeg, FRdeg):
command = f"{device} {RL_rpm} {RR_rpm} {FL_rpm} {FR_rpm} {RLdeg} {RRdeg} {FLdeg} {FRdeg}"
ser.write(command.encode()) # Encode the string to bytes
print(f"Sent: {command}")
time.sleep(0.045)
# GUI application setup
class Application(tk.Tk):
def __init__(self):
super().__init__()
self.title("Pi Pico Controller")
self.geometry("400x200")
self.slider_value = tk.IntVar()
# Stop Button
self.stop_button = tk.Button(self, text="Stop", command=self.stop_command, bg="red", fg="white")
self.stop_button.pack(pady=10)
# Slider
self.slider = tk.Scale(self, from_=-200, to=200, orient=tk.HORIZONTAL, variable=self.slider_value, length=300)
self.slider.pack(pady=10)
# Send Button
self.send_button = tk.Button(self, text="Send Command", command=self.send_command_with_slider, bg="green", fg="white")
self.send_button.pack(pady=10)
def stop_command(self):
send_command("m", 0, 0, 0, 0, 0, 0, 0, 0)
def send_command_with_slider(self):
value = self.slider_value.get()
send_command("m", value, value, value, value, 0, 0, 0, 0)
if __name__ == "__main__":
app = Application()
app.mainloop()
And here is the code that we developed in the previous few weeks to control the motors via UART
from machine import Pin, PWM, Timer, UART
import time
uart = UART(1, baudrate=9600, tx=Pin(4), rx=Pin(5)) # Using UART 1 for Pico B
print("Listening for UART messages...")
# Rear Left Pins
RLENA = Pin(13, Pin.OUT)
RLIN1 = Pin(14, Pin.OUT)
RLIN2 = Pin(15, Pin.OUT)
RLencoderPinA = Pin(2, Pin.IN, Pin.PULL_UP)
RLencoderPinB = Pin(3, Pin.IN, Pin.PULL_UP)
# Rear Right Pins
RRENB = Pin(10, Pin.OUT)
RRIN3 = Pin(11, Pin.OUT)
RRIN4 = Pin(12, Pin.OUT)
RRencoderPinA = Pin(0, Pin.IN, Pin.PULL_UP)
RRencoderPinB = Pin(1, Pin.IN, Pin.PULL_UP)
# Front Left Pins
FLENA = Pin(18, Pin.OUT)
FLIN1 = Pin(17, Pin.OUT)
FLIN2 = Pin(16, Pin.OUT)
FLencoderPinA = Pin(26, Pin.IN, Pin.PULL_UP)
FLencoderPinB = Pin(22, Pin.IN, Pin.PULL_UP)
# Front Right Pins
FRENB = Pin(21, Pin.OUT)
FRIN3 = Pin(20, Pin.OUT)
FRIN4 = Pin(19, Pin.OUT)
FRencoderPinA = Pin(27, Pin.IN, Pin.PULL_UP)
FRencoderPinB = Pin(28, Pin.IN, Pin.PULL_UP)
# Encoder variables
RLencoder_position = 0
RRencoder_position = 0
FLencoder_position = 0
FRencoder_position = 0
# PID control variables
Kp = 0.3 # Reduced Kp for less aggressive control
Ki = 0.2 # Reduced Ki
Kd = 0.3 # Reduced Kd
moving_average_size = 5 # Size of the moving average window
rpm_calculation_period = 0.04
# rpm stuff
globalRPM = 30
RLsetpointRPM = 0
RLinputRPM = 0.0
RLoutputPWM = 0.0
RLprevious_error = 0.0
RLintegral = 0.0
RRsetpointRPM = 0
RRinputRPM = 0.0
RRoutputPWM = 0.0
RRprevious_error = 0.0
RRintegral = 0.0
FLsetpointRPM = 0
FLinputRPM = 0.0
FLoutputPWM = 0.0
FLprevious_error = 0.0
FLintegral = 0.0
FRsetpointRPM = 0
FRinputRPM = 0.0
FRoutputPWM = 0.0
FRprevious_error = 0.0
FRintegral = 0.0
# Constants
counts_per_revolution = 1920.0
# Moving average buffer
RLrpm_buffer = []
RRrpm_buffer = []
FLrpm_buffer = []
FRrpm_buffer = []
# PWM setup
RLpwm = PWM(RLENA)
RLpwm.freq(1000)
RRpwm = PWM(RRENB)
RRpwm.freq(1000)
FLpwm = PWM(FLENA)
FLpwm.freq(1000)
FRpwm = PWM(FRENB)
FRpwm.freq(1000)
# Interrupt handler for encoder
def RRencoder(pin):
global RRencoder_position
if RRencoderPinA.value() == RRencoderPinB.value():
RRencoder_position += 1
else:
RRencoder_position -= 1
def RLencoder(pin):
global RLencoder_position
if RLencoderPinA.value() == RLencoderPinB.value():
RLencoder_position -= 1
else:
RLencoder_position += 1
def FRencoder(pin):
global FRencoder_position
if FRencoderPinA.value() == FRencoderPinB.value():
FRencoder_position += 1
else:
FRencoder_position -= 1
def FLencoder(pin):
global FLencoder_position
if FLencoderPinA.value() == FLencoderPinB.value():
FLencoder_position -= 1
else:
FLencoder_position += 1
# Attach interrupt to encoder pins
RLencoderPinA.irq(trigger=Pin.IRQ_RISING, handler=RLencoder)
RRencoderPinA.irq(trigger=Pin.IRQ_RISING, handler=RRencoder)
FLencoderPinA.irq(trigger=Pin.IRQ_RISING, handler=FLencoder)
FRencoderPinA.irq(trigger=Pin.IRQ_RISING, handler=FRencoder)
def pid_control():
global RRprevious_error, RRintegral, RRoutputPWM
global RLprevious_error, RLintegral, RLoutputPWM
global FRprevious_error, FRintegral, FRoutputPWM
global FLprevious_error, FLintegral, FLoutputPWM
# Rear Right Motor PID
error = RRsetpointRPM - RRinputRPM
RRintegral += error
derivative = error - RRprevious_error
RRoutputPWM = Kp * error + Ki * RRintegral + Kd * derivative
RRprevious_error = error
# Rear Left Motor PID
error = RLsetpointRPM - RLinputRPM
RLintegral += error
derivative = error - RLprevious_error
RLoutputPWM = Kp * error + Ki * RLintegral + Kd * derivative
RLprevious_error = error
# Front Right Motor PID
error = FRsetpointRPM - FRinputRPM
FRintegral += error
derivative = error - FRprevious_error
FRoutputPWM = Kp * error + Ki * FRintegral + Kd * derivative
FRprevious_error = error
# Front Left Motor PID
error = FLsetpointRPM - FLinputRPM
FLintegral += error
derivative = error - FLprevious_error
FLoutputPWM = Kp * error + Ki * FLintegral + Kd * derivative
FLprevious_error = error
def set_motor_speed(RLspeed, RRspeed, FLspeed, FRspeed):
# Rear Right Motor
if RRspeed > 0:
RRIN3.value(1)
RRIN4.value(0)
elif RRspeed < 0:
RRIN3.value(0)
RRIN4.value(1)
RRspeed = -RRspeed
else:
RRIN3.value(0)
RRIN4.value(0)
# Convert speed percentage to duty cycle (0-65535)
duty_cycle = int((RRspeed / 100) * 65535)
RRpwm.duty_u16(duty_cycle)
# Rear Left Motor
if RLspeed > 0:
RLIN1.value(0)
RLIN2.value(1)
elif RLspeed < 0:
RLIN1.value(1)
RLIN2.value(0)
RLspeed = -RLspeed
else:
RLIN1.value(0)
RLIN2.value(0)
# Convert speed percentage to duty cycle (0-65535)
duty_cycle = int((RLspeed / 100) * 65535)
RLpwm.duty_u16(duty_cycle)
# Front Right Motor
if FRspeed > 0:
FRIN3.value(1)
FRIN4.value(0)
elif FRspeed < 0:
FRIN3.value(0)
FRIN4.value(1)
FRspeed = -FRspeed
else:
FRIN3.value(0)
FRIN4.value(0)
# Convert speed percentage to duty cycle (0-65535)
duty_cycle = int((FRspeed / 100) * 65535)
FRpwm.duty_u16(duty_cycle)
# Front Left Motor
if FLspeed > 0:
FLIN1.value(0)
FLIN2.value(1)
elif FLspeed < 0:
FLIN1.value(1)
FLIN2.value(0)
FLspeed = -FLspeed
else:
FLIN1.value(0)
FLIN2.value(0)
# Convert speed percentage to duty cycle (0-65535)
duty_cycle = int((FLspeed / 100) * 65535)
FLpwm.duty_u16(duty_cycle)
while True:
if uart.any():
message = uart.read().decode().strip() # remove
try:
# Split and convert message to individual RPM values
device, iRLsetpointRPM, iRRsetpointRPM, iFLsetpointRPM, iFRsetpointRPM, iRLdeg, iRRdeg, iFLdeg, iFRdeg = message.split()
if device == "m":
RLsetpointRPM = int(iRLsetpointRPM)
RRsetpointRPM = int(iRRsetpointRPM)
FLsetpointRPM = int(iFLsetpointRPM)
FRsetpointRPM = int(iFRsetpointRPM)
else:
print("not for me")
except ValueError:
print("Invalid UART message format. Expected 8 numbers.")
print(message)
RRinputRPM = (166.666 * RRencoder_position / counts_per_revolution) / rpm_calculation_period
RLinputRPM = (166.666 * RLencoder_position / counts_per_revolution) / rpm_calculation_period
FRinputRPM = (166.666 * FRencoder_position / counts_per_revolution) / rpm_calculation_period
FLinputRPM = (166.666 * FLencoder_position / counts_per_revolution) / rpm_calculation_period
print("RR", RRinputRPM, "RL", RLinputRPM, "FR", FRinputRPM, "FL", FLinputRPM)
# Reset encoder positions for the next calculation period
RRencoder_position = 0
RLencoder_position = 0
FRencoder_position = 0
FLencoder_position = 0
pid_control()
set_motor_speed(RLoutputPWM, RRoutputPWM, FLoutputPWM, FRoutputPWM)
# Small delay to prevent overwhelming the CPU
time.sleep(rpm_calculation_period)