Introduce Rust FSBL
Some checks failed
ci / Check build (pull_request) Has been cancelled
ci / Check formatting (pull_request) Has been cancelled
ci / Check Documentation Build (pull_request) Has been cancelled
ci / Clippy (pull_request) Has been cancelled
ci / Check build (push) Has been cancelled
ci / Check formatting (push) Has been cancelled
ci / Check Documentation Build (push) Has been cancelled
ci / Clippy (push) Has been cancelled

This PR introduces some major features while also changing the project structure to be more flexible
for multiple platforms (e.g. host tooling). It also includes a lot of
bugfixes, renamings for consistency purposes and dependency updates.

Added features:

1. Pure Rust FSBL for the Zedboard. This first variant is simplistic. It
   is currently only capable of QSPI boot. It searches for a bitstream
   and ELF file inside the boot binary, flashes them and jumps to them.
2. QSPI flasher for the Zedboard.
3. DDR, QSPI, DEVC, private CPU timer and PLL configuration modules
3. Tooling to auto-generate board specific DDR and DDRIOB config
   parameters from the vendor provided ps7init.tcl file

Changed project structure:

1. All target specific project are inside a dedicated workspace inside
   the `zynq` folder now.
2. All tool intended to be run on a host are inside a `tools` workspace
3. All other common projects are at the project root

Major bugfixes:

1. SPI module: CPOL was not configured properly
2. Logger flush implementation was empty, implemented properly now.
This commit is contained in:
2025-08-01 14:32:08 +02:00
committed by Robin Mueller
parent 0cf5bf6885
commit 5d0f2837d1
166 changed files with 9496 additions and 979 deletions

View File

