switch to embassy

This commit is contained in:
2025-11-22 00:45:48 +01:00
parent f7d3c4c633
commit 2a32366c3a
6 changed files with 889 additions and 662 deletions

921
Cargo.lock generated

File diff suppressed because it is too large Load Diff

View File

@@ -9,15 +9,30 @@ test = false
bench = false
[dependencies]
cortex-m = { version = "0.7", features = ["inline-asm"] }
cortex-m-rt = "0.7"
embassy-rp = { version = "0.8", features = [
"time-driver",
"defmt",
"rp2040",
"unstable-pac",
"critical-section-impl",
"intrinsics",
] }
embassy-executor = { version = "0.9", features = [
"defmt",
"executor-thread",
"executor-interrupt",
"arch-cortex-m",
] }
embassy-usb = { version = "0.5", default-features = false, features = [
"defmt",
] }
embassy-futures = { version = "0.1", features = ["defmt"] }
panic-probe = { version = "1.0", features = ["print-defmt", "defmt-error"] }
rp-pico = "0.9"
embedded-hal = "1.0"
pio = "0.2"
pio-proc = "0.2"
usb-device = { version = "0.3", features = ["defmt"] }
usbd-serial = "0.2"
static_cell = "2.1"
portable-atomic = { version = "1.11", features = ["critical-section"] }
critical-section = "1.2"
defmt = "1.0"
defmt-rtt = "1.1"

36
Embed.toml Normal file
View File

@@ -0,0 +1,36 @@
[default.probe]
protocol = "Swd"
speed = 20000
# If you only have one probe cargo embed will pick automatically
# Otherwise: add your probe's VID/PID/serial to filter
## rust-dap
# usb_vid = "6666"
# usb_pid = "4444"
# serial = "test"
[default.flashing]
enabled = true
[default.reset]
enabled = true
halt_afterwards = false
[default.general]
chip = "RP2040"
log_level = "WARN"
# RP2040 does not support connect_under_reset
connect_under_reset = false
[default.rtt]
enabled = true
up_mode = "NoBlockSkip"
up_channels = [{ channel = 0, name = "name", format = "Defmt" }]
timeout = 3000
log_enabled = false
log_path = "./logs"
[default.gdb]
enabled = true
gdb_connection_string = "127.0.0.1:1337"

View File

@@ -13,12 +13,10 @@ SECTIONS {
{
KEEP(*(.boot2));
} > BOOT2
} INSERT BEFORE .text;
SECTIONS {
/* ### Boot loader */
/* Initial ROM data */
.romdata ORIGIN(ROM) :
{
KEEP(*(.romdata));
KEEP(*(.romdata*));
} > ROM
} INSERT AFTER .bss;
} INSERT BEFORE .text;

View File

