We have previously looked at bringing up the Adiuvo Tile Carrier Card which uses the RPI5 Compute module. Along with the RPI5 Compute Module the carrier is designed to accommodate the Adiuvo Tile.
The previous project we walked through setting up the RPI5 Compute Module which is the first time I had set out to do that.
There is still a lot of work to do on the bring up especially in relation to verifying the FPGA Tile and support capabilities on the carrier card for the tile.
Things we want to check are
- Tile fit and initial power up - The smoke test does it fit and can we work with it, if not then we will find out pretty quickly as the magic smoke escapes.
- PMOD interfaces - Can the FPGA communicate with the Pmod interfaces correctly
- RPI5 CM - FPGA interface - Can we communicate between the RPI5 CM and the FPGA.
- FTDI IO - The IO connected to the FTDI FT4232H
- Programmable Clock - The programmable clock generator on the carrier for the FPGA.
For this project I am going to look at creating an application which will test out the Tile Fit, Pmod and RPI5 CM interface.
I want to do this as I have an idea for the project I would like to develop on this board.
ApproachThis design will therefore use the RPI5 to communicate with the FPGA tile, to do this initially a UART protocol will be used. We have used this protocol before in a Hackster project.
This protocol enables a sequence of bytes sent over the UART to trigger either a AXI Lite read or write depending upon the sequence sent.
As I want to eventually work on a Robotic Arm project which requires PWM to drive the robotic servos, we will focus on the Pmods in this project.
Why would we not just use the RPI5 CM ? The RPI5 CM can only implement four hardware PWM outputs, the robot arm needs at least six. While the RPI5 CM can generate SW PWM this is not well suited for robotics as it suffers from jitter. This is a perfect application for our first application of the FPGA Tile.
As such this application will use the following IP from the Adiuvo repository
- UART AXIS - A UART which has AXIS interfaces for Tx and RX
- Protocol - The protocol convertor which receives the UART Bytes and actions the AXI Lite read or write.
- AXI Registers - A collection of AXI addressable registers which can also be accessed discretely for read and write.
- PWM IP - A PWM output block we will need 6 of these one for each joint eventually.
The RPI5 CM GPIO allocations are shown below.
For this application I want to ensure we can communicate from the RPI5 to the FPGA using the UART, and drive the Pmod with a PWM.
To provide the Pmod are working correctly with the FPGA tile, I will use a simple Pmod LED the intensity of the LED can then be changed under control of the RPI5 CM.
With this all working we can then focus next time on the robotic application having reduced the risk on the underlying hardware.
RTL DesignThe RTL design is uses the modules identified above, at Adiuvo we have quite a large range of IP cores. For this application I quickly pulled together the files graphically using HDL Designer. The source code is available in the git repo.
UART and Protocol Module
AXI Register and Register Decoding
The final element is a simple LED toggling module, which toggles the two LEDs on the tile itself.
Of course before we can test this on the hardware we need to be ensure the design works as expected.
I created a simple test bench which uses a UART BFM to send in commands to the UART and ensure the PWM registers were updated over the net work.
The simulation was run using the Questa Base Simulator. You can see in the image below the PWM registers being updated over the AXI network. These registers are the final part of the communication chain.
This project is targeting a Lattice Certus NX device on the Galaxia Space Tile as such we need to use Lattice Radiant to create the implementation files.
The first step is to create a project with the RTL files added and named correctly for the library which contains them. The project is available in the git repo and the Certus NX is covered by the Radiant free licensing.
The connections to the RPI5 CM and the Pmod are allocated in the PDC file, we can also define the clock constraints here as well. We will be making use of the 100MHz clock which is on the tile.
ldc_set_location -site {F16} [get_ports clk]
ldc_set_location -site {E15} [get_ports LED0]
ldc_set_location -site {E16} [get_ports LED1]
ldc_set_location -site {G16} [get_ports reset]
ldc_set_location -site {G10} [get_ports rx]
ldc_set_location -site {G9} [get_ports tx]
ldc_set_location -site {K6} [get_ports pwm_op]
ldc_set_location -site {K4} [get_ports pwm_op1]
ldc_set_location -site {K1} [get_ports pwm_op2]
ldc_set_location -site {J1} [get_ports pwm_op3]
ldc_set_location -site {L3} [get_ports pwm_op4]
ldc_set_location -site {L5} [get_ports pwm_op5]
create_clock -name {clk} -period 10 -add [get_ports clk]
The design is pretty small so it will only take a few minutes to implement.
Once the programming file is available, using JTAG we are able to download the programming file to the device.
Now we need to get the RPI5 CM configured correctly for development.
RPI5 CM ConfigThe next step is to make sure the UARTs on the RPI5 CM are enabled. The first thing we will do is install VS Code on the RPI5 CM as we will need to edit some files.
We can do this by using the command
sudo apt install code.
This will take a few minutes but after that we will have VS Code on the RPI5 which means we can also use the RPI5 CM for development if we wish.
To enable the UARTs on the RPI we need to set the configuration correctly using the configuration page. This is available under the preferences menu option, make sure the SSH option is also enabled as we will be using that also.
Along with enabling the UARTs in the configuration we also need to update the firmware configuration, this file lives at /boot/firmware/config, txt
Use VS Code to open the file and add in the commands, you will need to save using sudo.
enable_uart=1
dtoverlay=uart2
Save the file and reboot the RPI5 CM for the changes to make effect.
We are now in a position we can develop the RPI5 CM application, to do this we will use VS code.
However, instead of using VS Code on the RPI5 CM as just installed, we will use VS Code on the host machine and configure VS Code for remote SSH development.
To do this we open VS Code on the host machine, and if not installed select the extensions manager and add in the remote development extension.
With the extension installed we can remotely connect into the RPI5 CM and develop the application. You need to know the IP address of the RPI5 CM and I did this on the same local network not remotely.
The application is simple, it will create a pulsing (breathing) PWM pattern on the LEDs along with providing us with a simple write capability to any desired PWM register. This direct write capability is something we can build upon when we want to work on the robotics project.
#!/usr/bin/env python3
"""
fpga_uart_pwm_combo.py — Combined UART tool for Raspberry Pi 5 Compute Module to talk to an FPGA.
What this version does:
- Serial: 115200 baud, 8 data bits, **No parity**, **2 stop bits** (8N2).
- **GPIO2 reset**: holds BCM GPIO 2 LOW for ~100 µs on startup, then drives HIGH for program lifetime.
- **Per-byte gap**: enforces ~100 µs idle **between every UART byte** (default; change with --inter-us).
Example on the wire: 0x09, 100 µs gap, Addr3, 100 µs, Addr2, 100 µs, Addr1, 100 µs, Addr0, 100 µs, 0x01, 100 µs, Data3, ...
Protocol (single WRITE frame, big-endian):
[0x09][Addr3][Addr2][Addr1][Addr0][0x01][Data3][Data2][Data1][Data0]
Usage (global flags go BEFORE the subcommand):
# Single write with 100 µs inter-byte gap
python3 fpga_uart_pwm_combo.py --port /dev/ttyAMA2 --inter-us 100 write --addr 0x0 --data 0x12345678
# Breathe demo across 6 registers (base, base+4, ... base+0x14)
python3 fpga_uart_pwm_combo.py --port /dev/ttyAMA2 --inter-us 100 breathe --base-addr 0x0 --mode all --steps 512 --step-delay 0.01
"""
import argparse
import sys
import time
from typing import List, Optional
try:
import serial # pyserial
except ImportError:
print("Error: This script requires the 'pyserial' package. Install with:\n pip3 install pyserial", file=sys.stderr)
sys.exit(1)
# ---------------------------- Protocol constants ----------------------------
WRITE_OPCODE = 0x09
FIXED_LENGTH = 0x01 # one 32-bit word
PWM_BITS = 21
PWM_MASK = (1 << PWM_BITS) - 1 # 0x1F_FFFF
# ------------------------------- GPIO control --------------------------------
_gpio2_handle = None # keep reference to hold line for program lifetime
def init_gpio2_with_pulse(verbose: bool = False, pulse_low_us: int = 100) -> None:
"""
Request BCM GPIO 2 as output, drive LOW for ~pulse_low_us microseconds (default 100 µs), then HIGH.
Keeps a handle alive for program lifetime so the line stays driven.
"""
global _gpio2_handle
# Try libgpiod v2
try:
import gpiod # type: ignore
if hasattr(gpiod, 'request_lines'): # v2 API
req = gpiod.request_lines(
"/dev/gpiochip0",
consumer="fpga_combo",
config={2: gpiod.LineSettings(direction=gpiod.LineDirection.OUTPUT,
output_value=0)}
)
time.sleep(max(pulse_low_us, 0) / 1_000_000.0) # LOW pulse
req.set_values({2: 1}) # HIGH
_gpio2_handle = req
if verbose:
print(f"GPIO2 pulsed LOW for ~{pulse_low_us} us, now HIGH (libgpiod v2)")
return
except Exception:
pass
# Try libgpiod v1
try:
import gpiod # type: ignore
chip = gpiod.Chip('gpiochip0')
line = chip.get_line(2)
line.request(consumer='fpga_combo', type=gpiod.LINE_REQ_DIR_OUT, default_vals=[0])
time.sleep(max(pulse_low_us, 0) / 1_000_000.0)
line.set_value(1)
_gpio2_handle = (chip, line)
if verbose:
print(f"GPIO2 pulsed LOW for ~{pulse_low_us} us, now HIGH (libgpiod v1)")
return
except Exception:
pass
# Try RPi.GPIO
try:
import RPi.GPIO as GPIO # type: ignore
GPIO.setmode(GPIO.BCM)
GPIO.setwarnings(False)
GPIO.setup(2, GPIO.OUT, initial=GPIO.LOW)
time.sleep(max(pulse_low_us, 0) / 1_000_000.0)
GPIO.output(2, GPIO.HIGH)
_gpio2_handle = GPIO
if verbose:
print(f"GPIO2 pulsed LOW for ~{pulse_low_us} us, now HIGH (RPi.GPIO)")
return
except Exception:
pass
# Try gpiozero
try:
from gpiozero import LED # type: ignore
led = LED(2, active_high=True, initial_value=False)
time.sleep(max(pulse_low_us, 0) / 1_000_000.0)
led.on()
_gpio2_handle = led
if verbose:
print(f"GPIO2 pulsed LOW for ~{pulse_low_us} us, now HIGH (gpiozero)")
return
except Exception:
pass
print("Warning: Could not control GPIO2 (no suitable GPIO library found)", file=sys.stderr)
# ------------------------------- Serial helpers ------------------------------
def open_serial(port: str, baud: int = 115200, timeout: float = 1.0) -> "serial.Serial":
"""Open a serial port with 115200-8N2 (no parity, two stop bits)."""
return serial.Serial(
port=port,
baudrate=baud,
bytesize=serial.EIGHTBITS,
parity=serial.PARITY_NONE, # No parity
stopbits=serial.STOPBITS_TWO, # 2 stop bits
timeout=timeout,
write_timeout=timeout,
rtscts=False,
dsrdtr=False,
xonxoff=False,
)
def hexdump(b: bytes) -> str:
return " ".join(f"{x:02X}" for x in b)
# ------------------------ Low-level transmit with gaps -----------------------
def _bits_per_byte(parity, stopbits) -> float:
"""Compute serial bits per 'byte' on the wire given parity/stop config."""
p = 0 if parity == serial.PARITY_NONE else 1
if stopbits == serial.STOPBITS_ONE:
s = 1
elif stopbits == serial.STOPBITS_TWO:
s = 2
else: # HANDLE 1.5 as 2 for timing safety
s = 2
return 1 + 8 + p + s # start + data + parity + stop
def send_bytes_with_interbyte_gap(ser: "serial.Serial", data: bytes, inter_gap_sec: float) -> None:
"""
Send 'data' one byte at a time, inserting an idle gap AFTER EACH BYTE except the last.
Gap timing is approximated in userspace; for strict timing, use hardware support.
"""
if not data:
return
byte_time = _bits_per_byte(ser.parity, ser.stopbits) / float(ser.baudrate)
gap = max(inter_gap_sec, 0.0)
# To create an *idle* period on the line, wait for the time it takes to clock the byte,
# plus the desired idle gap before issuing the next byte.
# This reduces the chance that the next byte queues immediately with no idle time.
per_byte_wait = byte_time + gap
for i, b in enumerate(data):
ser.write(bytes((b,)))
if i != len(data) - 1:
time.sleep(per_byte_wait)
ser.flush()
# ------------------------------ Frame builders -------------------------------
def build_write_frame(address: int, data: int) -> bytes:
"""
Build the WRITE frame:
[0x09][Addr3][Addr2][Addr1][Addr0][0x01][Data3][Data2][Data1][Data0]
Address and data are 32-bit unsigned (big-endian).
"""
if not (0 <= address <= 0xFFFFFFFF):
raise ValueError("address must be 0..0xFFFFFFFF")
if not (0 <= data <= 0xFFFFFFFF):
raise ValueError("data must be 0..0xFFFFFFFF")
return bytes([WRITE_OPCODE]) + \
address.to_bytes(4, "big") + \
bytes([FIXED_LENGTH]) + \
data.to_bytes(4, "big")
# ----------------------------- Register writers ------------------------------
def write_reg(ser: "serial.Serial", address: int, value_21bit: int, shift: int,
inter_gap_sec: float) -> None:
"""Write a masked 21-bit value (optionally shifted) into a 32-bit register, gapped between BYTES."""
value = (int(value_21bit) & PWM_MASK) << shift
frame = build_write_frame(address, value)
send_bytes_with_interbyte_gap(ser, frame, inter_gap_sec)
# ------------------------------ Command actions ------------------------------
def do_write(port: str, baud: int, address: int, data: int, quiet: bool, no_gpio: bool,
inter_gap_sec: float) -> int:
if not no_gpio:
init_gpio2_with_pulse(verbose=not quiet) # default 100 µs LOW
frame = build_write_frame(address, data)
try:
with open_serial(port=port, baud=baud) as ser:
try:
ser.reset_input_buffer()
ser.reset_output_buffer()
except Exception:
pass
send_bytes_with_interbyte_gap(ser, frame, inter_gap_sec)
if not quiet:
print(f"TX ({len(frame)} bytes): {hexdump(frame)}")
return 0
except serial.SerialException as e:
print(f"Serial error: {e}", file=sys.stderr)
return 1
def gen_addresses(base_addr: int, count: int = 6, stride: int = 4) -> List[int]:
return [base_addr + i * stride for i in range(count)]
def norm_to_21bit(norm: float, gamma: float = 1.0) -> int:
"""Map 0.0..1.0 to a 21-bit integer with optional gamma correction."""
n = min(max(norm, 0.0), 1.0)
if gamma != 1.0:
n = n ** gamma
return int(round(n * PWM_MASK))
def breathe_sequence(ser: "serial.Serial", addrs: List[int], step_delay: float, steps: int,
hold: float, gamma: float, mode: str, shift: int, inter_gap_sec: float) -> None:
"""Continuously breathe up and down. Ctrl+C to stop."""
def ramp_channel(addr_list: List[int]):
# Up
for s in range(steps + 1):
n = s / steps
v = norm_to_21bit(n, gamma)
for a in addr_list:
write_reg(ser, a, v, shift, inter_gap_sec)
ser.flush()
time.sleep(step_delay)
if hold > 0:
time.sleep(hold)
# Down
for s in range(steps, -1, -1):
n = s / steps
v = norm_to_21bit(n, gamma)
for a in addr_list:
write_reg(ser, a, v, shift, inter_gap_sec)
ser.flush()
time.sleep(step_delay)
if hold > 0:
time.sleep(hold)
if mode == "all":
while True:
ramp_channel(addrs)
elif mode == "chase":
while True:
for a in addrs:
# Clear others
for other in addrs:
if other != a:
write_reg(ser, other, 0, shift, inter_gap_sec)
ser.flush()
ramp_channel([a])
else:
raise ValueError("mode must be 'all' or 'chase'")
def do_breathe(port: str, baud: int, base_addr: int, count: int, stride: int, shift: int,
steps: int, step_delay: float, hold: float, gamma: float, mode: str, no_gpio: bool,
inter_gap_sec: float) -> int:
if not no_gpio:
init_gpio2_with_pulse(verbose=True) # default 100 µs LOW
addrs = gen_addresses(base_addr, count, stride)
try:
with open_serial(port, baud) as ser:
# Clear outputs initially
for a in addrs:
write_reg(ser, a, 0, shift, inter_gap_sec)
ser.flush()
print("Breathing... Press Ctrl+C to stop.")
breathe_sequence(ser, addrs, step_delay, steps, hold, gamma, mode, shift, inter_gap_sec)
return 0
except KeyboardInterrupt:
print("\nStopping, setting all channels to 0.")
try:
with open_serial(port, baud) as ser:
for a in gen_addresses(base_addr, count, stride):
write_reg(ser, a, 0, shift, inter_gap_sec)
ser.flush()
except Exception:
pass
return 0
except serial.SerialException as e:
print(f"Serial error: {e}", file=sys.stderr)
return 1
except Exception as e:
print(f"Error: {e}", file=sys.stderr)
return 1
# --------------------------------- CLI ---------------------------------------
def build_cli(argv: Optional[list[str]] = None) -> argparse.Namespace:
p = argparse.ArgumentParser(
description="Combined UART tool for FPGA (115200-8N2). Provides 'write' and 'breathe' commands, with per-byte gaps."
)
p.add_argument("--port", default="/dev/ttyAMA2", help="Serial device path (default: /dev/ttyAMA2)")
p.add_argument("--baud", type=int, default=115200, help="Baud rate (default: 115200)")
p.add_argument("--inter-us", type=float, default=100.0,
help="Idle time between UART BYTES, in microseconds (default: 100).")
p.add_argument("--no-gpio", action="store_true", help="Do NOT touch BCM GPIO 2 (default: 100 µs LOW then HIGH)")
sub = p.add_subparsers(dest="cmd", required=True)
# write
pw = sub.add_parser("write", help="Send one WRITE frame to address/data")
pw.add_argument("--addr", "--address", dest="address", type=lambda x: int(x, 0), required=True,
help="32-bit address (e.g., 0x12345678)")
pw.add_argument("--data", dest="data", type=lambda x: int(x, 0), required=True,
help="32-bit data word (e.g., 0x9ABCDEF0)")
pw.add_argument("--quiet", action="store_true", help="Suppress hexdump output")
# breathe
pb = sub.add_parser("breathe", help="Run 21-bit PWM breathe across N registers")
pb.add_argument("--base-addr", type=lambda x: int(x, 0), default=0x0, help="Base register address (default: 0x0)")
pb.add_argument("--count", type=int, default=6, help="Number of registers (default: 6)")
pb.add_argument("--stride", type=lambda x: int(x, 0), default=0x4, help="Address stride (default: 0x4)")
pb.add_argument("--shift", type=int, default=0, help="Bit position of PWM field within 32-bit word (default: 0)")
pb.add_argument("--steps", type=int, default=512, help="Steps per half-cycle (default: 512)")
pb.add_argument("--step-delay", type=float, default=0.01, help="Seconds to wait between steps (default: 0.01)")
pb.add_argument("--hold", type=float, default=0.0, help="Hold time at min/max (seconds, default: 0)")
pb.add_argument("--gamma", type=float, default=1.8, help="Perceptual gamma (default: 1.8)")
pb.add_argument("--mode", choices=["all", "chase"], default="all",
help="Breathe all channels together or one at a time (default: all)")
return p.parse_args(argv)
def main(argv: Optional[list[str]] = None) -> int:
args = build_cli(argv)
inter_gap_sec = max(args.inter_us, 0.0) / 1_000_000.0 # µs -> seconds
if args.cmd == "write":
return do_write(args.port, args.baud, args.address, args.data, args.quiet, args.no_gpio, inter_gap_sec)
elif args.cmd == "breathe":
return do_breathe(args.port, args.baud, args.base_addr, args.count, args.stride,
args.shift, args.steps, args.step_delay, args.hold, args.gamma,
args.mode, args.no_gpio, inter_gap_sec)
else:
print("Unknown command", file=sys.stderr)
return 2
if __name__ == "__main__":
sys.exit(main())
helpfully we can run this script also remotely using the terminal inbuilt to VS code.
Running the application we should see several things, the first is the reset pulse on GPIO 2 from the RPI5 CM to the FPGA to reset the FPGA at start up.
Following the reset the write sequence should begin, we can observe this using a scope and decode the commands as they are sent if the scope is capable. You can see below the write sequences necessary for updating all six PWM registers.
Running on the hardware we will see the lights come on, across four LEDs on one Pmod and two LEDs on a the other. This is because the robot control signals are connected in reality via PmodCon3 which supports four PWM interfaces.
A slight oddity is I thought I had mapped four pins to Pmod1 and two to Pmod2 but I will need to investigate this further.
This project has shown the FPGA tile working on the Adiuvo Tile Carrier Card, communicating with the RPI5 CM and the Pmods.
With this underlaying hardware element check out I am able to progress and look at a more in depth application which can be demonstrated in a future project.
Comments