@@ -0,0 +1,526 @@
//! Zedboard ethernet example code.
//!
//! This code uses embassy-net, a smoltcp based networking stack, as the IP stack.
//! It uses DHCP by default to assign the IP address. The assigned address will be displayed on
//! the console.
//!
//! Alternatively, you can also set a static IPv4 configuration via the `STATIC_IPV4_CONFIG`
//! constant and by setting `USE_DHCP` to `false`.
//!
//! It also exposes simple UDP and TCP echo servers. You can use the following sample commands
//! to send UDP or TCP data to the Zedboard using the Unix `netcat` application:
//!
//! ## UDP
//!
//! ```sh
//! echo "Hello Zedboard" | nc -uN <ip-address> 8000
//! ```
//!
//! ## TCP
//!
//! ```sh
//! echo "Hello Zedboard" | nc -N <ip-address> 8000
//! ```
#![no_std]
#![no_main]
use core::{net::Ipv4Addr, panic::PanicInfo};
use cortex_ar::asm::nop;
use embassy_executor::Spawner;
use embassy_net::{Ipv4Cidr, StaticConfigV4, tcp::TcpSocket, udp::UdpSocket};
use embassy_time::{Duration, Timer};
use embedded_io::Write;
use embedded_io_async::Write as _;
use log::{LevelFilter, debug, error, info, warn};
use rand::{RngCore, SeedableRng};
use zedboard::PS_CLOCK_FREQUENCY;
use zedboard_bsp::phy_marvell;
use zynq7000_hal::{
BootMode,
clocks::Clocks,
configure_level_shifter,
eth::{
AlignedBuffer, ClockDivSet, EthernetConfig, EthernetLowLevel, embassy_net::InterruptResult,
},
gic::{GicConfigurator, GicInterruptHelper, Interrupt},
gpio::{GpioPins, Output, PinState},
gtc::GlobalTimerCounter,
l2_cache,
uart::{ClockConfig, Config, Uart},
};
use zynq7000::{Peripherals, slcr::LevelShifterConfig};
use zynq7000_rt::{self as _, mmu::section_attrs::SHAREABLE_DEVICE, mmu_l1_table_mut};
const USE_DHCP: bool = true;
const UDP_AND_TCP_PORT: u16 = 8000;
const PRINT_PACKET_STATS: bool = false;
const LOG_LEVEL: LevelFilter = LevelFilter::Info;
const NUM_RX_SLOTS: usize = 16;
const NUM_TX_SLOTS: usize = 16;
const STATIC_IPV4_CONFIG: StaticConfigV4 = StaticConfigV4 {
address: Ipv4Cidr::new(Ipv4Addr::new(192, 168, 179, 25), 24),
gateway: None,
dns_servers: heapless::Vec::new(),
};
const INIT_STRING: &str = "-- Zynq 7000 Zedboard Ethernet Example --\n\r";
// Unicast address with OUI of the Marvell 88E1518 PHY.
const MAC_ADDRESS: [u8; 6] = [
0x00,
((phy_marvell::MARVELL_88E1518_OUI >> 8) & 0xff) as u8,
(phy_marvell::MARVELL_88E1518_OUI & 0xff) as u8,
0x00,
0x00,
0x01,
];
/// See memory.x file. 1 MB starting at this address will be configured as uncached memory using the
/// MMU.
const UNCACHED_ADDR: u32 = 0x4000000;
// These descriptors must be placed in uncached memory. The MMU will be used to configure the
// .uncached memory segment as device memory.
#[unsafe(link_section = ".uncached")]
static RX_DESCRIPTORS: zynq7000_hal::eth::rx_descr::DescriptorList<NUM_RX_SLOTS> =
zynq7000_hal::eth::rx_descr::DescriptorList::new();
#[unsafe(link_section = ".uncached")]
static TX_DESCRIPTORS: zynq7000_hal::eth::tx_descr::DescriptorList<NUM_TX_SLOTS> =
zynq7000_hal::eth::tx_descr::DescriptorList::new();
static ETH_ERR_QUEUE: embassy_sync::channel::Channel<
embassy_sync::blocking_mutex::raw::CriticalSectionRawMutex,
InterruptResult,
8,
> = embassy_sync::channel::Channel::new();
#[derive(Debug, PartialEq, Eq)]
pub enum IpMode {
LinkDown,
AutoNegotiating,
AwaitingIpConfig,
StackReady,
}
/// Entry point (not called like a normal main function)
#[unsafe(no_mangle)]
pub extern "C" fn boot_core(cpu_id: u32) -> ! {
if cpu_id != 0 {
panic!("unexpected CPU ID {}", cpu_id);
}
main();
}
#[embassy_executor::task]
async fn embassy_net_task(
mut runner: embassy_net::Runner<'static, zynq7000_hal::eth::embassy_net::Driver>,
) -> ! {
runner.run().await
}
/// Simple UDP echo task.
#[embassy_executor::task]
async fn udp_task(mut udp: UdpSocket<'static>) -> ! {
let mut rx_buf = [0; zynq7000_hal::eth::MTU];
udp.bind(UDP_AND_TCP_PORT)
.expect("failed to bind UDP socket to port 8000");
loop {
match udp.recv_from(&mut rx_buf).await {
Ok((data, meta)) => {
log::info!("udp rx {data} bytes from {meta:?}");
match udp.send_to(&rx_buf[0..data], meta).await {
Ok(_) => (),
Err(e) => {
log::warn!("udp send error: {e:?}");
Timer::after_millis(100).await;
}
}
}
Err(e) => {
log::warn!("udp receive error: {e:?}");
Timer::after_millis(100).await;
}
}
}
}
/// Simple TCP echo task.
#[embassy_executor::task]
async fn tcp_task(mut tcp: TcpSocket<'static>) -> ! {
let mut rx_buf = [0; zynq7000_hal::eth::MTU];
tcp.set_timeout(Some(Duration::from_secs(2)));
loop {
match tcp.accept(UDP_AND_TCP_PORT).await {
Ok(_) => {
log::info!("tcp connection to {:?} accepted", tcp.remote_endpoint());
loop {
if tcp.may_recv() {
match tcp.read(&mut rx_buf).await {
Ok(0) => {
log::info!("tcp EOF received");
tcp.close();
}
Ok(read_bytes) => {
log::info!("tcp rx {read_bytes} bytes");
if tcp.may_send() {
match tcp.write_all(&rx_buf[0..read_bytes]).await {
Ok(_) => continue,
Err(e) => {
log::warn!("tcp error when writing: {e:?}");
Timer::after_millis(100).await;
}
}
} else {
log::warn!("tcp remote endpoint not writeable");
continue;
}
}
Err(_) => {
log::warn!("tcp connection reset by remote endpoint.");
tcp.close();
}
}
}
if !tcp.may_send() && !tcp.may_recv() {
log::info!("tcp send and receive side closed");
tcp.close();
}
if tcp.state() == embassy_net::tcp::State::Closed {
log::info!("tcp socket closed, exiting loop");
break;
}
Timer::after_millis(100).await;
}
}
Err(e) => {
log::warn!("tcp error accepting connection: {e:?}");
Timer::after_millis(100).await;
continue;
}
}
}
}
#[embassy_executor::main]
#[unsafe(export_name = "main")]
async fn main(spawner: Spawner) -> ! {
let mut dp = Peripherals::take().unwrap();
l2_cache::init_with_defaults(&mut dp.l2c);
// Enable PS-PL level shifters.
configure_level_shifter(LevelShifterConfig::EnableAll);
// Configure the uncached memory region using the MMU.
mmu_l1_table_mut()
.update(UNCACHED_ADDR, SHAREABLE_DEVICE)
.expect("configuring uncached memory section failed");
// Clock was already initialized by PS7 Init TCL script or FSBL, we just read it.
let clocks = Clocks::new_from_regs(PS_CLOCK_FREQUENCY).unwrap();
// Set up the global interrupt controller.
let mut gic = GicConfigurator::new_with_init(dp.gicc, dp.gicd);
gic.enable_all_interrupts();
gic.set_all_spi_interrupt_targets_cpu0();
gic.enable();
unsafe {
gic.enable_interrupts();
}
let gpio_pins = GpioPins::new(dp.gpio);
// Set up global timer counter and embassy time driver.
let gtc = GlobalTimerCounter::new(dp.gtc, clocks.arm_clocks());
zynq7000_embassy::init(clocks.arm_clocks(), gtc);
// Set up the UART, we are logging with it.
let uart_clk_config = ClockConfig::new_autocalc_with_error(clocks.io_clocks(), 115200)
.unwrap()
.0;
let mut uart = Uart::new_with_mio(
dp.uart_1,
Config::new_with_clk_config(uart_clk_config),
(gpio_pins.mio.mio48, gpio_pins.mio.mio49),
)
.unwrap();
uart.write_all(INIT_STRING.as_bytes()).unwrap();
// Safety: We are not multi-threaded yet.
unsafe { zynq7000_hal::log::uart_blocking::init_unsafe_single_core(uart, LOG_LEVEL, false) };
let boot_mode = BootMode::new_from_regs();
info!("Boot mode: {:?}", boot_mode);
static ETH_RX_BUFS: static_cell::ConstStaticCell<[AlignedBuffer; NUM_RX_SLOTS]> =
static_cell::ConstStaticCell::new(
[AlignedBuffer([0; zynq7000_hal::eth::MTU]); NUM_RX_SLOTS],
);
static ETH_TX_BUFS: static_cell::ConstStaticCell<[AlignedBuffer; NUM_TX_SLOTS]> =
static_cell::ConstStaticCell::new(
[AlignedBuffer([0; zynq7000_hal::eth::MTU]); NUM_TX_SLOTS],
);
let rx_bufs = ETH_RX_BUFS.take();
let tx_bufs = ETH_TX_BUFS.take();
let rx_descr = RX_DESCRIPTORS.take().unwrap();
let tx_descr = TX_DESCRIPTORS.take().unwrap();
// Unwraps okay, list length is not 0
let mut rx_descr_ref =
zynq7000_hal::eth::rx_descr::DescriptorListWrapper::new(rx_descr.as_mut_slice());
let mut tx_descr_ref =
zynq7000_hal::eth::tx_descr::DescriptorListWrapper::new(tx_descr.as_mut_slice());
rx_descr_ref.init_with_aligned_bufs(rx_bufs.as_slice());
tx_descr_ref.init_or_reset();
// Unwrap okay, this is a valid peripheral.
let eth_ll = EthernetLowLevel::new(dp.eth_0).unwrap();
let mod_id = eth_ll.regs.read_module_id();
info!("Ethernet Module ID: {mod_id:?}");
assert_eq!(mod_id, 0x20118);
let (clk_divs, clk_errors) = ClockDivSet::calculate_for_rgmii_and_io_clock(clocks.io_clocks());
debug!(
"Calculated RGMII clock configuration: {:?}, errors (missmatch from ideal rate in hertz): {:?}",
clk_divs, clk_errors
);
// Unwrap okay, we use a standard clock config, and the clock config should never fail.
let eth_cfg = EthernetConfig::new(
zynq7000_hal::eth::ClockConfig::new(clk_divs.cfg_1000_mbps),
zynq7000_hal::eth::calculate_mdc_clk_div(clocks.arm_clocks()).unwrap(),
MAC_ADDRESS,
);
// Configures all the physical pins for ethernet operation and sets up the
// ethernet peripheral.
let mut eth = zynq7000_hal::eth::Ethernet::new_with_mio(
eth_ll,
eth_cfg,
gpio_pins.mio.mio16,
gpio_pins.mio.mio21,
(
gpio_pins.mio.mio17,
gpio_pins.mio.mio18,
gpio_pins.mio.mio19,
gpio_pins.mio.mio20,
),
gpio_pins.mio.mio22,
gpio_pins.mio.mio27,
(
gpio_pins.mio.mio23,
gpio_pins.mio.mio24,
gpio_pins.mio.mio25,
gpio_pins.mio.mio26,
),
Some((gpio_pins.mio.mio52, gpio_pins.mio.mio53)),
);
eth.set_rx_buf_descriptor_base_address(rx_descr_ref.base_addr());
eth.set_tx_buf_descriptor_base_address(tx_descr_ref.base_addr());
eth.start();
let (mut phy, phy_rev) = phy_marvell::Marvell88E1518Phy::new_autoprobe_addr(eth.mdio_mut())
.expect("could not auto-detect phy");
info!(
"Detected Marvell 88E1518 PHY with revision number: {:?}",
phy_rev
);
phy.reset();
phy.restart_auto_negotiation();
let driver = zynq7000_hal::eth::embassy_net::Driver::new(
&eth,
MAC_ADDRESS,
zynq7000_hal::eth::embassy_net::DescriptorsAndBuffers::new(
rx_descr_ref,
rx_bufs,
tx_descr_ref,
tx_bufs,
)
.unwrap(),
);
let config = if USE_DHCP {
embassy_net::Config::dhcpv4(Default::default())
} else {
embassy_net::Config::ipv4_static(STATIC_IPV4_CONFIG)
};
static RESOURCES: static_cell::StaticCell<embassy_net::StackResources<3>> =
static_cell::StaticCell::new();
let mut rng = rand::rngs::SmallRng::seed_from_u64(1);
let (stack, runner) = embassy_net::new(
driver,
config,
RESOURCES.init(embassy_net::StackResources::new()),
rng.next_u64(),
);
// Ensure those are in the data section by making them static.
static RX_UDP_META: static_cell::ConstStaticCell<[embassy_net::udp::PacketMetadata; 8]> =
static_cell::ConstStaticCell::new([embassy_net::udp::PacketMetadata::EMPTY; 8]);
static TX_UDP_META: static_cell::ConstStaticCell<[embassy_net::udp::PacketMetadata; 8]> =
static_cell::ConstStaticCell::new([embassy_net::udp::PacketMetadata::EMPTY; 8]);
static TX_UDP_BUFS: static_cell::ConstStaticCell<[u8; zynq7000_hal::eth::MTU]> =
static_cell::ConstStaticCell::new([0; zynq7000_hal::eth::MTU]);
static RX_UDP_BUFS: static_cell::ConstStaticCell<[u8; zynq7000_hal::eth::MTU]> =
static_cell::ConstStaticCell::new([0; zynq7000_hal::eth::MTU]);
let udp_socket = UdpSocket::new(
stack,
RX_UDP_META.take(),
RX_UDP_BUFS.take(),
TX_UDP_META.take(),
TX_UDP_BUFS.take(),
);
// Ensure those are in the data section by making them static.
static TX_TCP_BUFS: static_cell::ConstStaticCell<[u8; zynq7000_hal::eth::MTU]> =
static_cell::ConstStaticCell::new([0; zynq7000_hal::eth::MTU]);
static RX_TCP_BUFS: static_cell::ConstStaticCell<[u8; zynq7000_hal::eth::MTU]> =
static_cell::ConstStaticCell::new([0; zynq7000_hal::eth::MTU]);
let tcp_socket = TcpSocket::new(stack, RX_TCP_BUFS.take(), TX_TCP_BUFS.take());
// Spawn all embassy tasks.
spawner.spawn(embassy_net_task(runner)).unwrap();
spawner.spawn(udp_task(udp_socket)).unwrap();
spawner.spawn(tcp_task(tcp_socket)).unwrap();
let mut mio_led = Output::new_for_mio(gpio_pins.mio.mio7, PinState::Low);
let mut ip_mode = IpMode::LinkDown;
let mut transmitted_frames = 0;
let mut received_frames = 0;
let receiver = ETH_ERR_QUEUE.receiver();
loop {
// Handle error messages from ethernet interrupt.
while let Ok(msg) = receiver.try_receive() {
info!("Received interrupt result: {msg:?}");
}
if PRINT_PACKET_STATS {
let sent_frames_since_last = eth.ll().regs.statistics().read_tx_count();
if sent_frames_since_last > 0 {
transmitted_frames += sent_frames_since_last;
info!("Frame sent count: {transmitted_frames}");
}
let received_frames_since_last = eth.ll().regs.statistics().read_rx_count();
if received_frames_since_last > 0 {
received_frames += received_frames_since_last;
info!("Frame received count: {received_frames}");
}
}
// This is basically a linker checker task. It also takes care of notifying the
// embassy stack of link state changes.
match ip_mode {
// Assuming that auto-negotiation is performed automatically.
IpMode::LinkDown => {
mio_led.set_low();
zynq7000_hal::eth::embassy_net::update_link_state(
embassy_net::driver::LinkState::Down,
);
ip_mode = IpMode::AutoNegotiating;
}
IpMode::AutoNegotiating => {
let status = phy.read_copper_status();
if status.auto_negotiation_complete() {
let extended_status = phy.read_copper_specific_status_register_1();
info!(
"link is up and auto-negotiation complete. Setting speed {:?} and duplex {:?}",
extended_status.speed().as_zynq7000_eth_speed().unwrap(),
extended_status.duplex().as_zynq7000_eth_duplex()
);
eth.configure_clock_and_speed_duplex(
// If this has the reserved bits, what do we even do? For this example app,
// I am going to assume this never happens..
extended_status.speed().as_zynq7000_eth_speed().unwrap(),
extended_status.duplex().as_zynq7000_eth_duplex(),
&clk_divs,
);
zynq7000_hal::eth::embassy_net::update_link_state(
embassy_net::driver::LinkState::Up,
);
ip_mode = IpMode::AwaitingIpConfig;
} else {
Timer::after_millis(100).await;
}
}
IpMode::AwaitingIpConfig => {
if stack.is_config_up() {
let network_config = stack.config_v4();
info!("Network configuration is up. config: {network_config:?}!",);
ip_mode = IpMode::StackReady;
mio_led.set_high();
} else {
Timer::after_millis(100).await;
}
}
IpMode::StackReady => {
let status = phy.read_copper_status();
// Periodically check for link changes.
if status.copper_link_status() == phy_marvell::LatchingLinkStatus::DownSinceLastRead
{
warn!("ethernet link is down.");
ip_mode = IpMode::LinkDown;
continue;
}
Timer::after_millis(100).await;
}
}
}
}
#[zynq7000_rt::irq]
fn irq_handler() {
let mut gic_helper = GicInterruptHelper::new();
let irq_info = gic_helper.acknowledge_interrupt();
match irq_info.interrupt() {
Interrupt::Sgi(_) => (),
Interrupt::Ppi(ppi_interrupt) => {
if ppi_interrupt == zynq7000_hal::gic::PpiInterrupt::GlobalTimer {
unsafe {
zynq7000_embassy::on_interrupt();
}
}
}
Interrupt::Spi(spi_interrupt) => {
if spi_interrupt == zynq7000_hal::gic::SpiInterrupt::Eth0 {
// This generic library provided interrupt handler takes care of waking
// the driver on received or sent frames while also reporting anomalies
// and errors.
let result = zynq7000_hal::eth::embassy_net::on_interrupt(
zynq7000_hal::eth::EthernetId::Eth0,
);
if result.has_errors() {
ETH_ERR_QUEUE.try_send(result).ok();
}
}
}
Interrupt::Invalid(_) => (),
Interrupt::Spurious => (),
}
gic_helper.end_of_interrupt(irq_info);
}
#[zynq7000_rt::exception(DataAbort)]
fn data_abort_handler(_faulting_addr: usize) -> ! {
loop {
nop();
}
}
#[zynq7000_rt::exception(Undefined)]
fn undefined_handler(_faulting_addr: usize) -> ! {
loop {
nop();
}
}
#[zynq7000_rt::exception(PrefetchAbort)]
fn prefetch_handler(_faulting_addr: usize) -> ! {
loop {
nop();
}
}
/// Panic handler
#[panic_handler]
fn panic(info: &PanicInfo) -> ! {
error!("Panic: {info:?}");
loop {}
}