@@ -11,143 +11,70 @@
mod serial;
use core::{
cell::Cell,
mem::MaybeUninit,
sync::atomic::{AtomicU8, Ordering},
task::Poll,
};
use cortex_m::{delay::Delay, interrupt::Mutex, singleton};
use defmt_rtt as _;
use embedded_hal::digital::OutputPin;
use panic_probe as _;
use pio_proc::pio_asm;
use rp_pico::{
Pins, XOSC_CRYSTAL_FREQ, entry,
hal::{
Sio, Watchdog,
clocks::init_clocks_and_plls,
gpio::{FunctionPio0, PullNone},
pio::{PIO0SM0, PIO0SM3, PIOBuilder, PioIRQ, Rx, Tx},
prelude::*,
usb::UsbBus,
},
pac::{self, CorePeripherals, Peripherals, interrupt},
use embassy_executor::{InterruptExecutor, Spawner, task};
use embassy_futures::{poll_once, yield_now};
use embassy_rp::{
bind_interrupts,
clocks::ClockConfig,
gpio::{Drive, Level, Output, SlewRate},
interrupt::{self, InterruptExt, Priority},
peripherals::{PIO0, USB},
pio::{self, Direction, Pio, ShiftConfig, ShiftDirection, StateMachine, program::pio_asm},
usb::{self, Driver},
};
use usb_device::{class_prelude::*, prelude::*};
use usbd_serial::SerialPort;
use embassy_usb::{
UsbDevice,
class::cdc_acm::{self, CdcAcmClass},
};
use panic_probe as _;
use static_cell::{ConstStaticCell, StaticCell};
use crate::serial::{Link, PacketBuilder};
const ADDRESS_BASE: u8 = 0;
const ADDRESS_PINS: u8 = 15;
const DATA_BASE: u8 = 15;
const DATA_PINS: u8 = 8;
const CE: u8 = 26;
#[allow(unused)]
const OE: u8 = 27;
const ROM_SIZE: usize = 1024 * 32;
static GLOBAL_ADDRESS_RX: Mutex<Cell<Option<Rx<PIO0SM3>>>> = Mutex::new(Cell::new(None));
static GLOBAL_DATA_TX: Mutex<Cell<Option<Tx<PIO0SM0>>>> = Mutex::new(Cell::new(None));
static ROM_DATA: [AtomicU8; ROM_SIZE] = [const { AtomicU8::new(0) }; ROM_SIZE];
static GLOBAL_USB_DEVICE: Mutex<Cell<Option<UsbDevice<UsbBus>>>> = Mutex::new(Cell::new(None));
static GLOBAL_USB_SERIAL: Mutex<Cell<Option<SerialPort<UsbBus>>>> = Mutex::new(Cell::new(None));
#[unsafe(link_section = ".romdata")]
#[used]
static INIT_ROM_DATA: MaybeUninit<[u8; ROM_SIZE]> = MaybeUninit::uninit();
#[entry]
fn main() -> ! {
let mut pac = Peripherals::take().unwrap();
let mut core = CorePeripherals::take().unwrap();
bind_interrupts!(struct Irqs {
PIO0_IRQ_0 => pio::InterruptHandler<PIO0>;
USBCTRL_IRQ => usb::InterruptHandler<USB>;
});
let mut watchdog = Watchdog::new(pac.WATCHDOG);
static EXECUTOR_HIGH: InterruptExecutor = InterruptExecutor::new();
let clocks = init_clocks_and_plls(
XOSC_CRYSTAL_FREQ,
pac.XOSC,
pac.CLOCKS,
pac.PLL_SYS,
pac.PLL_USB,
&mut pac.RESETS,
&mut watchdog,
)
.ok()
.unwrap();
#[embassy_rp::interrupt]
unsafe fn SWI_IRQ_0() {
unsafe { EXECUTOR_HIGH.on_interrupt() }
}
let mut delay = Delay::new(core.SYST, clocks.system_clock.freq().to_Hz());
#[embassy_executor::main]
async fn main(spawner: Spawner) -> ! {
let config =
embassy_rp::config::Config::new(defmt::unwrap!(ClockConfig::system_freq(133_000_000)));
let p = embassy_rp::init(config);
let sio = Sio::new(pac.SIO);
let led = unsafe { p.PIN_25.clone_unchecked() };
let pins = Pins::new(
pac.IO_BANK0,
pac.PADS_BANK0,
sio.gpio_bank0,
&mut pac.RESETS,
);
let mut led_pin = pins.led.into_push_pull_output();
// set address pins as schmitt-trigger inputs
pins.gpio0
.reconfigure::<FunctionPio0, PullNone>()
.set_schmitt_enabled(true);
pins.gpio1
.reconfigure::<FunctionPio0, PullNone>()
.set_schmitt_enabled(true);
pins.gpio2
.reconfigure::<FunctionPio0, PullNone>()
.set_schmitt_enabled(true);
pins.gpio3
.reconfigure::<FunctionPio0, PullNone>()
.set_schmitt_enabled(true);
pins.gpio4
.reconfigure::<FunctionPio0, PullNone>()
.set_schmitt_enabled(true);
pins.gpio5
.reconfigure::<FunctionPio0, PullNone>()
.set_schmitt_enabled(true);
pins.gpio6
.reconfigure::<FunctionPio0, PullNone>()
.set_schmitt_enabled(true);
pins.gpio7
.reconfigure::<FunctionPio0, PullNone>()
.set_schmitt_enabled(true);
pins.gpio8
.reconfigure::<FunctionPio0, PullNone>()
.set_schmitt_enabled(true);
pins.gpio9
.reconfigure::<FunctionPio0, PullNone>()
.set_schmitt_enabled(true);
pins.gpio10
.reconfigure::<FunctionPio0, PullNone>()
.set_schmitt_enabled(true);
pins.gpio11
.reconfigure::<FunctionPio0, PullNone>()
.set_schmitt_enabled(true);
pins.gpio12
.reconfigure::<FunctionPio0, PullNone>()
.set_schmitt_enabled(true);
pins.gpio13
.reconfigure::<FunctionPio0, PullNone>()
.set_schmitt_enabled(true);
pins.gpio14
.reconfigure::<FunctionPio0, PullNone>()
.set_schmitt_enabled(true);
// set data pins as inputs as we don't know if the output should be enabled yet
pins.gpio15.reconfigure::<FunctionPio0, PullNone>();
pins.gpio16.reconfigure::<FunctionPio0, PullNone>();
pins.gpio17.reconfigure::<FunctionPio0, PullNone>();
pins.gpio18.reconfigure::<FunctionPio0, PullNone>();
pins.gpio19.reconfigure::<FunctionPio0, PullNone>();
pins.gpio20.reconfigure::<FunctionPio0, PullNone>();
pins.gpio21.reconfigure::<FunctionPio0, PullNone>();
pins.gpio22.reconfigure::<FunctionPio0, PullNone>();
// set CE and OE as schmitt-triger inputs
pins.gpio26
.reconfigure::<FunctionPio0, PullNone>()
.set_schmitt_enabled(true);
pins.gpio27
.reconfigure::<FunctionPio0, PullNone>()
.set_schmitt_enabled(true);
// initialize rom data
for (init, byte) in unsafe { INIT_ROM_DATA.assume_init_ref() }
.iter()
.zip(ROM_DATA.iter())
{
byte.store(*init, Ordering::SeqCst);
}
// Pull from fifo and write to all data pins
let data = pio_asm!(".wrap_target", "out pins, 8", ".wrap");
@@ -176,175 +103,238 @@ fn main() -> ! {
".wrap"
);
let (mut pio, sm0, sm1, sm2, sm3) = pac.PIO0.split(&mut pac.RESETS);
let Pio {
mut common,
mut sm0,
mut sm1,
mut sm2,
mut sm3,
..
} = Pio::new(p.PIO0, Irqs);
let output_enable = common.load_program(&output_enable.program);
let data = pio.install(&data.program).unwrap();
let output_enable = pio.install(&output_enable.program).unwrap();
let address = pio.install(&report_data.program).unwrap();
let (data_sm, _, data_tx) = PIOBuilder::from_installed_program(data)
.out_pins(DATA_BASE, DATA_PINS)
.pull_threshold(DATA_PINS)
.autopull(true)
.build(sm0);
let _data_sm = data_sm.start();
cortex_m::interrupt::free(|cs| GLOBAL_DATA_TX.borrow(cs).set(Some(data_tx)));
let (output_enable_low_sm, _, _) =
PIOBuilder::from_installed_program(unsafe { output_enable.share() })
.side_set_pin_base(DATA_BASE)
.in_pin_base(CE)
.build(sm1);
let _output_enable_low_sm = output_enable_low_sm.start();
let (output_enable_high_sm, _, _) = PIOBuilder::from_installed_program(output_enable)
.side_set_pin_base(DATA_BASE + 4)
.in_pin_base(CE)
.build(sm2);
let _output_enable_high_sm = output_enable_high_sm.start();
let (address_sm, address_rx, _) = PIOBuilder::from_installed_program(address)
.in_pin_base(ADDRESS_BASE)
.push_threshold(ADDRESS_PINS)
.autopush(true)
.build(sm3);
let _address_sm = address_sm.start();
address_rx.enable_rx_not_empty_interrupt(PioIRQ::Irq0);
cortex_m::interrupt::free(|cs| GLOBAL_ADDRESS_RX.borrow(cs).set(Some(address_rx)));
let usbctrl_regs = pac.USBCTRL_REGS;
let usbctrl_dpram = pac.USBCTRL_DPRAM;
let resets = &mut pac.RESETS;
let usb_bus = singleton!(: UsbBusAllocator<UsbBus> = UsbBusAllocator::new(UsbBus::new(
usbctrl_regs,
usbctrl_dpram,
clocks.usb_clock,
true,
resets,
)))
.unwrap();
let serial = SerialPort::new(usb_bus);
cortex_m::interrupt::free(|cs| GLOBAL_USB_SERIAL.borrow(cs).set(Some(serial)));
let usb_dev = UsbDeviceBuilder::new(usb_bus, UsbVidPid(0x2e8a, 0x000a))
.strings(&[StringDescriptors::default()
.manufacturer("Max Känner")
.product("PicoROM.rs")
.serial_number("1")])
.unwrap()
.device_class(2)
.build();
cortex_m::interrupt::free(|cs| GLOBAL_USB_DEVICE.borrow(cs).set(Some(usb_dev)));
unsafe {
// Highest priority for pio
core.NVIC.set_priority(pac::interrupt::PIO0_IRQ_0, 0x00);
// lowest priority for usb
core.NVIC.set_priority(pac::interrupt::USBCTRL_IRQ, 0xFF);
pac::NVIC::unmask(pac::interrupt::PIO0_IRQ_0);
pac::NVIC::unmask(pac::interrupt::USBCTRL_IRQ);
let mut address_pins = [
common.make_pio_pin(p.PIN_0),
common.make_pio_pin(p.PIN_1),
common.make_pio_pin(p.PIN_2),
common.make_pio_pin(p.PIN_3),
common.make_pio_pin(p.PIN_4),
common.make_pio_pin(p.PIN_5),
common.make_pio_pin(p.PIN_6),
common.make_pio_pin(p.PIN_7),
common.make_pio_pin(p.PIN_8),
common.make_pio_pin(p.PIN_9),
common.make_pio_pin(p.PIN_10),
common.make_pio_pin(p.PIN_11),
common.make_pio_pin(p.PIN_12),
common.make_pio_pin(p.PIN_13),
common.make_pio_pin(p.PIN_14),
];
for pin in &mut address_pins {
pin.set_schmitt(true);
}
let mut data_pins = [
common.make_pio_pin(p.PIN_15),
common.make_pio_pin(p.PIN_16),
common.make_pio_pin(p.PIN_17),
common.make_pio_pin(p.PIN_18),
common.make_pio_pin(p.PIN_19),
common.make_pio_pin(p.PIN_20),
common.make_pio_pin(p.PIN_21),
common.make_pio_pin(p.PIN_22),
];
for pin in &mut data_pins {
pin.set_slew_rate(SlewRate::Fast);
pin.set_drive_strength(Drive::_12mA);
pin.set_schmitt(true);
}
let data_pins = [
&data_pins[0],
&data_pins[1],
&data_pins[2],
&data_pins[3],
&data_pins[4],
&data_pins[5],
&data_pins[6],
&data_pins[7],
];
let mut ce_pin = common.make_pio_pin(p.PIN_26);
ce_pin.set_schmitt(true);
let mut oe_pin = common.make_pio_pin(p.PIN_27);
oe_pin.set_schmitt(true);
let led_pin = common.make_pio_pin(p.PIN_25);
let address_pins = [
&address_pins[0],
&address_pins[1],
&address_pins[2],
&address_pins[3],
&address_pins[4],
&address_pins[5],
&address_pins[6],
&address_pins[7],
&address_pins[8],
&address_pins[9],
&address_pins[10],
&address_pins[11],
&address_pins[12],
&address_pins[13],
&address_pins[14],
data_pins[0],
data_pins[1],
data_pins[2],
data_pins[3],
data_pins[4],
data_pins[5],
data_pins[6],
data_pins[7],
&common.make_pio_pin(p.PIN_23),
&common.make_pio_pin(p.PIN_24),
&led_pin,
&ce_pin,
&oe_pin,
];
// configure data pio
let mut cfg = pio::Config::default();
cfg.use_program(&common.load_program(&data.program), &[]);
cfg.set_out_pins(&data_pins[..]);
cfg.shift_out = ShiftConfig {
threshold: DATA_PINS,
direction: ShiftDirection::default(),
auto_fill: true,
};
sm0.set_config(&cfg);
sm0.set_enable(true);
// configure output enable pio
let mut cfg = pio::Config::default();
cfg.use_program(&output_enable, &data_pins[..4]);
cfg.set_in_pins(&[&ce_pin, &oe_pin]);
sm1.set_config(&cfg);
sm1.set_enable(true);
cfg.use_program(&output_enable, &data_pins[4..]);
sm2.set_config(&cfg);
sm2.set_enable(true);
// configure address pio
let mut cfg = pio::Config::default();
cfg.use_program(&common.load_program(&report_data.program), &[]);
cfg.set_in_pins(&address_pins[..]);
cfg.shift_in = ShiftConfig {
threshold: ADDRESS_PINS,
direction: ShiftDirection::default(),
auto_fill: true,
};
sm3.set_pin_dirs(Direction::In, &address_pins[..]);
sm3.set_pin_dirs(Direction::Out, &[&led_pin]);
sm3.set_config(&cfg);
sm3.set_enable(true);
let driver = Driver::new(p.USB, Irqs);
let config = {
let mut config = embassy_usb::Config::new(0x2e8a, 0x000a);
config.manufacturer = Some("Max Känner");
config.product = Some("PicoROM.rs");
config.serial_number = Some("2");
config.max_power = 100;
config.max_packet_size_0 = 64;
config
};
let mut builder = {
static CONFIG_DESCRIPTOR: ConstStaticCell<[u8; 256]> = ConstStaticCell::new([0; 256]);
static BOS_DESCRIPTOR: ConstStaticCell<[u8; 256]> = ConstStaticCell::new([0; 256]);
static CONTROL_BUF: ConstStaticCell<[u8; 64]> = ConstStaticCell::new([0; 64]);
embassy_usb::Builder::new(
driver,
config,
CONFIG_DESCRIPTOR.take(),
BOS_DESCRIPTOR.take(),
&mut [],
CONTROL_BUF.take(),
)
};
let mut class = {
static STATE: StaticCell<cdc_acm::State> = StaticCell::new();
CdcAcmClass::new(&mut builder, STATE.init(cdc_acm::State::new()), 64)
};
let usb = builder.build();
interrupt::SWI_IRQ_0.set_priority(Priority::P1);
interrupt::PIO0_IRQ_0.set_priority(Priority::P0);
interrupt::USBCTRL_IRQ.set_priority(Priority::P3);
let int_spawner = EXECUTOR_HIGH.start(interrupt::SWI_IRQ_0);
int_spawner.must_spawn(pio_task(sm0, sm3));
spawner.must_spawn(usb_task(usb));
let mut led = Output::new(led, Level::Low);
loop {
led_pin.set_high().unwrap();
delay.delay_ms(500);
led_pin.set_low().unwrap();
delay.delay_ms(500);
}
}
#[interrupt]
fn PIO0_IRQ_0() {
static mut ADDRESS: Option<Rx<PIO0SM3>> = None;
static mut DATA: Option<Tx<PIO0SM0>> = None;
if ADDRESS.is_none() {
*ADDRESS = cortex_m::interrupt::free(|cs| GLOBAL_ADDRESS_RX.borrow(cs).take());
}
if DATA.is_none() {
*DATA = cortex_m::interrupt::free(|cs| GLOBAL_DATA_TX.borrow(cs).take());
}
if let Some(address) = ADDRESS {
while let Some(rx) = address.read() {
let address = (rx & 0x7fff) as u16;
if let Some(tx) = DATA {
let data = ROM_DATA[usize::from(address)].load(Ordering::Relaxed);
defmt::trace!("replying with {:#04x} @ {:#06x}", data, address);
tx.write(u32::from(data));
'outer: {
led.set_low();
class.wait_connection().await;
while !class.rts() {
yield_now().await;
}
}
}
}
#[interrupt]
fn USBCTRL_IRQ() {
static mut USB_DEVICE: Option<UsbDevice<UsbBus>> = None;
static mut USB_SERIAL: Option<SerialPort<UsbBus>> = None;
static mut DO_PREAMBLE: bool = true;
static mut PACKET_BUILDER: PacketBuilder = PacketBuilder::new();
static mut LINK: Link = Link::new();
const PREAMBLE: &[u8] = b"PicoROM Hello";
if USB_DEVICE.is_none() {
*USB_DEVICE = cortex_m::interrupt::free(|cs| GLOBAL_USB_DEVICE.borrow(cs).take());
}
if USB_SERIAL.is_none() {
*USB_SERIAL = cortex_m::interrupt::free(|cs| GLOBAL_USB_SERIAL.borrow(cs).take());
}
let Some(usb_dev) = USB_DEVICE else { return };
let Some(serial) = USB_SERIAL else { return };
if !serial.rts() {
*DO_PREAMBLE = true;
}
if *DO_PREAMBLE && serial.rts() {
match serial.write(PREAMBLE) {
Ok(count) if count == PREAMBLE.len() => {
*DO_PREAMBLE = false;
defmt::info!("Send Preamble")
defmt::info!("USB Connected");
led.set_high();
if let Err(e) = class.write_packet(b"PicoROM Hello").await {
defmt::error!("Error sending preamble: {}", e);
break 'outer;
}
Ok(count) => {
defmt::warn!(
"Unable to write the whole preamble. Only wrote {} Bytes",
count
);
}
Err(UsbError::WouldBlock) => (),
Err(e) => {
defmt::error!("Unable to write preamble: {}", e)
}
}
}
if usb_dev.poll(&mut [serial]) {
let mut buf = [0u8; 64];
match serial.read(&mut buf) {
Ok(0) => {}
Ok(count) => {
for byte in buf.into_iter().take(count) {
if let Some(packet) = PACKET_BUILDER.push(byte) {
let mut buf = [0; 64];
let mut packet_builder = PacketBuilder::new();
let mut link = Link::new();
while class.rts() {
let n = match poll_once(class.read_packet(&mut buf)) {
Poll::Ready(Ok(n)) => n,
Poll::Ready(Err(e)) => {
defmt::error!("Error reading packet data: {}", e);
break 'outer;
}
Poll::Pending => {
yield_now().await;
continue;
}
};
for byte in buf.into_iter().take(n) {
if let Some(packet) = packet_builder.push(byte) {
defmt::debug!("Got packet: {}", packet);
if let Some(response) = LINK.handle_packet(&packet) {
if let Some(response) = link.handle_packet(&packet) {
defmt::info!("Sending Response: {}", response);
if let Err(e) = response.send(serial)
&& e != UsbError::WouldBlock
{
if let Err(e) = response.send(&mut class).await {
defmt::error!("Unable to send response: {}", e);
break 'outer;
}
}
}
}
}
Err(UsbError::WouldBlock) => (),
Err(e) => {
defmt::error!("USB Error: {}", e);
}
}
}
if usb_dev.state() == UsbDeviceState::Default {
*DO_PREAMBLE = true;
defmt::info!("USB Disconnected");
}
}
#[task]
async fn usb_task(mut usb: UsbDevice<'static, Driver<'static, USB>>) -> ! {
usb.run().await
}
#[task]
async fn pio_task(
mut data_sm: StateMachine<'static, PIO0, 0>,
mut address_sm: StateMachine<'static, PIO0, 3>,
) -> ! {
loop {
let address = address_sm.rx().wait_pull().await;
let address = (address & 0x7fff) as u16;
let data = ROM_DATA[usize::from(address)].load(Ordering::SeqCst);
defmt::trace!("replying with {:#04x} @ {:#06x}", data, address);
data_sm.tx().try_push(u32::from(data));
}
}

View File

@@ -1,10 +1,10 @@
use core::{borrow::BorrowMut, sync::atomic::Ordering};
use core::sync::atomic::Ordering;
use defmt::Format;
use embassy_rp::usb::{self, Driver};
use embassy_usb::{class::cdc_acm::CdcAcmClass, driver::EndpointError};
use heapless::{String, Vec};
use num_enum::{IntoPrimitive, TryFromPrimitive};
use usb_device::{UsbError, bus::UsbBus};
use usbd_serial::SerialPort;
use crate::ROM_DATA;
@@ -60,16 +60,15 @@ impl Format for Packet {
}
impl Packet {
pub fn send(
pub async fn send(
&self,
serial: &mut SerialPort<impl UsbBus, impl BorrowMut<[u8]>, impl BorrowMut<[u8]>>,
) -> Result<(), UsbError> {
serial.write(&[
self.kind.into(),
u8::try_from(self.payload.len()).unwrap_or(MAX_PAYLOAD),
])?;
serial.write(&self.payload)?;
Ok(())
serial: &mut CdcAcmClass<'static, Driver<'static, impl usb::Instance>>,
) -> Result<(), EndpointError> {
let mut packet = Vec::<_, 32>::new();
let _ = packet.push(self.kind.into());
let _ = packet.push(u8::try_from(self.payload.len()).unwrap_or(MAX_PAYLOAD));
let _ = packet.extend_from_slice(self.payload.as_slice());
serial.write_packet(&packet).await
}
pub fn error<const N: usize>(reason: &[u8; N]) -> Self {
@@ -160,6 +159,7 @@ impl Link {
}
}
#[unsafe(link_section = ".data")]
pub fn handle_packet(&mut self, packet: &Packet) -> Option<Packet> {
if self.name.is_empty() {
let _ = self.name.push_str("rom");
@@ -184,7 +184,7 @@ impl Link {
// return Some(Packet::error(b"Write out of range"));
continue;
};
target.store(*byte, Ordering::Relaxed);
target.store(*byte, Ordering::SeqCst);
self.pointer += 1;
}
None
@@ -274,6 +274,7 @@ impl Link {
}
}
}
Kind::CommitFlash => None,
_ => Some(Packet::error(b"Unrecognized packet")),
}
}