View File

@@ -0,0 +1,206 @@
//! PS I2C example using a L3GD20H sensor.
//!
//! External HW connections:
//!
//! - SCK pin to JE4 (MIO 12)
//! - SDA pin to JE1 (MIO 13)
//! - SDO / SA0 pin to JE3 (MIO 11) to select I2C address.
#![no_std]
#![no_main]
use core::panic::PanicInfo;
use cortex_ar::asm::nop;
use embassy_executor::Spawner;
use embassy_time::{Delay, Duration, Ticker};
use embedded_hal::digital::StatefulOutputPin;
use embedded_hal_async::delay::DelayNs;
use embedded_io::Write;
use l3gd20::i2c::I2cAddr;
use log::{error, info};
use zynq7000_hal::{
BootMode,
clocks::Clocks,
configure_level_shifter,
gic::{GicConfigurator, GicInterruptHelper, Interrupt},
gpio::{GpioPins, Output, PinState},
gtc::GlobalTimerCounter,
i2c, l2_cache,
time::Hertz,
uart,
};
use zynq7000::{Peripherals, slcr::LevelShifterConfig};
use zynq7000_rt as _;
// Define the clock frequency as a constant
const PS_CLOCK_FREQUENCY: Hertz = Hertz::from_raw(33_333_300);
const I2C_ADDR_SEL: I2cAddr = I2cAddr::Sa0Low;
/// Entry point (not called like a normal main function)
#[unsafe(no_mangle)]
pub extern "C" fn boot_core(cpu_id: u32) -> ! {
if cpu_id != 0 {
panic!("unexpected CPU ID {}", cpu_id);
}
main();
}
#[embassy_executor::main]
#[unsafe(export_name = "main")]
async fn main(_spawner: Spawner) -> ! {
let mut dp = Peripherals::take().unwrap();
l2_cache::init_with_defaults(&mut dp.l2c);
// Enable PS-PL level shifters.
configure_level_shifter(LevelShifterConfig::EnableAll);
// Clock was already initialized by PS7 Init TCL script or FSBL, we just read it.
let clocks = Clocks::new_from_regs(PS_CLOCK_FREQUENCY).unwrap();
// Set up the global interrupt controller.
let mut gic = GicConfigurator::new_with_init(dp.gicc, dp.gicd);
gic.enable_all_interrupts();
gic.set_all_spi_interrupt_targets_cpu0();
gic.enable();
unsafe {
gic.enable_interrupts();
}
let mut gpio_pins = GpioPins::new(dp.gpio);
// Set up global timer counter and embassy time driver.
let gtc = GlobalTimerCounter::new(dp.gtc, clocks.arm_clocks());
zynq7000_embassy::init(clocks.arm_clocks(), gtc);
// Set up the UART, we are logging with it.
let uart_clk_config = uart::ClockConfig::new_autocalc_with_error(clocks.io_clocks(), 115200)
.unwrap()
.0;
let mut uart = uart::Uart::new_with_mio(
dp.uart_1,
uart::Config::new_with_clk_config(uart_clk_config),
(gpio_pins.mio.mio48, gpio_pins.mio.mio49),
)
.unwrap();
uart.write_all(b"-- Zynq 7000 Zedboard I2C L3GD20H example --\n\r")
.unwrap();
// Safety: We are not multi-threaded yet.
unsafe {
zynq7000_hal::log::uart_blocking::init_unsafe_single_core(
uart,
log::LevelFilter::Trace,
false,
)
};
let boot_mode = BootMode::new_from_regs();
info!("Boot mode: {:?}", boot_mode);
let pin_sel = match I2C_ADDR_SEL {
I2cAddr::Sa0Low => PinState::Low,
I2cAddr::Sa0High => PinState::High,
};
let _sa0_pin = Output::new_for_mio(gpio_pins.mio.mio11, pin_sel);
// The CS pin must be pulled high.
let _cs_pin = Output::new_for_mio(gpio_pins.mio.mio10, PinState::High);
let clk_config = i2c::calculate_divisors(
clocks.arm_clocks().cpu_1x_clk(),
i2c::I2cSpeed::Normal100kHz,
)
.unwrap();
let i2c = i2c::I2c::new_with_mio(
dp.i2c_1,
clk_config,
(gpio_pins.mio.mio12, gpio_pins.mio.mio13),
)
.unwrap();
let mut l3gd20 = l3gd20::i2c::L3gd20::new(i2c, l3gd20::i2c::I2cAddr::Sa0Low).unwrap();
let who_am_i = l3gd20.who_am_i().unwrap();
info!("L3GD20 WHO_AM_I: 0x{:02X}", who_am_i);
let mut delay = Delay;
let mut ticker = Ticker::every(Duration::from_millis(400));
let mut mio_led = Output::new_for_mio(gpio_pins.mio.mio7, PinState::Low);
let mut emio_leds: [Output; 8] = [
Output::new_for_emio(gpio_pins.emio.take(0).unwrap(), PinState::Low),
Output::new_for_emio(gpio_pins.emio.take(1).unwrap(), PinState::Low),
Output::new_for_emio(gpio_pins.emio.take(2).unwrap(), PinState::Low),
Output::new_for_emio(gpio_pins.emio.take(3).unwrap(), PinState::Low),
Output::new_for_emio(gpio_pins.emio.take(4).unwrap(), PinState::Low),
Output::new_for_emio(gpio_pins.emio.take(5).unwrap(), PinState::Low),
Output::new_for_emio(gpio_pins.emio.take(6).unwrap(), PinState::Low),
Output::new_for_emio(gpio_pins.emio.take(7).unwrap(), PinState::Low),
];
for (idx, led) in emio_leds.iter_mut().enumerate() {
if idx.is_multiple_of(2) {
led.set_high();
} else {
led.set_low();
}
}
// Power up time for the sensor to get good readings.
delay.delay_ms(50).await;
loop {
mio_led.toggle().unwrap();
let measurements = l3gd20.all().unwrap();
info!("L3GD20: {measurements:?}");
info!("L3GD20 Temp: {:?}", measurements.temp_celcius());
for led in emio_leds.iter_mut() {
led.toggle().unwrap();
}
ticker.next().await; // Wait for the next cycle of the ticker
}
}
#[unsafe(no_mangle)]
pub extern "C" fn _irq_handler() {
let mut gic_helper = GicInterruptHelper::new();
let irq_info = gic_helper.acknowledge_interrupt();
match irq_info.interrupt() {
Interrupt::Sgi(_) => (),
Interrupt::Ppi(ppi_interrupt) => {
if ppi_interrupt == zynq7000_hal::gic::PpiInterrupt::GlobalTimer {
unsafe {
zynq7000_embassy::on_interrupt();
}
}
}
Interrupt::Spi(_spi_interrupt) => (),
Interrupt::Invalid(_) => (),
Interrupt::Spurious => (),
}
gic_helper.end_of_interrupt(irq_info);
}
#[unsafe(no_mangle)]
pub extern "C" fn _abort_handler() {
loop {
nop();
}
}
#[unsafe(no_mangle)]
pub extern "C" fn _undefined_handler() {
loop {
nop();
}
}
#[unsafe(no_mangle)]
pub extern "C" fn _prefetch_handler() {
loop {
nop();
}
}
/// Panic handler
#[panic_handler]
fn panic(info: &PanicInfo) -> ! {
error!("Panic: {info:?}");
loop {}
}

View File

@@ -0,0 +1,296 @@
//! PS SPI example using a L3GD20H sensor.
//!
//! External HW connections:
//!
//! - SCK pin to JE4 (MIO 12)
//! - MOSI pin to JE2 (MIO 10)
//! - MISO pin to JE3 (MIO 11)
//! - SS pin to JE1 (MIO 13)
#![no_std]
#![no_main]
use core::panic::PanicInfo;
use cortex_ar::asm::nop;
use embassy_executor::Spawner;
use embassy_time::{Delay, Duration, Ticker};
use embedded_hal::digital::StatefulOutputPin;
use embedded_hal_async::delay::DelayNs;
use embedded_io::Write;
use log::{error, info};
use zynq7000_hal::{
BootMode,
clocks::Clocks,
configure_level_shifter,
gic::{GicConfigurator, GicInterruptHelper, Interrupt},
gpio::{GpioPins, Output, PinState},
gtc::GlobalTimerCounter,
l2_cache,
spi::{self, SpiAsync, SpiId, SpiWithHwCs, SpiWithHwCsAsync, on_interrupt},
time::Hertz,
uart::{self, TxAsync, on_interrupt_tx},
};
use zynq7000::{Peripherals, slcr::LevelShifterConfig, spi::DelayControl};
use zynq7000_rt as _;
// Define the clock frequency as a constant
const PS_CLOCK_FREQUENCY: Hertz = Hertz::from_raw(33_333_300);
const DEBUG_SPI_CLK_CONFIG: bool = false;
const BLOCKING: bool = false;
/// Entry point (not called like a normal main function)
#[unsafe(no_mangle)]
pub extern "C" fn boot_core(cpu_id: u32) -> ! {
if cpu_id != 0 {
panic!("unexpected CPU ID {}", cpu_id);
}
main();
}
#[embassy_executor::main]
#[unsafe(export_name = "main")]
async fn main(spawner: Spawner) -> ! {
let mut dp = Peripherals::take().unwrap();
l2_cache::init_with_defaults(&mut dp.l2c);
// Enable PS-PL level shifters.
configure_level_shifter(LevelShifterConfig::EnableAll);
// Clock was already initialized by PS7 Init TCL script or FSBL, we just read it.
let mut clocks = Clocks::new_from_regs(PS_CLOCK_FREQUENCY).unwrap();
// SPI reference clock must be larger than the CPU 1x clock.
let spi_ref_clk_div = spi::calculate_largest_allowed_spi_ref_clk_divisor(&clocks)
.unwrap()
.value()
- 1;
spi::configure_spi_ref_clk(&mut clocks, arbitrary_int::u6::new(spi_ref_clk_div as u8));
// Set up the global interrupt controller.
let mut gic = GicConfigurator::new_with_init(dp.gicc, dp.gicd);
gic.enable_all_interrupts();
gic.set_all_spi_interrupt_targets_cpu0();
gic.enable();
unsafe {
gic.enable_interrupts();
}
let mut gpio_pins = GpioPins::new(dp.gpio);
// Set up global timer counter and embassy time driver.
let gtc = GlobalTimerCounter::new(dp.gtc, clocks.arm_clocks());
zynq7000_embassy::init(clocks.arm_clocks(), gtc);
// Set up the UART, we are logging with it.
let uart_clk_config = uart::ClockConfig::new_autocalc_with_error(clocks.io_clocks(), 115200)
.unwrap()
.0;
let mut uart = uart::Uart::new_with_mio(
dp.uart_1,
uart::Config::new_with_clk_config(uart_clk_config),
(gpio_pins.mio.mio48, gpio_pins.mio.mio49),
)
.unwrap();
uart.write_all(b"-- Zynq 7000 Zedboard SPI L3GD20H example --\n\r")
.unwrap();
zynq7000_hal::log::rb::init(log::LevelFilter::Trace);
let boot_mode = BootMode::new_from_regs();
info!("Boot mode: {:?}", boot_mode);
if DEBUG_SPI_CLK_CONFIG {
info!(
"SPI Clock Information: CPU 1x: {:?}, IO Ref Clk: {:?}, SPI Ref Clk: {:?}, DIV: {:?}",
clocks.arm_clocks().cpu_1x_clk(),
clocks.io_clocks().ref_clk(),
clocks.io_clocks().spi_clk(),
spi_ref_clk_div
);
}
let mut spi = spi::Spi::new_one_hw_cs(
dp.spi_1,
clocks.io_clocks(),
spi::Config::new(
// 10 MHz maximum rating of the sensor.
zynq7000::spi::BaudDivSel::By64,
//l3gd20::MODE,
embedded_hal::spi::MODE_3,
spi::SlaveSelectConfig::AutoWithAutoStart,
),
(
gpio_pins.mio.mio12,
gpio_pins.mio.mio10,
gpio_pins.mio.mio11,
),
gpio_pins.mio.mio13,
)
.unwrap();
let mod_id = spi.regs().read_mod_id();
assert_eq!(mod_id, spi::MODULE_ID);
assert!(spi.sclk() <= Hertz::from_raw(10_000_000));
let min_delay = (spi.sclk().raw() * 5) / 1_000_000_000;
spi.inner().configure_delays(
DelayControl::builder()
.with_inter_word_cs_deassert(0)
.with_between_cs_assertion(0)
.with_inter_word(0)
.with_cs_to_first_bit(min_delay as u8)
.build(),
);
let mio_led = Output::new_for_mio(gpio_pins.mio.mio7, PinState::Low);
let mut emio_leds: [Output; 8] = [
Output::new_for_emio(gpio_pins.emio.take(0).unwrap(), PinState::Low),
Output::new_for_emio(gpio_pins.emio.take(1).unwrap(), PinState::Low),
Output::new_for_emio(gpio_pins.emio.take(2).unwrap(), PinState::Low),
Output::new_for_emio(gpio_pins.emio.take(3).unwrap(), PinState::Low),
Output::new_for_emio(gpio_pins.emio.take(4).unwrap(), PinState::Low),
Output::new_for_emio(gpio_pins.emio.take(5).unwrap(), PinState::Low),
Output::new_for_emio(gpio_pins.emio.take(6).unwrap(), PinState::Low),
Output::new_for_emio(gpio_pins.emio.take(7).unwrap(), PinState::Low),
];
for (idx, led) in emio_leds.iter_mut().enumerate() {
if idx.is_multiple_of(2) {
led.set_high();
} else {
led.set_low();
}
}
spawner.spawn(logger_task(uart)).unwrap();
if BLOCKING {
blocking_application(mio_led, emio_leds, spi).await;
} else {
non_blocking_application(mio_led, emio_leds, spi).await;
}
}
#[embassy_executor::task]
pub async fn logger_task(uart: uart::Uart) {
let (tx, _) = uart.split();
let mut tx_async = TxAsync::new(tx);
let frame_queue = zynq7000_hal::log::rb::get_frame_queue();
let mut log_buf: [u8; 2048] = [0; 2048];
loop {
let next_frame_len = frame_queue.receive().await;
zynq7000_hal::log::rb::read_next_frame(next_frame_len, &mut log_buf);
tx_async.write(&log_buf[0..next_frame_len]).await;
}
}
pub async fn blocking_application(
mut mio_led: Output,
mut emio_leds: [Output; 8],
spi: spi::Spi,
) -> ! {
let mut delay = Delay;
let spi_dev = SpiWithHwCs::new(spi, spi::ChipSelect::Slave0, delay.clone());
let mut l3gd20 = l3gd20::spi::L3gd20::new(spi_dev).unwrap();
let who_am_i = l3gd20.who_am_i().unwrap();
info!("L3GD20 WHO_AM_I: 0x{who_am_i:02X}");
let mut ticker = Ticker::every(Duration::from_millis(400));
// Power up time for the sensor to get good readings.
delay.delay_ms(50).await;
loop {
mio_led.toggle().unwrap();
let measurements = l3gd20.all().unwrap();
info!("L3GD20: {measurements:?}");
info!("L3GD20 Temp: {:?}", measurements.temp_celcius());
for led in emio_leds.iter_mut() {
led.toggle().unwrap();
}
ticker.next().await; // Wait for the next cycle of the ticker
}
}
pub async fn non_blocking_application(
mut mio_led: Output,
mut emio_leds: [Output; 8],
spi: spi::Spi,
) -> ! {
let mut delay = Delay;
let spi_async = SpiAsync::new(spi);
let spi_dev = SpiWithHwCsAsync::new(spi_async, spi::ChipSelect::Slave0, delay.clone());
let mut l3gd20 = l3gd20::asynchronous::spi::L3gd20::new(spi_dev)
.await
.unwrap();
let who_am_i = l3gd20.who_am_i().await.unwrap();
info!("L3GD20 WHO_AM_I: 0x{who_am_i:02X}");
let mut ticker = Ticker::every(Duration::from_millis(400));
// Power up time for the sensor to get good readings.
delay.delay_ms(50).await;
loop {
mio_led.toggle().unwrap();
let measurements = l3gd20.all().await.unwrap();
info!("L3GD20: {measurements:?}");
info!("L3GD20 Temp: {:?}", measurements.temp_celcius());
for led in emio_leds.iter_mut() {
led.toggle().unwrap();
}
ticker.next().await; // Wait for the next cycle of the ticker
}
}
#[unsafe(no_mangle)]
pub extern "C" fn _irq_handler() {
let mut gic_helper = GicInterruptHelper::new();
let irq_info = gic_helper.acknowledge_interrupt();
match irq_info.interrupt() {
Interrupt::Sgi(_) => (),
Interrupt::Ppi(ppi_interrupt) => {
if ppi_interrupt == zynq7000_hal::gic::PpiInterrupt::GlobalTimer {
unsafe {
zynq7000_embassy::on_interrupt();
}
}
}
Interrupt::Spi(spi_interrupt) => {
if spi_interrupt == zynq7000_hal::gic::SpiInterrupt::Spi1 {
on_interrupt(SpiId::Spi1);
} else if spi_interrupt == zynq7000_hal::gic::SpiInterrupt::Uart1 {
on_interrupt_tx(zynq7000_hal::uart::UartId::Uart1);
}
}
Interrupt::Invalid(_) => (),
Interrupt::Spurious => (),
}
gic_helper.end_of_interrupt(irq_info);
}
#[unsafe(no_mangle)]
pub extern "C" fn _abort_handler() {
loop {
nop();
}
}
#[unsafe(no_mangle)]
pub extern "C" fn _undefined_handler() {
loop {
nop();
}
}
#[unsafe(no_mangle)]
pub extern "C" fn _prefetch_handler() {
loop {
nop();
}
}
/// Panic handler
#[panic_handler]
fn panic(info: &PanicInfo) -> ! {
error!("Panic: {info:?}");
loop {}
}

View File

@@ -0,0 +1,211 @@
#![no_std]
#![no_main]
use core::panic::PanicInfo;
use cortex_ar::asm::nop;
use embassy_executor::Spawner;
use embassy_time::{Duration, Ticker};
use embedded_hal::digital::StatefulOutputPin;
use embedded_io::Write;
use log::{error, info};
use zedboard::PS_CLOCK_FREQUENCY;
use zedboard_bsp::qspi_spansion;
use zynq7000_hal::{BootMode, clocks, gic, gpio, gtc, prelude::*, qspi, uart};
use zynq7000_rt as _;
const INIT_STRING: &str = "-- Zynq 7000 Zedboard QSPI example --\n\r";
const QSPI_DEV_COMBINATION: qspi::QspiDeviceCombination = qspi::QspiDeviceCombination {
vendor: qspi::QspiVendor::WinbondAndSpansion,
operating_mode: qspi::OperatingMode::FastReadQuadOutput,
two_devices: false,
};
/// Entry point (not called like a normal main function)
#[unsafe(no_mangle)]
pub extern "C" fn boot_core(cpu_id: u32) -> ! {
if cpu_id != 0 {
panic!("unexpected CPU ID {}", cpu_id);
}
main();
}
const ERASE_PROGRAM_READ_TEST: bool = false;
#[embassy_executor::main]
#[unsafe(export_name = "main")]
async fn main(_spawner: Spawner) -> ! {
let periphs = zynq7000_hal::init(zynq7000_hal::Config {
init_l2_cache: true,
level_shifter_config: Some(zynq7000_hal::LevelShifterConfig::EnableAll),
interrupt_config: Some(zynq7000_hal::InteruptConfig::AllInterruptsToCpu0),
})
.unwrap();
// Clock was already initialized by PS7 Init TCL script or FSBL, we just read it.
let clocks = clocks::Clocks::new_from_regs(PS_CLOCK_FREQUENCY).unwrap();
let gpio_pins = gpio::GpioPins::new(periphs.gpio);
// Set up global timer counter and embassy time driver.
let gtc = gtc::GlobalTimerCounter::new(periphs.gtc, clocks.arm_clocks());
zynq7000_embassy::init(clocks.arm_clocks(), gtc);
// Set up the UART, we are logging with it.
let uart_clk_config = uart::ClockConfig::new_autocalc_with_error(clocks.io_clocks(), 115200)
.unwrap()
.0;
let mut uart = uart::Uart::new_with_mio(
periphs.uart_1,
uart::Config::new_with_clk_config(uart_clk_config),
(gpio_pins.mio.mio48, gpio_pins.mio.mio49),
)
.unwrap();
uart.write_all(INIT_STRING.as_bytes()).unwrap();
// Safety: We are not multi-threaded yet.
unsafe {
zynq7000_hal::log::uart_blocking::init_unsafe_single_core(
uart,
log::LevelFilter::Trace,
false,
)
};
let boot_mode = BootMode::new_from_regs();
info!("Boot mode: {:?}", boot_mode);
let qspi_clock_config =
qspi::ClockConfig::calculate_with_loopback(qspi::SrcSelIo::IoPll, &clocks, 100.MHz())
.expect("QSPI clock calculation failed");
let qspi = qspi::Qspi::new_single_qspi_with_feedback(
periphs.qspi,
qspi_clock_config,
embedded_hal::spi::MODE_0,
qspi::IoType::LvCmos33,
gpio_pins.mio.mio1,
(
gpio_pins.mio.mio2,
gpio_pins.mio.mio3,
gpio_pins.mio.mio4,
gpio_pins.mio.mio5,
),
gpio_pins.mio.mio6,
gpio_pins.mio.mio8,
);
let qspi_io_mode = qspi.into_io_mode(false);
let mut spansion_qspi = qspi_spansion::QspiSpansionS25Fl256SIoMode::new(qspi_io_mode, true);
let rdid = spansion_qspi.read_rdid_extended();
info!(
"QSPI Info: manufacturer ID: {:?}, interface type: {:?}, density: {:?}, sector arch: {:?}, model number: {:?}",
rdid.base_id().manufacturer_id(),
rdid.base_id().memory_interface_type(),
rdid.base_id().density(),
rdid.sector_arch(),
rdid.model_number()
);
let cr1 = spansion_qspi.read_configuration_register();
info!("QSPI Configuration Register 1: {:?}", cr1);
let mut write_buf: [u8; u8::MAX as usize + 1] = [0x0; u8::MAX as usize + 1];
for (idx, byte) in write_buf.iter_mut().enumerate() {
*byte = idx as u8;
}
let mut read_buf = [0u8; 256];
if ERASE_PROGRAM_READ_TEST {
info!("performing erase, program, read test");
spansion_qspi
.erase_sector(0x10000)
.expect("erasing sector failed");
spansion_qspi.read_page_fast_read(0x10000, &mut read_buf, true);
for read in read_buf.iter() {
assert_eq!(*read, 0xFF);
}
read_buf.fill(0);
spansion_qspi.program_page(0x10000, &write_buf).unwrap();
spansion_qspi.read_page_fast_read(0x10000, &mut read_buf, true);
for (read, written) in read_buf.iter().zip(write_buf.iter()) {
assert_eq!(read, written);
}
info!("test successful");
}
let mut spansion_lqspi = spansion_qspi.into_linear_addressed(QSPI_DEV_COMBINATION.into());
let guard = spansion_lqspi.read_guard();
unsafe {
core::ptr::copy_nonoverlapping(
(qspi::QSPI_START_ADDRESS + 0x10000) as *const u8,
read_buf.as_mut_ptr(),
256,
);
}
drop(guard);
if ERASE_PROGRAM_READ_TEST {
for (read, written) in read_buf.iter().zip(write_buf.iter()) {
assert_eq!(
read, written,
"linear read failure, read and write missmatch"
);
}
}
let mut ticker = Ticker::every(Duration::from_millis(200));
let mut mio_led = gpio::Output::new_for_mio(gpio_pins.mio.mio7, gpio::PinState::Low);
loop {
mio_led.toggle().unwrap();
ticker.next().await; // Wait for the next cycle of the ticker
}
}
#[zynq7000_rt::irq]
fn irq_handler() {
let mut gic_helper = gic::GicInterruptHelper::new();
let irq_info = gic_helper.acknowledge_interrupt();
match irq_info.interrupt() {
gic::Interrupt::Sgi(_) => (),
gic::Interrupt::Ppi(ppi_interrupt) => {
if ppi_interrupt == gic::PpiInterrupt::GlobalTimer {
unsafe {
zynq7000_embassy::on_interrupt();
}
}
}
gic::Interrupt::Spi(_spi_interrupt) => (),
gic::Interrupt::Invalid(_) => (),
gic::Interrupt::Spurious => (),
}
gic_helper.end_of_interrupt(irq_info);
}
#[zynq7000_rt::exception(DataAbort)]
fn data_abort_handler(_faulting_addr: usize) -> ! {
loop {
nop();
}
}
#[zynq7000_rt::exception(Undefined)]
fn undefined_handler(_faulting_addr: usize) -> ! {
loop {
nop();
}
}
#[zynq7000_rt::exception(PrefetchAbort)]
fn prefetch_handler(_faulting_addr: usize) -> ! {
loop {
nop();
}
}
/// Panic handler
#[panic_handler]
fn panic(info: &PanicInfo) -> ! {
error!("Panic: {info:?}");
loop {}
}

View File

@@ -0,0 +1,267 @@
#![no_std]
#![no_main]
use axi_uart16550::AxiUart16550;
use axi_uartlite::AxiUartlite;
use core::panic::PanicInfo;
use cortex_ar::asm::nop;
use embassy_executor::Spawner;
use embassy_time::{Duration, Ticker};
use embedded_hal::digital::StatefulOutputPin;
use embedded_io::Write;
use fugit::RateExtU32;
use log::{error, info};
use zedboard::PS_CLOCK_FREQUENCY;
use zynq7000_hal::{
BootMode,
clocks::Clocks,
configure_level_shifter,
gic::{GicConfigurator, GicInterruptHelper, Interrupt},
gpio::{GpioPins, Output, PinState},
gtc::GlobalTimerCounter,
l2_cache,
uart::{ClockConfig, Config, Uart},
};
use zynq7000::{Peripherals, slcr::LevelShifterConfig};
use zynq7000_rt as _;
const INIT_STRING: &str = "-- Zynq 7000 Zedboard blocking UART example --\n\r";
const AXI_UARTLITE_BASE_ADDR: u32 = 0x42C0_0000;
const AXI_UAR16550_BASE_ADDR: u32 = 0x43C0_0000;
/// Entry point (not called like a normal main function)
#[unsafe(no_mangle)]
pub extern "C" fn boot_core(cpu_id: u32) -> ! {
if cpu_id != 0 {
panic!("unexpected CPU ID {}", cpu_id);
}
main();
}
#[derive(Debug, Copy, Clone, PartialEq)]
pub enum UartSel {
Uart0 = 0b000,
Uartlite = 0b001,
Uart16550 = 0b010,
Uart0ToUartlite = 0b011,
Uart0ToUart16550 = 0b100,
UartliteToUart16550 = 0b101,
}
pub struct UartMultiplexer {
sel_pins: [Output; 3],
}
impl UartMultiplexer {
pub fn new(mut sel_pins: [Output; 3]) -> Self {
for pin in sel_pins.iter_mut() {
pin.set_low();
}
Self { sel_pins }
}
pub fn select(&mut self, sel: UartSel) {
// TODO: A pin group switcher would be nice to do this in one go.
match sel {
UartSel::Uart0 => {
self.sel_pins[2].set_low();
self.sel_pins[1].set_low();
self.sel_pins[0].set_low();
}
UartSel::Uartlite => {
self.sel_pins[2].set_low();
self.sel_pins[1].set_low();
self.sel_pins[0].set_high();
}
UartSel::Uart16550 => {
self.sel_pins[2].set_low();
self.sel_pins[1].set_high();
self.sel_pins[0].set_low();
}
UartSel::Uart0ToUartlite => {
self.sel_pins[2].set_low();
self.sel_pins[1].set_high();
self.sel_pins[0].set_high();
}
UartSel::Uart0ToUart16550 => {
self.sel_pins[2].set_high();
self.sel_pins[1].set_low();
self.sel_pins[0].set_low();
}
UartSel::UartliteToUart16550 => {
self.sel_pins[2].set_high();
self.sel_pins[1].set_low();
self.sel_pins[0].set_high();
}
}
}
}
#[embassy_executor::main]
#[unsafe(export_name = "main")]
async fn main(_spawner: Spawner) -> ! {
let mut dp = Peripherals::take().unwrap();
l2_cache::init_with_defaults(&mut dp.l2c);
// Enable PS-PL level shifters.
configure_level_shifter(LevelShifterConfig::EnableAll);
// Clock was already initialized by PS7 Init TCL script or FSBL, we just read it.
let clocks = Clocks::new_from_regs(PS_CLOCK_FREQUENCY).unwrap();
// Set up the global interrupt controller.
let mut gic = GicConfigurator::new_with_init(dp.gicc, dp.gicd);
gic.enable_all_interrupts();
gic.set_all_spi_interrupt_targets_cpu0();
gic.enable();
unsafe {
gic.enable_interrupts();
}
let mut gpio_pins = GpioPins::new(dp.gpio);
// Set up global timer counter and embassy time driver.
let gtc = GlobalTimerCounter::new(dp.gtc, clocks.arm_clocks());
zynq7000_embassy::init(clocks.arm_clocks(), gtc);
// Set up the UART, we are logging with it.
let uart_clk_config = ClockConfig::new_autocalc_with_error(clocks.io_clocks(), 115200)
.unwrap()
.0;
let mut log_uart = Uart::new_with_mio(
dp.uart_1,
Config::new_with_clk_config(uart_clk_config),
(gpio_pins.mio.mio48, gpio_pins.mio.mio49),
)
.unwrap();
log_uart.write_all(INIT_STRING.as_bytes()).unwrap();
// Safety: Co-operative multi-tasking is used.
unsafe {
zynq7000_hal::log::uart_blocking::init_unsafe_single_core(
log_uart,
log::LevelFilter::Trace,
false,
)
};
// UART0 routed through EMIO to PL pins.
let mut uart_0 =
Uart::new_with_emio(dp.uart_0, Config::new_with_clk_config(uart_clk_config)).unwrap();
// Safety: Valid address of AXI UARTLITE.
let mut uartlite = unsafe { AxiUartlite::new(AXI_UARTLITE_BASE_ADDR) };
// TODO: Can we determine/read the clock frequency to the FPGAs as well?
let (clk_config, error) =
axi_uart16550::ClkConfig::new_autocalc_with_error(100.MHz(), 115200).unwrap();
assert!(error < 0.02);
let mut uart_16550 = unsafe {
AxiUart16550::new(
AXI_UAR16550_BASE_ADDR,
axi_uart16550::UartConfig::new_with_clk_config(clk_config),
)
};
let boot_mode = BootMode::new_from_regs();
info!("Boot mode: {:?}", boot_mode);
let mut ticker = Ticker::every(Duration::from_millis(1000));
let mut mio_led = Output::new_for_mio(gpio_pins.mio.mio7, PinState::Low);
let mut emio_leds: [Output; 8] = [
Output::new_for_emio(gpio_pins.emio.take(0).unwrap(), PinState::Low),
Output::new_for_emio(gpio_pins.emio.take(1).unwrap(), PinState::Low),
Output::new_for_emio(gpio_pins.emio.take(2).unwrap(), PinState::Low),
Output::new_for_emio(gpio_pins.emio.take(3).unwrap(), PinState::Low),
Output::new_for_emio(gpio_pins.emio.take(4).unwrap(), PinState::Low),
Output::new_for_emio(gpio_pins.emio.take(5).unwrap(), PinState::Low),
Output::new_for_emio(gpio_pins.emio.take(6).unwrap(), PinState::Low),
Output::new_for_emio(gpio_pins.emio.take(7).unwrap(), PinState::Low),
];
let mut uart_mux = UartMultiplexer::new([
Output::new_for_emio(gpio_pins.emio.take(8).unwrap(), PinState::Low),
Output::new_for_emio(gpio_pins.emio.take(9).unwrap(), PinState::Low),
Output::new_for_emio(gpio_pins.emio.take(10).unwrap(), PinState::Low),
]);
let mut current_sel = UartSel::Uart0;
uart_mux.select(current_sel);
let mut led_idx = 0;
loop {
mio_led.toggle().unwrap();
emio_leds[led_idx].toggle().unwrap();
led_idx += 1;
if led_idx >= emio_leds.len() {
led_idx = 0;
}
uart_0
.write_all("Hello, World from UART0!\n\r".as_bytes())
.unwrap();
uartlite
.write_all("Hello, World from AXI UARTLITE!\n\r".as_bytes())
.unwrap();
uart_16550
.write_all("Hello, World from AXI UART16550!\n\r".as_bytes())
.unwrap();
uart_0.flush().unwrap();
uartlite.flush().unwrap();
uart_16550.flush().unwrap();
match current_sel {
UartSel::Uart0 => current_sel = UartSel::Uartlite,
UartSel::Uartlite => current_sel = UartSel::Uart16550,
UartSel::Uart16550 => current_sel = UartSel::Uart0,
UartSel::Uart0ToUartlite | UartSel::Uart0ToUart16550 | UartSel::UartliteToUart16550 => {
}
}
uart_mux.select(current_sel);
ticker.next().await; // Wait for the next cycle of the ticker
}
}
#[zynq7000_rt::irq]
fn irq_handler() {
let mut gic_helper = GicInterruptHelper::new();
let irq_info = gic_helper.acknowledge_interrupt();
match irq_info.interrupt() {
Interrupt::Sgi(_) => (),
Interrupt::Ppi(ppi_interrupt) => {
if ppi_interrupt == zynq7000_hal::gic::PpiInterrupt::GlobalTimer {
unsafe {
zynq7000_embassy::on_interrupt();
}
}
}
Interrupt::Spi(_spi_interrupt) => (),
Interrupt::Invalid(_) => (),
Interrupt::Spurious => (),
}
gic_helper.end_of_interrupt(irq_info);
}
#[zynq7000_rt::exception(DataAbort)]
fn data_abort_handler(_faulting_addr: usize) -> ! {
loop {
nop();
}
}
#[zynq7000_rt::exception(Undefined)]
fn undefined_handler(_faulting_addr: usize) -> ! {
loop {
nop();
}
}
#[zynq7000_rt::exception(PrefetchAbort)]
fn prefetch_handler(_faulting_addr: usize) -> ! {
loop {
nop();
}
}
/// Panic handler
#[panic_handler]
fn panic(info: &PanicInfo) -> ! {
error!("Panic: {info:?}");
loop {}
}

View File

@@ -0,0 +1,574 @@
//! This example application shows usage of the non-blocking APIs offered for
//! various UART peripherals which are part of the PS or the sample bitstream.
//!
//! This example ONLY works with the provided `zedboard-fpga-design`.
//! The example FPGA design contains the following components relevant for this design
//!
//! - An AXI UARTLite peripheral, with the interrupt signal connected to the PS
//! - An AXI UART16550 peripheral, with the interrupt signal connected to the PS
//! - A custom UART multiplexer component. This multiplexer has various configuration modes
//! configurable via 3 EMIO pins:
//! 1. Route UART0 RX to pin JA1 and TX to JA2.
//! 2. Route AXI UARTLite RX to pin JA1 and TX to JA2.
//! 3. Route AXI UART16550 RX to pin JA1 and TX to JA2.
//! 4. Route UART0 to AXI UARTLite.
//! 5. Route UART0 to AXI 16550.
//! 6. Route AXI UARTLite to AXI 16550.
//! - Options 4, 5 and 6 allow to test and show the non-blocking API without the need for external
//! hardware.
//!
//! This example runs one embassy task for each UART, which periodically sends variable sized
//! string content out via its TX port. Each UART peripheral also permanently listens to all
//! incoming RX data via interrupts. Received data will be sent from the interrupt handler
//! to the main thread and will be printed to the main console on UART 1.
#![no_std]
#![no_main]
extern crate alloc;
use alloc::format;
use axi_uart16550::AxiUart16550;
use axi_uartlite::AxiUartlite;
use core::{cell::RefCell, panic::PanicInfo};
use cortex_ar::asm::nop;
use critical_section::Mutex;
use embassy_executor::Spawner;
use embassy_time::{Duration, Ticker};
use embedded_alloc::LlffHeap as Heap;
use embedded_hal::digital::StatefulOutputPin;
use embedded_io::Write as _;
use heapless::spsc::Queue;
use log::{error, info, warn};
use zynq7000_hal::{
BootMode,
clocks::Clocks,
configure_level_shifter,
gic::{GicConfigurator, GicInterruptHelper, Interrupt},
gpio::{GpioPins, Output, PinState},
gtc::GlobalTimerCounter,
l2_cache,
time::Hertz,
uart::{ClockConfig, Config, Uart},
};
pub enum UartMode {
Uart0ToUartlite,
Uart0ToUart16550,
UartliteToUart16550,
}
const UART_MODE: UartMode = UartMode::Uart0ToUart16550;
const INIT_STRING: &str = "-- Zynq 7000 Zedboard non-blocking UART example --\n\r";
#[global_allocator]
static HEAP: Heap = Heap::empty();
use zynq7000::{Peripherals, slcr::LevelShifterConfig};
use zynq7000_rt as _;
// Define the clock frequency as a constant
const PS_CLOCK_FREQUENCY: Hertz = Hertz::from_raw(33_333_300);
const AXI_UARTLITE_BASE_ADDR: u32 = 0x42C0_0000;
const AXI_UAR16550_BASE_ADDR: u32 = 0x43C0_0000;
pub const UARTLITE_PL_INT_ID: usize = 0;
pub const UART16550_PL_INT_ID: usize = 1;
const RB_SIZE: usize = 512;
// These queues are used to send all data received in the UART interrupt handlers to the main
// processing thread.
static QUEUE_UART_0: static_cell::ConstStaticCell<heapless::spsc::Queue<u8, RB_SIZE>> =
static_cell::ConstStaticCell::new(Queue::new());
static QUEUE_UARTLITE: static_cell::ConstStaticCell<heapless::spsc::Queue<u8, RB_SIZE>> =
static_cell::ConstStaticCell::new(Queue::new());
static QUEUE_UART16550: static_cell::ConstStaticCell<heapless::spsc::Queue<u8, RB_SIZE>> =
static_cell::ConstStaticCell::new(Queue::new());
// Those are all used by the interrupt handler, so we have to do the Mutex dance.
static RX_UART_0: Mutex<RefCell<Option<zynq7000_hal::uart::Rx>>> = Mutex::new(RefCell::new(None));
static UART_0_PROD: Mutex<RefCell<Option<heapless::spsc::Producer<'static, u8, RB_SIZE>>>> =
Mutex::new(RefCell::new(None));
static UARTLITE_PROD: Mutex<RefCell<Option<heapless::spsc::Producer<'static, u8, RB_SIZE>>>> =
Mutex::new(RefCell::new(None));
static UART16550_PROD: Mutex<RefCell<Option<heapless::spsc::Producer<'static, u8, RB_SIZE>>>> =
Mutex::new(RefCell::new(None));
/// Entry point (not called like a normal main function)
#[unsafe(no_mangle)]
pub extern "C" fn boot_core(cpu_id: u32) -> ! {
if cpu_id != 0 {
panic!("unexpected CPU ID {}", cpu_id);
}
main();
}
#[derive(Debug, Copy, Clone, PartialEq)]
pub enum UartSel {
Uart0 = 0b000,
Uartlite = 0b001,
Uart16550 = 0b010,
Uart0ToUartlite = 0b011,
Uart0ToUart16550 = 0b100,
UartliteToUart16550 = 0b101,
}
pub struct UartMultiplexer {
sel_pins: [Output; 3],
}
impl UartMultiplexer {
pub fn new(mut sel_pins: [Output; 3]) -> Self {
for pin in sel_pins.iter_mut() {
pin.set_low();
}
Self { sel_pins }
}
pub fn select(&mut self, sel: UartSel) {
// TODO: A pin group switcher would be nice to do this in one go.
match sel {
UartSel::Uart0 => {
self.sel_pins[2].set_low();
self.sel_pins[1].set_low();
self.sel_pins[0].set_low();
}
UartSel::Uartlite => {
self.sel_pins[2].set_low();
self.sel_pins[1].set_low();
self.sel_pins[0].set_high();
}
UartSel::Uart16550 => {
self.sel_pins[2].set_low();
self.sel_pins[1].set_high();
self.sel_pins[0].set_low();
}
UartSel::Uart0ToUartlite => {
self.sel_pins[2].set_low();
self.sel_pins[1].set_high();
self.sel_pins[0].set_high();
}
UartSel::Uart0ToUart16550 => {
self.sel_pins[2].set_high();
self.sel_pins[1].set_low();
self.sel_pins[0].set_low();
}
UartSel::UartliteToUart16550 => {
self.sel_pins[2].set_high();
self.sel_pins[1].set_low();
self.sel_pins[0].set_high();
}
}
}
}
#[embassy_executor::main]
#[unsafe(export_name = "main")]
async fn main(spawner: Spawner) -> ! {
let mut dp = Peripherals::take().unwrap();
l2_cache::init_with_defaults(&mut dp.l2c);
// Enable PS-PL level shifters.
configure_level_shifter(LevelShifterConfig::EnableAll);
// Clock was already initialized by PS7 Init TCL script or FSBL, we just read it.
let clocks = Clocks::new_from_regs(PS_CLOCK_FREQUENCY).unwrap();
// Set up the global interrupt controller.
let mut gic = GicConfigurator::new_with_init(dp.gicc, dp.gicd);
gic.enable_all_interrupts();
gic.set_all_spi_interrupt_targets_cpu0();
// AXI UARTLite documentation mentions that a rising-edge sensitive interrupt is generated,
// but the GIC configures high-level sensitivity for the PL interrupts by default. We
// need to change it to edge sensitivity.
gic.set_pl_interrupt_sensitivity(UARTLITE_PL_INT_ID, zynq7000_hal::gic::SpiSensitivity::Edge)
.unwrap();
gic.enable();
unsafe {
gic.enable_interrupts();
}
let mut gpio_pins = GpioPins::new(dp.gpio);
// Set up global timer counter and embassy time driver.
let gtc = GlobalTimerCounter::new(dp.gtc, clocks.arm_clocks());
zynq7000_embassy::init(clocks.arm_clocks(), gtc);
// Set up the UART, we are logging with it.
let uart_clk_config = ClockConfig::new_autocalc_with_error(clocks.io_clocks(), 115200)
.unwrap()
.0;
let mut log_uart = Uart::new_with_mio(
dp.uart_1,
Config::new_with_clk_config(uart_clk_config),
(gpio_pins.mio.mio48, gpio_pins.mio.mio49),
)
.unwrap();
log_uart.write_all(INIT_STRING.as_bytes()).unwrap();
// Initialize the allocator BEFORE you use it
{
use core::mem::MaybeUninit;
// 10 kB heap.
const HEAP_SIZE: usize = 1024 * 10;
static mut HEAP_MEM: [MaybeUninit<u8>; HEAP_SIZE] = [MaybeUninit::uninit(); HEAP_SIZE];
unsafe { HEAP.init(&raw mut HEAP_MEM as usize, HEAP_SIZE) }
}
// Safety: We are not multi-threaded yet.
unsafe {
zynq7000_hal::log::uart_blocking::init_unsafe_single_core(
log_uart,
log::LevelFilter::Trace,
false,
)
};
// Set up UART multiplexing before creating and configuring the UARTs.
let mut uart_mux = UartMultiplexer::new([
Output::new_for_emio(gpio_pins.emio.take(8).unwrap(), PinState::Low),
Output::new_for_emio(gpio_pins.emio.take(9).unwrap(), PinState::Low),
Output::new_for_emio(gpio_pins.emio.take(10).unwrap(), PinState::Low),
]);
match UART_MODE {
UartMode::Uart0ToUartlite => uart_mux.select(UartSel::Uart0ToUartlite),
UartMode::Uart0ToUart16550 => uart_mux.select(UartSel::Uart0ToUart16550),
UartMode::UartliteToUart16550 => uart_mux.select(UartSel::UartliteToUart16550),
}
// UART0 routed through EMIO to PL pins.
let uart_0 =
Uart::new_with_emio(dp.uart_0, Config::new_with_clk_config(uart_clk_config)).unwrap();
// Safety: Valid address of AXI UARTLITE.
let mut uartlite = unsafe { AxiUartlite::new(AXI_UARTLITE_BASE_ADDR) };
// We need to call this before splitting the structure, because the interrupt signal is
// used for both TX and RX, so the API is only exposed for this structure.
uartlite.enable_interrupt();
let (clk_config, error) =
axi_uart16550::ClkConfig::new_autocalc_with_error(clocks.pl_clocks()[0], 115200).unwrap();
assert!(error < 0.02);
let _uart_16550 = unsafe {
AxiUart16550::new(
AXI_UAR16550_BASE_ADDR,
axi_uart16550::UartConfig::new_with_clk_config(clk_config),
)
};
let boot_mode = BootMode::new_from_regs();
info!("Boot mode: {:?}", boot_mode);
let mio_led = Output::new_for_mio(gpio_pins.mio.mio7, PinState::Low);
let emio_leds: [Output; 8] = [
Output::new_for_emio(gpio_pins.emio.take(0).unwrap(), PinState::Low),
Output::new_for_emio(gpio_pins.emio.take(1).unwrap(), PinState::Low),
Output::new_for_emio(gpio_pins.emio.take(2).unwrap(), PinState::Low),
Output::new_for_emio(gpio_pins.emio.take(3).unwrap(), PinState::Low),
Output::new_for_emio(gpio_pins.emio.take(4).unwrap(), PinState::Low),
Output::new_for_emio(gpio_pins.emio.take(5).unwrap(), PinState::Low),
Output::new_for_emio(gpio_pins.emio.take(6).unwrap(), PinState::Low),
Output::new_for_emio(gpio_pins.emio.take(7).unwrap(), PinState::Low),
];
let (uart_0_tx, mut uart_0_rx) = uart_0.split();
let (uartlite_tx, _uartlite_rx) = uartlite.split();
let (uart_16550_tx, mut uart_16550_rx) = _uart_16550.split();
let (uart_0_prod, mut uart_0_cons) = QUEUE_UART_0.take().split();
let (uartlite_prod, mut uartlite_cons) = QUEUE_UARTLITE.take().split();
let (uart16550_prod, mut uart16550_cons) = QUEUE_UART16550.take().split();
// Use our helper function to start RX handling.
uart_0_rx.start_interrupt_driven_reception();
// Use our helper function to start RX handling.
uart_16550_rx.start_interrupt_driven_reception();
critical_section::with(|cs| {
UART_0_PROD.borrow(cs).borrow_mut().replace(uart_0_prod);
UARTLITE_PROD.borrow(cs).borrow_mut().replace(uartlite_prod);
UART16550_PROD
.borrow(cs)
.borrow_mut()
.replace(uart16550_prod);
RX_UART_0.borrow(cs).borrow_mut().replace(uart_0_rx);
});
spawner.spawn(led_task(mio_led, emio_leds)).unwrap();
match UART_MODE {
UartMode::Uart0ToUartlite => {
spawner.spawn(uartlite_task(uartlite_tx)).unwrap();
spawner.spawn(uart_0_task(uart_0_tx)).unwrap();
}
UartMode::Uart0ToUart16550 => {
spawner.spawn(uart_0_task(uart_0_tx)).unwrap();
spawner.spawn(uart_16550_task(uart_16550_tx)).unwrap();
}
UartMode::UartliteToUart16550 => {
spawner.spawn(uartlite_task(uartlite_tx)).unwrap();
spawner.spawn(uart_16550_task(uart_16550_tx)).unwrap();
}
}
let mut read_buf: [u8; RB_SIZE] = [0; RB_SIZE];
let mut ticker = Ticker::every(Duration::from_millis(200));
loop {
let read_bytes = uart_0_cons.len();
(0..read_bytes).for_each(|i| {
read_buf[i] = unsafe { uart_0_cons.dequeue_unchecked() };
});
if read_bytes > 0 {
info!("Received {read_bytes} bytes on UART0");
info!(
"Data: {:?}",
core::str::from_utf8(&read_buf[0..read_bytes]).unwrap()
);
}
let read_bytes = uartlite_cons.len();
(0..read_bytes).for_each(|i| {
read_buf[i] = unsafe { uartlite_cons.dequeue_unchecked() };
});
if read_bytes > 0 {
info!("Received {read_bytes} bytes on UARTLITE");
info!(
"Data: {:?}",
core::str::from_utf8(&read_buf[0..read_bytes]).unwrap()
);
}
let read_bytes = uart16550_cons.len();
(0..read_bytes).for_each(|i| {
read_buf[i] = unsafe { uart16550_cons.dequeue_unchecked() };
});
if read_bytes > 0 {
info!("Received {read_bytes} bytes on UART16550");
info!(
"Data: {:?}",
core::str::from_utf8(&read_buf[0..read_bytes]).unwrap()
);
}
ticker.next().await; // Wait for the next cycle of the ticker
}
}
fn build_print_string(prefix: &str, base_str: &str) -> alloc::string::String {
format!("{prefix} {base_str}\n\r")
}
#[embassy_executor::task]
async fn led_task(mut mio_led: Output, mut emio_leds: [Output; 8]) {
let mut ticker = Ticker::every(Duration::from_millis(1000));
let mut led_idx = 0;
loop {
mio_led.toggle().unwrap();
emio_leds[led_idx].toggle().unwrap();
led_idx += 1;
if led_idx >= emio_leds.len() {
led_idx = 0;
}
ticker.next().await;
}
}
#[embassy_executor::task]
async fn uartlite_task(uartlite: axi_uartlite::Tx) {
let mut ticker = Ticker::every(Duration::from_millis(1000));
let str0 = build_print_string("UARTLITE:", "Hello World");
let str1 = build_print_string(
"UARTLITE:",
"Long Hello which should completely fill the FIFO",
);
let mut idx = 0;
let print_strs = [str0.as_bytes(), str1.as_bytes()];
let mut tx_async = axi_uartlite::tx_async::TxAsync::new(uartlite, 0).unwrap();
loop {
tx_async.write(print_strs[idx]).await;
idx += 1;
if idx == 2 {
idx = 0;
}
ticker.next().await;
}
}
#[embassy_executor::task]
async fn uart_0_task(uart_tx: zynq7000_hal::uart::Tx) {
let mut ticker = Ticker::every(Duration::from_millis(1000));
let mut tx_async = zynq7000_hal::uart::TxAsync::new(uart_tx);
let str0 = build_print_string("UART0:", "Hello World");
let str1 = build_print_string(
"UART0:",
"Long Hello which should completely fill the 64 byte FIFO of the UART0 peripheral",
);
let mut idx = 0;
let print_strs = [str0.as_bytes(), str1.as_bytes()];
loop {
tx_async.write(print_strs[idx]).await;
idx += 1;
if idx == 2 {
idx = 0;
}
ticker.next().await;
}
}
#[embassy_executor::task]
async fn uart_16550_task(uart_tx: axi_uart16550::Tx) {
let mut ticker = Ticker::every(Duration::from_millis(1000));
let mut tx_async = axi_uart16550::TxAsync::new(uart_tx, 0, embassy_time::Delay).unwrap();
let str0 = build_print_string("UART16550:", "Hello World");
let str1 = build_print_string(
"UART16550:",
"Long Hello which should completely fill the FIFO",
);
let mut idx = 0;
let print_strs = [str0.as_bytes(), str1.as_bytes()];
loop {
tx_async.write(print_strs[idx]).await;
idx += 1;
if idx == 2 {
idx = 0;
}
ticker.next().await;
}
}
#[zynq7000_rt::irq]
fn irq_handler() {
let mut gic_helper = GicInterruptHelper::new();
let irq_info = gic_helper.acknowledge_interrupt();
match irq_info.interrupt() {
Interrupt::Sgi(_) => (),
Interrupt::Ppi(ppi_interrupt) => {
if ppi_interrupt == zynq7000_hal::gic::PpiInterrupt::GlobalTimer {
unsafe {
zynq7000_embassy::on_interrupt();
}
}
}
Interrupt::Spi(spi_interrupt) => match spi_interrupt {
zynq7000_hal::gic::SpiInterrupt::Pl0 => {
on_interrupt_axi_uartlite();
}
zynq7000_hal::gic::SpiInterrupt::Pl1 => {
on_interrupt_axi_16550();
}
zynq7000_hal::gic::SpiInterrupt::Uart0 => {
on_interrupt_uart_0();
}
_ => (),
},
Interrupt::Invalid(_) => (),
Interrupt::Spurious => (),
}
gic_helper.end_of_interrupt(irq_info);
}
fn on_interrupt_axi_uartlite() {
let mut buf = [0; axi_uartlite::FIFO_DEPTH];
let mut rx = unsafe { axi_uartlite::Rx::steal(AXI_UARTLITE_BASE_ADDR as usize) };
// Handle RX first: Empty the FIFO content into local buffer.
let read_bytes = rx.on_interrupt_rx(&mut buf);
// Handle TX next: Handle pending asynchronous TX operations.
let mut tx = unsafe { axi_uartlite::Tx::steal(AXI_UARTLITE_BASE_ADDR as usize) };
axi_uartlite::on_interrupt_tx(&mut tx, 0);
// Send received RX data to main task.
if read_bytes > 0 {
critical_section::with(|cs| {
let mut prod_ref_mut = UARTLITE_PROD.borrow(cs).borrow_mut();
let prod = prod_ref_mut.as_mut().unwrap();
(0..read_bytes).for_each(|i| {
prod.enqueue(buf[i]).expect("failed to enqueue byte");
});
});
}
}
fn on_interrupt_axi_16550() {
let mut buf = [0; axi_uart16550::FIFO_DEPTH];
let mut read_bytes = 0;
let mut rx = unsafe { axi_uart16550::Rx::steal(AXI_UAR16550_BASE_ADDR as usize) };
let iir = rx.read_iir();
if let Ok(int_id) = iir.int_id() {
match int_id {
axi_uart16550::registers::IntId2::ReceiverLineStatus => {
let errors = rx.on_interrupt_receiver_line_status(iir);
warn!("Receiver line status error: {errors:?}");
}
axi_uart16550::registers::IntId2::RxDataAvailable
| axi_uart16550::registers::IntId2::CharTimeout => {
read_bytes = rx.on_interrupt_data_available_or_char_timeout(int_id, &mut buf);
}
axi_uart16550::registers::IntId2::ThrEmpty => {
let mut tx = unsafe { axi_uart16550::Tx::steal(AXI_UAR16550_BASE_ADDR as usize) };
axi_uart16550::tx_async::on_interrupt_tx(&mut tx, 0);
}
axi_uart16550::registers::IntId2::ModemStatus => (),
}
}
// Send received RX data to main task.
if read_bytes > 0 {
critical_section::with(|cs| {
let mut prod_ref_mut = UART16550_PROD.borrow(cs).borrow_mut();
let prod = prod_ref_mut.as_mut().unwrap();
(0..read_bytes).for_each(|i| {
prod.enqueue(buf[i]).expect("failed to enqueue byte");
});
});
}
}
fn on_interrupt_uart_0() {
let mut buf = [0; zynq7000_hal::uart::FIFO_DEPTH];
let mut read_bytes = 0;
// Handle RX first: Empty the FIFO content into local buffer.
critical_section::with(|cs| {
let mut uart0 = RX_UART_0.borrow(cs).borrow_mut();
read_bytes = uart0
.as_mut()
.unwrap()
.on_interrupt(&mut buf, true)
.read_bytes();
});
// Handle TX next: Handle pending asynchronous TX operations.
zynq7000_hal::uart::on_interrupt_tx(zynq7000_hal::uart::UartId::Uart0);
// Send received RX data to main task.
if read_bytes > 0 {
critical_section::with(|cs| {
let mut prod_ref_mut = UART_0_PROD.borrow(cs).borrow_mut();
let prod = prod_ref_mut.as_mut().unwrap();
(0..read_bytes).for_each(|i| {
prod.enqueue(buf[i]).expect("failed to enqueue byte");
});
});
}
}
#[zynq7000_rt::exception(DataAbort)]
fn data_abort_handler(_faulting_addr: usize) -> ! {
loop {
nop();
}
}
#[zynq7000_rt::exception(Undefined)]
fn undefined_handler(_faulting_addr: usize) -> ! {
loop {
nop();
}
}
#[zynq7000_rt::exception(PrefetchAbort)]
fn prefetch_handler(_faulting_addr: usize) -> ! {
loop {
nop();
}
}
/// Panic handler
#[panic_handler]
fn panic(info: &PanicInfo) -> ! {
error!("Panic: {info:?}");
loop {}
}

View File

@@ -0,0 +1,5 @@
#![no_std]
use zynq7000_hal::time::Hertz;
// Define the clock frequency as a constant
pub const PS_CLOCK_FREQUENCY: Hertz = Hertz::from_raw(33_333_333);

View File

@@ -0,0 +1,140 @@
#![no_std]
#![no_main]
use core::panic::PanicInfo;
use cortex_ar::asm::nop;
use embassy_executor::Spawner;
use embassy_time::{Duration, Ticker};
use embedded_hal::digital::StatefulOutputPin;
use embedded_io::Write;
use log::{error, info};
use zedboard::PS_CLOCK_FREQUENCY;
use zynq7000_hal::{BootMode, clocks, gic, gpio, gtc, uart};
use zynq7000_rt as _;
const INIT_STRING: &str = "-- Zynq 7000 Zedboard GPIO blinky example --\n\r";
/// Entry point (not called like a normal main function)
#[unsafe(no_mangle)]
pub extern "C" fn boot_core(cpu_id: u32) -> ! {
if cpu_id != 0 {
panic!("unexpected CPU ID {}", cpu_id);
}
main();
}
#[embassy_executor::main]
#[unsafe(export_name = "main")]
async fn main(_spawner: Spawner) -> ! {
let periphs = zynq7000_hal::init(zynq7000_hal::Config {
init_l2_cache: true,
level_shifter_config: Some(zynq7000_hal::LevelShifterConfig::EnableAll),
interrupt_config: Some(zynq7000_hal::InteruptConfig::AllInterruptsToCpu0),
})
.unwrap();
// Clock was already initialized by PS7 Init TCL script or FSBL, we just read it.
let clocks = clocks::Clocks::new_from_regs(PS_CLOCK_FREQUENCY).unwrap();
let mut gpio_pins = gpio::GpioPins::new(periphs.gpio);
// Set up global timer counter and embassy time driver.
let gtc = gtc::GlobalTimerCounter::new(periphs.gtc, clocks.arm_clocks());
zynq7000_embassy::init(clocks.arm_clocks(), gtc);
// Set up the UART, we are logging with it.
let uart_clk_config = uart::ClockConfig::new_autocalc_with_error(clocks.io_clocks(), 115200)
.unwrap()
.0;
let mut uart = uart::Uart::new_with_mio(
periphs.uart_1,
uart::Config::new_with_clk_config(uart_clk_config),
(gpio_pins.mio.mio48, gpio_pins.mio.mio49),
)
.unwrap();
uart.write_all(INIT_STRING.as_bytes()).unwrap();
// Safety: We are not multi-threaded yet.
unsafe {
zynq7000_hal::log::uart_blocking::init_unsafe_single_core(
uart,
log::LevelFilter::Trace,
false,
)
};
let boot_mode = BootMode::new_from_regs();
info!("Boot mode: {:?}", boot_mode);
let mut ticker = Ticker::every(Duration::from_millis(200));
let mut mio_led = gpio::Output::new_for_mio(gpio_pins.mio.mio7, gpio::PinState::Low);
let mut emio_leds: [gpio::Output; 8] = [
gpio::Output::new_for_emio(gpio_pins.emio.take(0).unwrap(), gpio::PinState::Low),
gpio::Output::new_for_emio(gpio_pins.emio.take(1).unwrap(), gpio::PinState::Low),
gpio::Output::new_for_emio(gpio_pins.emio.take(2).unwrap(), gpio::PinState::Low),
gpio::Output::new_for_emio(gpio_pins.emio.take(3).unwrap(), gpio::PinState::Low),
gpio::Output::new_for_emio(gpio_pins.emio.take(4).unwrap(), gpio::PinState::Low),
gpio::Output::new_for_emio(gpio_pins.emio.take(5).unwrap(), gpio::PinState::Low),
gpio::Output::new_for_emio(gpio_pins.emio.take(6).unwrap(), gpio::PinState::Low),
gpio::Output::new_for_emio(gpio_pins.emio.take(7).unwrap(), gpio::PinState::Low),
];
loop {
mio_led.toggle().unwrap();
// Create a wave pattern for emio_leds
for led in emio_leds.iter_mut() {
led.toggle().unwrap();
ticker.next().await; // Wait for the next ticker for each toggle
}
ticker.next().await; // Wait for the next cycle of the ticker
}
}
#[zynq7000_rt::irq]
fn irq_handler() {
let mut gic_helper = gic::GicInterruptHelper::new();
let irq_info = gic_helper.acknowledge_interrupt();
match irq_info.interrupt() {
gic::Interrupt::Sgi(_) => (),
gic::Interrupt::Ppi(ppi_interrupt) => {
if ppi_interrupt == gic::PpiInterrupt::GlobalTimer {
unsafe {
zynq7000_embassy::on_interrupt();
}
}
}
gic::Interrupt::Spi(_spi_interrupt) => (),
gic::Interrupt::Invalid(_) => (),
gic::Interrupt::Spurious => (),
}
gic_helper.end_of_interrupt(irq_info);
}
#[zynq7000_rt::exception(DataAbort)]
fn data_abort_handler(_faulting_addr: usize) -> ! {
loop {
nop();
}
}
#[zynq7000_rt::exception(Undefined)]
fn undefined_handler(_faulting_addr: usize) -> ! {
loop {
nop();
}
}
#[zynq7000_rt::exception(PrefetchAbort)]
fn prefetch_handler(_faulting_addr: usize) -> ! {
loop {
nop();
}
}
/// Panic handler
#[panic_handler]
fn panic(info: &PanicInfo) -> ! {
error!("Panic: {info:?}");
loop {}
}