Merge branch 'main' of https://github.com/embassy-rs/embassy into hrtim
This commit is contained in:
@ -34,3 +34,6 @@ log = { version = "0.4.17", optional = true }
|
||||
[[bin]]
|
||||
name = "rtos_trace"
|
||||
required-features = ["nightly"]
|
||||
|
||||
[profile.release]
|
||||
debug = 2
|
||||
|
@ -19,3 +19,6 @@ cortex-m = { version = "0.7.6", features = ["inline-asm", "critical-section-sing
|
||||
cortex-m-rt = "0.7.0"
|
||||
panic-probe = { version = "0.3", features = ["print-defmt"] }
|
||||
futures = { version = "0.3.17", default-features = false, features = ["async-await"] }
|
||||
|
||||
[profile.release]
|
||||
debug = 2
|
||||
|
@ -57,5 +57,5 @@ embedded-hal-async = { version = "0.2.0-alpha.2", optional = true }
|
||||
num-integer = { version = "0.1.45", default-features = false }
|
||||
microfft = "0.5.0"
|
||||
|
||||
[patch.crates-io]
|
||||
lora-phy = { git = "https://github.com/embassy-rs/lora-phy", rev = "ad289428fd44b02788e2fa2116445cc8f640a265" }
|
||||
[profile.release]
|
||||
debug = 2
|
||||
|
@ -53,3 +53,6 @@ rand = { version = "0.8.4", default-features = false }
|
||||
embedded-storage = "0.3.0"
|
||||
usbd-hid = "0.6.0"
|
||||
serde = { version = "1.0.136", default-features = false }
|
||||
|
||||
[profile.release]
|
||||
debug = 2
|
||||
|
@ -53,7 +53,4 @@ pio = "0.2.1"
|
||||
rand = { version = "0.8.5", default-features = false }
|
||||
|
||||
[profile.release]
|
||||
debug = true
|
||||
|
||||
[patch.crates-io]
|
||||
lora-phy = { git = "https://github.com/embassy-rs/lora-phy", rev = "ad289428fd44b02788e2fa2116445cc8f640a265" }
|
||||
debug = 2
|
||||
|
@ -8,7 +8,6 @@ use embassy_executor::Spawner;
|
||||
use embassy_rp::bind_interrupts;
|
||||
use embassy_rp::peripherals::PIO0;
|
||||
use embassy_rp::pio::{Common, Config, InterruptHandler, Irq, Pio, PioPin, ShiftDirection, StateMachine};
|
||||
use embassy_rp::relocate::RelocatedProgram;
|
||||
use fixed::traits::ToFixed;
|
||||
use fixed_macro::types::U56F8;
|
||||
use {defmt_rtt as _, panic_probe as _};
|
||||
@ -29,9 +28,8 @@ fn setup_pio_task_sm0<'a>(pio: &mut Common<'a, PIO0>, sm: &mut StateMachine<'a,
|
||||
".wrap",
|
||||
);
|
||||
|
||||
let relocated = RelocatedProgram::new(&prg.program);
|
||||
let mut cfg = Config::default();
|
||||
cfg.use_program(&pio.load_program(&relocated), &[]);
|
||||
cfg.use_program(&pio.load_program(&prg.program), &[]);
|
||||
let out_pin = pio.make_pio_pin(pin);
|
||||
cfg.set_out_pins(&[&out_pin]);
|
||||
cfg.set_set_pins(&[&out_pin]);
|
||||
@ -65,9 +63,8 @@ fn setup_pio_task_sm1<'a>(pio: &mut Common<'a, PIO0>, sm: &mut StateMachine<'a,
|
||||
".wrap",
|
||||
);
|
||||
|
||||
let relocated = RelocatedProgram::new(&prg.program);
|
||||
let mut cfg = Config::default();
|
||||
cfg.use_program(&pio.load_program(&relocated), &[]);
|
||||
cfg.use_program(&pio.load_program(&prg.program), &[]);
|
||||
cfg.clock_divider = (U56F8!(125_000_000) / 2000).to_fixed();
|
||||
cfg.shift_in.auto_fill = true;
|
||||
cfg.shift_in.direction = ShiftDirection::Right;
|
||||
@ -96,9 +93,8 @@ fn setup_pio_task_sm2<'a>(pio: &mut Common<'a, PIO0>, sm: &mut StateMachine<'a,
|
||||
"irq 3 [15]",
|
||||
".wrap",
|
||||
);
|
||||
let relocated = RelocatedProgram::new(&prg.program);
|
||||
let mut cfg = Config::default();
|
||||
cfg.use_program(&pio.load_program(&relocated), &[]);
|
||||
cfg.use_program(&pio.load_program(&prg.program), &[]);
|
||||
cfg.clock_divider = (U56F8!(125_000_000) / 2000).to_fixed();
|
||||
sm.set_config(&cfg);
|
||||
}
|
||||
|
@ -8,7 +8,6 @@ use embassy_executor::Spawner;
|
||||
use embassy_futures::join::join;
|
||||
use embassy_rp::peripherals::PIO0;
|
||||
use embassy_rp::pio::{Config, InterruptHandler, Pio, ShiftConfig, ShiftDirection};
|
||||
use embassy_rp::relocate::RelocatedProgram;
|
||||
use embassy_rp::{bind_interrupts, Peripheral};
|
||||
use fixed::traits::ToFixed;
|
||||
use fixed_macro::types::U56F8;
|
||||
@ -46,9 +45,8 @@ async fn main(_spawner: Spawner) {
|
||||
".wrap",
|
||||
);
|
||||
|
||||
let relocated = RelocatedProgram::new(&prg.program);
|
||||
let mut cfg = Config::default();
|
||||
cfg.use_program(&common.load_program(&relocated), &[]);
|
||||
cfg.use_program(&common.load_program(&prg.program), &[]);
|
||||
cfg.clock_divider = (U56F8!(125_000_000) / U56F8!(10_000)).to_fixed();
|
||||
cfg.shift_in = ShiftConfig {
|
||||
auto_fill: true,
|
||||
|
@ -14,7 +14,6 @@ use embassy_rp::pio::{
|
||||
Config, Direction, FifoJoin, InterruptHandler, Pio, PioPin, ShiftConfig, ShiftDirection, StateMachine,
|
||||
};
|
||||
use embassy_rp::pwm::{self, Pwm};
|
||||
use embassy_rp::relocate::RelocatedProgram;
|
||||
use embassy_rp::{bind_interrupts, into_ref, Peripheral, PeripheralRef};
|
||||
use embassy_time::{Duration, Instant, Timer};
|
||||
use {defmt_rtt as _, panic_probe as _};
|
||||
@ -127,9 +126,8 @@ impl<'l> HD44780<'l> {
|
||||
|
||||
sm0.set_pin_dirs(Direction::Out, &[&rs, &rw, &e, &db4, &db5, &db6, &db7]);
|
||||
|
||||
let relocated = RelocatedProgram::new(&prg.program);
|
||||
let mut cfg = Config::default();
|
||||
cfg.use_program(&common.load_program(&relocated), &[&e]);
|
||||
cfg.use_program(&common.load_program(&prg.program), &[&e]);
|
||||
cfg.clock_divider = 125u8.into();
|
||||
cfg.set_out_pins(&[&db4, &db5, &db6, &db7]);
|
||||
cfg.shift_out = ShiftConfig {
|
||||
@ -201,9 +199,8 @@ impl<'l> HD44780<'l> {
|
||||
"#
|
||||
);
|
||||
|
||||
let relocated = RelocatedProgram::new(&prg.program);
|
||||
let mut cfg = Config::default();
|
||||
cfg.use_program(&common.load_program(&relocated), &[&e]);
|
||||
cfg.use_program(&common.load_program(&prg.program), &[&e]);
|
||||
cfg.clock_divider = 8u8.into(); // ~64ns/insn
|
||||
cfg.set_jmp_pin(&db7);
|
||||
cfg.set_set_pins(&[&rs, &rw]);
|
||||
|
392
examples/rp/src/bin/pio_uart.rs
Normal file
392
examples/rp/src/bin/pio_uart.rs
Normal file
@ -0,0 +1,392 @@
|
||||
//! This example shows how to use the PIO module in the RP2040 chip to implement a duplex UART.
|
||||
//! The PIO module is a very powerful peripheral that can be used to implement many different
|
||||
//! protocols. It is a very flexible state machine that can be programmed to do almost anything.
|
||||
//!
|
||||
//! This example opens up a USB device that implements a CDC ACM serial port. It then uses the
|
||||
//! PIO module to implement a UART that is connected to the USB serial port. This allows you to
|
||||
//! communicate with a device connected to the RP2040 over USB serial.
|
||||
|
||||
#![no_std]
|
||||
#![no_main]
|
||||
#![feature(type_alias_impl_trait)]
|
||||
#![feature(async_fn_in_trait)]
|
||||
|
||||
use defmt::{info, panic, trace};
|
||||
use embassy_executor::Spawner;
|
||||
use embassy_futures::join::{join, join3};
|
||||
use embassy_rp::bind_interrupts;
|
||||
use embassy_rp::peripherals::{PIO0, USB};
|
||||
use embassy_rp::pio::InterruptHandler as PioInterruptHandler;
|
||||
use embassy_rp::usb::{Driver, Instance, InterruptHandler};
|
||||
use embassy_sync::blocking_mutex::raw::NoopRawMutex;
|
||||
use embassy_sync::pipe::Pipe;
|
||||
use embassy_usb::class::cdc_acm::{CdcAcmClass, Receiver, Sender, State};
|
||||
use embassy_usb::driver::EndpointError;
|
||||
use embassy_usb::{Builder, Config};
|
||||
use embedded_io::asynch::{Read, Write};
|
||||
use {defmt_rtt as _, panic_probe as _};
|
||||
|
||||
use crate::uart::PioUart;
|
||||
use crate::uart_rx::PioUartRx;
|
||||
use crate::uart_tx::PioUartTx;
|
||||
|
||||
bind_interrupts!(struct Irqs {
|
||||
USBCTRL_IRQ => InterruptHandler<USB>;
|
||||
PIO0_IRQ_0 => PioInterruptHandler<PIO0>;
|
||||
});
|
||||
|
||||
#[embassy_executor::main]
|
||||
async fn main(_spawner: Spawner) {
|
||||
info!("Hello there!");
|
||||
|
||||
let p = embassy_rp::init(Default::default());
|
||||
|
||||
// Create the driver, from the HAL.
|
||||
let driver = Driver::new(p.USB, Irqs);
|
||||
|
||||
// Create embassy-usb Config
|
||||
let mut config = Config::new(0xc0de, 0xcafe);
|
||||
config.manufacturer = Some("Embassy");
|
||||
config.product = Some("PIO UART example");
|
||||
config.serial_number = Some("12345678");
|
||||
config.max_power = 100;
|
||||
config.max_packet_size_0 = 64;
|
||||
|
||||
// Required for windows compatibility.
|
||||
// https://developer.nordicsemi.com/nRF_Connect_SDK/doc/1.9.1/kconfig/CONFIG_CDC_ACM_IAD.html#help
|
||||
config.device_class = 0xEF;
|
||||
config.device_sub_class = 0x02;
|
||||
config.device_protocol = 0x01;
|
||||
config.composite_with_iads = true;
|
||||
|
||||
// Create embassy-usb DeviceBuilder using the driver and config.
|
||||
// It needs some buffers for building the descriptors.
|
||||
let mut device_descriptor = [0; 256];
|
||||
let mut config_descriptor = [0; 256];
|
||||
let mut bos_descriptor = [0; 256];
|
||||
let mut control_buf = [0; 64];
|
||||
|
||||
let mut state = State::new();
|
||||
|
||||
let mut builder = Builder::new(
|
||||
driver,
|
||||
config,
|
||||
&mut device_descriptor,
|
||||
&mut config_descriptor,
|
||||
&mut bos_descriptor,
|
||||
&mut control_buf,
|
||||
);
|
||||
|
||||
// Create classes on the builder.
|
||||
let class = CdcAcmClass::new(&mut builder, &mut state, 64);
|
||||
|
||||
// Build the builder.
|
||||
let mut usb = builder.build();
|
||||
|
||||
// Run the USB device.
|
||||
let usb_fut = usb.run();
|
||||
|
||||
// PIO UART setup
|
||||
let uart = PioUart::new(9600, p.PIO0, p.PIN_4, p.PIN_5);
|
||||
let (mut uart_tx, mut uart_rx) = uart.split();
|
||||
|
||||
// Pipe setup
|
||||
let usb_pipe: Pipe<NoopRawMutex, 20> = Pipe::new();
|
||||
let mut usb_pipe_writer = usb_pipe.writer();
|
||||
let mut usb_pipe_reader = usb_pipe.reader();
|
||||
|
||||
let uart_pipe: Pipe<NoopRawMutex, 20> = Pipe::new();
|
||||
let mut uart_pipe_writer = uart_pipe.writer();
|
||||
let mut uart_pipe_reader = uart_pipe.reader();
|
||||
|
||||
let (mut usb_tx, mut usb_rx) = class.split();
|
||||
|
||||
// Read + write from USB
|
||||
let usb_future = async {
|
||||
loop {
|
||||
info!("Wait for USB connection");
|
||||
usb_rx.wait_connection().await;
|
||||
info!("Connected");
|
||||
let _ = join(
|
||||
usb_read(&mut usb_rx, &mut uart_pipe_writer),
|
||||
usb_write(&mut usb_tx, &mut usb_pipe_reader),
|
||||
)
|
||||
.await;
|
||||
info!("Disconnected");
|
||||
}
|
||||
};
|
||||
|
||||
// Read + write from UART
|
||||
let uart_future = join(
|
||||
uart_read(&mut uart_rx, &mut usb_pipe_writer),
|
||||
uart_write(&mut uart_tx, &mut uart_pipe_reader),
|
||||
);
|
||||
|
||||
// Run everything concurrently.
|
||||
// If we had made everything `'static` above instead, we could do this using separate tasks instead.
|
||||
join3(usb_fut, usb_future, uart_future).await;
|
||||
}
|
||||
|
||||
struct Disconnected {}
|
||||
|
||||
impl From<EndpointError> for Disconnected {
|
||||
fn from(val: EndpointError) -> Self {
|
||||
match val {
|
||||
EndpointError::BufferOverflow => panic!("Buffer overflow"),
|
||||
EndpointError::Disabled => Disconnected {},
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/// Read from the USB and write it to the UART TX pipe
|
||||
async fn usb_read<'d, T: Instance + 'd>(
|
||||
usb_rx: &mut Receiver<'d, Driver<'d, T>>,
|
||||
uart_pipe_writer: &mut embassy_sync::pipe::Writer<'_, NoopRawMutex, 20>,
|
||||
) -> Result<(), Disconnected> {
|
||||
let mut buf = [0; 64];
|
||||
loop {
|
||||
let n = usb_rx.read_packet(&mut buf).await?;
|
||||
let data = &buf[..n];
|
||||
trace!("USB IN: {:x}", data);
|
||||
uart_pipe_writer.write(data).await;
|
||||
}
|
||||
}
|
||||
|
||||
/// Read from the USB TX pipe and write it to the USB
|
||||
async fn usb_write<'d, T: Instance + 'd>(
|
||||
usb_tx: &mut Sender<'d, Driver<'d, T>>,
|
||||
usb_pipe_reader: &mut embassy_sync::pipe::Reader<'_, NoopRawMutex, 20>,
|
||||
) -> Result<(), Disconnected> {
|
||||
let mut buf = [0; 64];
|
||||
loop {
|
||||
let n = usb_pipe_reader.read(&mut buf).await;
|
||||
let data = &buf[..n];
|
||||
trace!("USB OUT: {:x}", data);
|
||||
usb_tx.write_packet(&data).await?;
|
||||
}
|
||||
}
|
||||
|
||||
/// Read from the UART and write it to the USB TX pipe
|
||||
async fn uart_read(
|
||||
uart_rx: &mut PioUartRx<'_>,
|
||||
usb_pipe_writer: &mut embassy_sync::pipe::Writer<'_, NoopRawMutex, 20>,
|
||||
) -> ! {
|
||||
let mut buf = [0; 64];
|
||||
loop {
|
||||
let n = uart_rx.read(&mut buf).await.expect("UART read error");
|
||||
if n == 0 {
|
||||
continue;
|
||||
}
|
||||
let data = &buf[..n];
|
||||
trace!("UART IN: {:x}", buf);
|
||||
usb_pipe_writer.write(data).await;
|
||||
}
|
||||
}
|
||||
|
||||
/// Read from the UART TX pipe and write it to the UART
|
||||
async fn uart_write(
|
||||
uart_tx: &mut PioUartTx<'_>,
|
||||
uart_pipe_reader: &mut embassy_sync::pipe::Reader<'_, NoopRawMutex, 20>,
|
||||
) -> ! {
|
||||
let mut buf = [0; 64];
|
||||
loop {
|
||||
let n = uart_pipe_reader.read(&mut buf).await;
|
||||
let data = &buf[..n];
|
||||
trace!("UART OUT: {:x}", data);
|
||||
let _ = uart_tx.write(&data).await;
|
||||
}
|
||||
}
|
||||
|
||||
mod uart {
|
||||
use embassy_rp::peripherals::PIO0;
|
||||
use embassy_rp::pio::{Pio, PioPin};
|
||||
use embassy_rp::Peripheral;
|
||||
|
||||
use crate::uart_rx::PioUartRx;
|
||||
use crate::uart_tx::PioUartTx;
|
||||
use crate::Irqs;
|
||||
|
||||
pub struct PioUart<'a> {
|
||||
tx: PioUartTx<'a>,
|
||||
rx: PioUartRx<'a>,
|
||||
}
|
||||
|
||||
impl<'a> PioUart<'a> {
|
||||
pub fn new(
|
||||
baud: u64,
|
||||
pio: impl Peripheral<P = PIO0> + 'a,
|
||||
tx_pin: impl PioPin,
|
||||
rx_pin: impl PioPin,
|
||||
) -> PioUart<'a> {
|
||||
let Pio {
|
||||
mut common, sm0, sm1, ..
|
||||
} = Pio::new(pio, Irqs);
|
||||
|
||||
let tx = PioUartTx::new(&mut common, sm0, tx_pin, baud);
|
||||
let rx = PioUartRx::new(&mut common, sm1, rx_pin, baud);
|
||||
|
||||
PioUart { tx, rx }
|
||||
}
|
||||
|
||||
pub fn split(self) -> (PioUartTx<'a>, PioUartRx<'a>) {
|
||||
(self.tx, self.rx)
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
mod uart_tx {
|
||||
use core::convert::Infallible;
|
||||
|
||||
use embassy_rp::gpio::Level;
|
||||
use embassy_rp::peripherals::PIO0;
|
||||
use embassy_rp::pio::{Common, Config, Direction, FifoJoin, PioPin, ShiftDirection, StateMachine};
|
||||
use embedded_io::asynch::Write;
|
||||
use embedded_io::Io;
|
||||
use fixed::traits::ToFixed;
|
||||
use fixed_macro::types::U56F8;
|
||||
|
||||
pub struct PioUartTx<'a> {
|
||||
sm_tx: StateMachine<'a, PIO0, 0>,
|
||||
}
|
||||
|
||||
impl<'a> PioUartTx<'a> {
|
||||
pub fn new(
|
||||
common: &mut Common<'a, PIO0>,
|
||||
mut sm_tx: StateMachine<'a, PIO0, 0>,
|
||||
tx_pin: impl PioPin,
|
||||
baud: u64,
|
||||
) -> Self {
|
||||
let prg = pio_proc::pio_asm!(
|
||||
r#"
|
||||
.side_set 1 opt
|
||||
|
||||
; An 8n1 UART transmit program.
|
||||
; OUT pin 0 and side-set pin 0 are both mapped to UART TX pin.
|
||||
|
||||
pull side 1 [7] ; Assert stop bit, or stall with line in idle state
|
||||
set x, 7 side 0 [7] ; Preload bit counter, assert start bit for 8 clocks
|
||||
bitloop: ; This loop will run 8 times (8n1 UART)
|
||||
out pins, 1 ; Shift 1 bit from OSR to the first OUT pin
|
||||
jmp x-- bitloop [6] ; Each loop iteration is 8 cycles.
|
||||
"#
|
||||
);
|
||||
let tx_pin = common.make_pio_pin(tx_pin);
|
||||
sm_tx.set_pins(Level::High, &[&tx_pin]);
|
||||
sm_tx.set_pin_dirs(Direction::Out, &[&tx_pin]);
|
||||
|
||||
let mut cfg = Config::default();
|
||||
|
||||
cfg.set_out_pins(&[&tx_pin]);
|
||||
cfg.use_program(&common.load_program(&prg.program), &[&tx_pin]);
|
||||
cfg.shift_out.auto_fill = false;
|
||||
cfg.shift_out.direction = ShiftDirection::Right;
|
||||
cfg.fifo_join = FifoJoin::TxOnly;
|
||||
cfg.clock_divider = (U56F8!(125_000_000) / (8 * baud)).to_fixed();
|
||||
sm_tx.set_config(&cfg);
|
||||
sm_tx.set_enable(true);
|
||||
|
||||
Self { sm_tx }
|
||||
}
|
||||
|
||||
pub async fn write_u8(&mut self, data: u8) {
|
||||
self.sm_tx.tx().wait_push(data as u32).await;
|
||||
}
|
||||
}
|
||||
|
||||
impl Io for PioUartTx<'_> {
|
||||
type Error = Infallible;
|
||||
}
|
||||
|
||||
impl Write for PioUartTx<'_> {
|
||||
async fn write(&mut self, buf: &[u8]) -> Result<usize, Infallible> {
|
||||
for byte in buf {
|
||||
self.write_u8(*byte).await;
|
||||
}
|
||||
Ok(buf.len())
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
mod uart_rx {
|
||||
use core::convert::Infallible;
|
||||
|
||||
use embassy_rp::gpio::Level;
|
||||
use embassy_rp::peripherals::PIO0;
|
||||
use embassy_rp::pio::{Common, Config, Direction, FifoJoin, PioPin, ShiftDirection, StateMachine};
|
||||
use embedded_io::asynch::Read;
|
||||
use embedded_io::Io;
|
||||
use fixed::traits::ToFixed;
|
||||
use fixed_macro::types::U56F8;
|
||||
|
||||
pub struct PioUartRx<'a> {
|
||||
sm_rx: StateMachine<'a, PIO0, 1>,
|
||||
}
|
||||
|
||||
impl<'a> PioUartRx<'a> {
|
||||
pub fn new(
|
||||
common: &mut Common<'a, PIO0>,
|
||||
mut sm_rx: StateMachine<'a, PIO0, 1>,
|
||||
rx_pin: impl PioPin,
|
||||
baud: u64,
|
||||
) -> Self {
|
||||
let prg = pio_proc::pio_asm!(
|
||||
r#"
|
||||
; Slightly more fleshed-out 8n1 UART receiver which handles framing errors and
|
||||
; break conditions more gracefully.
|
||||
; IN pin 0 and JMP pin are both mapped to the GPIO used as UART RX.
|
||||
|
||||
start:
|
||||
wait 0 pin 0 ; Stall until start bit is asserted
|
||||
set x, 7 [10] ; Preload bit counter, then delay until halfway through
|
||||
rx_bitloop: ; the first data bit (12 cycles incl wait, set).
|
||||
in pins, 1 ; Shift data bit into ISR
|
||||
jmp x-- rx_bitloop [6] ; Loop 8 times, each loop iteration is 8 cycles
|
||||
jmp pin good_rx_stop ; Check stop bit (should be high)
|
||||
|
||||
irq 4 rel ; Either a framing error or a break. Set a sticky flag,
|
||||
wait 1 pin 0 ; and wait for line to return to idle state.
|
||||
jmp start ; Don't push data if we didn't see good framing.
|
||||
|
||||
good_rx_stop: ; No delay before returning to start; a little slack is
|
||||
push ; important in case the TX clock is slightly too fast.
|
||||
"#
|
||||
);
|
||||
let mut cfg = Config::default();
|
||||
cfg.use_program(&common.load_program(&prg.program), &[]);
|
||||
|
||||
let rx_pin = common.make_pio_pin(rx_pin);
|
||||
sm_rx.set_pins(Level::High, &[&rx_pin]);
|
||||
cfg.set_in_pins(&[&rx_pin]);
|
||||
cfg.set_jmp_pin(&rx_pin);
|
||||
sm_rx.set_pin_dirs(Direction::In, &[&rx_pin]);
|
||||
|
||||
cfg.clock_divider = (U56F8!(125_000_000) / (8 * baud)).to_fixed();
|
||||
cfg.shift_out.auto_fill = false;
|
||||
cfg.shift_out.direction = ShiftDirection::Right;
|
||||
cfg.fifo_join = FifoJoin::RxOnly;
|
||||
sm_rx.set_config(&cfg);
|
||||
sm_rx.set_enable(true);
|
||||
|
||||
Self { sm_rx }
|
||||
}
|
||||
|
||||
pub async fn read_u8(&mut self) -> u8 {
|
||||
self.sm_rx.rx().wait_pull().await as u8
|
||||
}
|
||||
}
|
||||
|
||||
impl Io for PioUartRx<'_> {
|
||||
type Error = Infallible;
|
||||
}
|
||||
|
||||
impl Read for PioUartRx<'_> {
|
||||
async fn read(&mut self, buf: &mut [u8]) -> Result<usize, Infallible> {
|
||||
let mut i = 0;
|
||||
while i < buf.len() {
|
||||
buf[i] = self.read_u8().await;
|
||||
i += 1;
|
||||
}
|
||||
Ok(i)
|
||||
}
|
||||
}
|
||||
}
|
@ -12,7 +12,6 @@ use embassy_rp::peripherals::PIO0;
|
||||
use embassy_rp::pio::{
|
||||
Common, Config, FifoJoin, Instance, InterruptHandler, Pio, PioPin, ShiftConfig, ShiftDirection, StateMachine,
|
||||
};
|
||||
use embassy_rp::relocate::RelocatedProgram;
|
||||
use embassy_rp::{bind_interrupts, clocks, into_ref, Peripheral, PeripheralRef};
|
||||
use embassy_time::{Duration, Timer};
|
||||
use fixed::types::U24F8;
|
||||
@ -73,8 +72,7 @@ impl<'d, P: Instance, const S: usize, const N: usize> Ws2812<'d, P, S, N> {
|
||||
cfg.set_out_pins(&[&out_pin]);
|
||||
cfg.set_set_pins(&[&out_pin]);
|
||||
|
||||
let relocated = RelocatedProgram::new(&prg);
|
||||
cfg.use_program(&pio.load_program(&relocated), &[&out_pin]);
|
||||
cfg.use_program(&pio.load_program(&prg), &[&out_pin]);
|
||||
|
||||
// Clock config, measured in kHz to avoid overflows
|
||||
// TODO CLOCK_FREQ should come from embassy_rp
|
||||
|
@ -23,3 +23,6 @@ clap = { version = "3.0.0-beta.5", features = ["derive"] }
|
||||
rand_core = { version = "0.6.3", features = ["std"] }
|
||||
heapless = { version = "0.7.5", default-features = false }
|
||||
static_cell = { version = "1.1", features = ["nightly"]}
|
||||
|
||||
[profile.release]
|
||||
debug = 2
|
||||
|
@ -5,10 +5,11 @@ version = "0.1.0"
|
||||
license = "MIT OR Apache-2.0"
|
||||
|
||||
[dependencies]
|
||||
# Change stm32c031c6 to your chip name, if necessary.
|
||||
embassy-stm32 = { version = "0.1.0", path = "../../embassy-stm32", features = ["nightly", "defmt", "time-driver-any", "stm32c031c6", "memory-x", "unstable-pac", "exti"] }
|
||||
embassy-sync = { version = "0.2.0", path = "../../embassy-sync", features = ["defmt"] }
|
||||
embassy-executor = { version = "0.2.0", path = "../../embassy-executor", features = ["nightly", "arch-cortex-m", "executor-thread", "defmt", "integrated-timers"] }
|
||||
embassy-time = { version = "0.1.2", path = "../../embassy-time", features = ["defmt", "defmt-timestamp-uptime", "tick-hz-32_768"] }
|
||||
embassy-stm32 = { version = "0.1.0", path = "../../embassy-stm32", features = ["nightly", "defmt", "time-driver-any", "stm32c031c6", "memory-x", "unstable-pac", "exti"] }
|
||||
|
||||
defmt = "0.3"
|
||||
defmt-rtt = "0.4"
|
||||
@ -19,3 +20,6 @@ embedded-hal = "0.2.6"
|
||||
panic-probe = { version = "0.3", features = ["print-defmt"] }
|
||||
futures = { version = "0.3.17", default-features = false, features = ["async-await"] }
|
||||
heapless = { version = "0.7.5", default-features = false }
|
||||
|
||||
[profile.release]
|
||||
debug = 2
|
||||
|
@ -7,6 +7,8 @@ license = "MIT OR Apache-2.0"
|
||||
# See more keys and their definitions at https://doc.rust-lang.org/cargo/reference/manifest.html
|
||||
|
||||
[dependencies]
|
||||
# Change stm32f091rc to your chip name, if necessary.
|
||||
embassy-stm32 = { version = "0.1.0", path = "../../embassy-stm32", features = ["nightly", "defmt", "memory-x", "stm32f091rc", "time-driver-any", "exti", "unstable-pac"] }
|
||||
cortex-m = { version = "0.7.6", features = ["inline-asm", "critical-section-single-core"] }
|
||||
cortex-m-rt = "0.7.0"
|
||||
defmt = "0.3"
|
||||
@ -15,5 +17,7 @@ panic-probe = "0.3"
|
||||
embassy-sync = { version = "0.2.0", path = "../../embassy-sync", features = ["defmt"] }
|
||||
embassy-executor = { version = "0.2.0", path = "../../embassy-executor", features = ["nightly", "arch-cortex-m", "executor-thread", "executor-interrupt", "defmt", "integrated-timers"] }
|
||||
embassy-time = { version = "0.1.2", path = "../../embassy-time", features = ["defmt", "defmt-timestamp-uptime", "tick-hz-32_768"] }
|
||||
embassy-stm32 = { version = "0.1.0", path = "../../embassy-stm32", features = ["nightly", "defmt", "memory-x", "stm32f091rc", "time-driver-any", "exti", "unstable-pac"] }
|
||||
static_cell = { version = "1.1", features = ["nightly"]}
|
||||
|
||||
[profile.release]
|
||||
debug = 2
|
||||
|
@ -5,10 +5,11 @@ version = "0.1.0"
|
||||
license = "MIT OR Apache-2.0"
|
||||
|
||||
[dependencies]
|
||||
# Change stm32f103c8 to your chip name, if necessary.
|
||||
embassy-stm32 = { version = "0.1.0", path = "../../embassy-stm32", features = ["nightly", "defmt", "stm32f103c8", "unstable-pac", "memory-x", "time-driver-any", "unstable-traits" ] }
|
||||
embassy-sync = { version = "0.2.0", path = "../../embassy-sync", features = ["defmt"] }
|
||||
embassy-executor = { version = "0.2.0", path = "../../embassy-executor", features = ["nightly", "arch-cortex-m", "executor-thread", "defmt", "integrated-timers"] }
|
||||
embassy-time = { version = "0.1.2", path = "../../embassy-time", features = ["defmt", "defmt-timestamp-uptime", "tick-hz-32_768"] }
|
||||
embassy-stm32 = { version = "0.1.0", path = "../../embassy-stm32", features = ["nightly", "defmt", "stm32f103c8", "unstable-pac", "memory-x", "time-driver-any", "unstable-traits" ] }
|
||||
embassy-usb = { version = "0.1.0", path = "../../embassy-usb", features = ["defmt"] }
|
||||
embassy-futures = { version = "0.1.0", path = "../../embassy-futures" }
|
||||
|
||||
@ -25,3 +26,6 @@ nb = "1.0.0"
|
||||
|
||||
[profile.dev]
|
||||
opt-level = "s"
|
||||
|
||||
[profile.release]
|
||||
debug = 2
|
||||
|
@ -5,10 +5,11 @@ version = "0.1.0"
|
||||
license = "MIT OR Apache-2.0"
|
||||
|
||||
[dependencies]
|
||||
# Change stm32f207zg to your chip name, if necessary.
|
||||
embassy-stm32 = { version = "0.1.0", path = "../../embassy-stm32", features = ["nightly", "defmt", "stm32f207zg", "unstable-pac", "memory-x", "time-driver-any", "exti"] }
|
||||
embassy-sync = { version = "0.2.0", path = "../../embassy-sync", features = ["defmt"] }
|
||||
embassy-executor = { version = "0.2.0", path = "../../embassy-executor", features = ["nightly", "arch-cortex-m", "executor-thread", "defmt", "integrated-timers"] }
|
||||
embassy-time = { version = "0.1.2", path = "../../embassy-time", features = ["defmt", "defmt-timestamp-uptime", "tick-hz-32_768"] }
|
||||
embassy-stm32 = { version = "0.1.0", path = "../../embassy-stm32", features = ["nightly", "defmt", "stm32f207zg", "unstable-pac", "memory-x", "time-driver-any", "exti"] }
|
||||
|
||||
defmt = "0.3"
|
||||
defmt-rtt = "0.4"
|
||||
@ -20,3 +21,6 @@ panic-probe = { version = "0.3", features = ["print-defmt"] }
|
||||
futures = { version = "0.3.17", default-features = false, features = ["async-await"] }
|
||||
heapless = { version = "0.7.5", default-features = false }
|
||||
nb = "1.0.0"
|
||||
|
||||
[profile.release]
|
||||
debug = 2
|
||||
|
@ -5,10 +5,11 @@ version = "0.1.0"
|
||||
license = "MIT OR Apache-2.0"
|
||||
|
||||
[dependencies]
|
||||
# Change stm32f303ze to your chip name, if necessary.
|
||||
embassy-stm32 = { version = "0.1.0", path = "../../embassy-stm32", features = ["nightly", "defmt", "stm32f303ze", "unstable-pac", "memory-x", "time-driver-any", "exti"] }
|
||||
embassy-sync = { version = "0.2.0", path = "../../embassy-sync", features = ["defmt"] }
|
||||
embassy-executor = { version = "0.2.0", path = "../../embassy-executor", features = ["nightly", "arch-cortex-m", "executor-thread", "executor-interrupt", "defmt", "integrated-timers"] }
|
||||
embassy-time = { version = "0.1.2", path = "../../embassy-time", features = ["defmt", "defmt-timestamp-uptime", "tick-hz-32_768"] }
|
||||
embassy-stm32 = { version = "0.1.0", path = "../../embassy-stm32", features = ["nightly", "defmt", "stm32f303ze", "unstable-pac", "memory-x", "time-driver-any", "exti"] }
|
||||
embassy-usb = { version = "0.1.0", path = "../../embassy-usb", features = ["defmt"] }
|
||||
embassy-futures = { version = "0.1.0", path = "../../embassy-futures" }
|
||||
|
||||
@ -24,3 +25,6 @@ heapless = { version = "0.7.5", default-features = false }
|
||||
nb = "1.0.0"
|
||||
embedded-storage = "0.3.0"
|
||||
static_cell = { version = "1.1", features = ["nightly"]}
|
||||
|
||||
[profile.release]
|
||||
debug = 2
|
||||
|
@ -5,10 +5,11 @@ version = "0.1.0"
|
||||
license = "MIT OR Apache-2.0"
|
||||
|
||||
[dependencies]
|
||||
embassy-sync = { version = "0.2.0", path = "../../embassy-sync", features = ["defmt"] }
|
||||
embassy-executor = { version = "0.2.0", path = "../../embassy-executor", features = ["nightly", "arch-cortex-m", "executor-thread", "executor-interrupt", "defmt", "integrated-timers", "arch-cortex-m", "executor-thread", "executor-interrupt"] }
|
||||
embassy-time = { version = "0.1.2", path = "../../embassy-time", features = ["defmt", "defmt-timestamp-uptime", "unstable-traits", "tick-hz-32_768"] }
|
||||
# Change stm32f429zi to your chip name, if necessary.
|
||||
embassy-stm32 = { version = "0.1.0", path = "../../embassy-stm32", features = ["nightly", "unstable-traits", "defmt", "stm32f429zi", "unstable-pac", "memory-x", "time-driver-any", "exti", "embedded-sdmmc", "chrono"] }
|
||||
embassy-sync = { version = "0.2.0", path = "../../embassy-sync", features = ["defmt"] }
|
||||
embassy-executor = { version = "0.2.0", path = "../../embassy-executor", features = ["nightly", "arch-cortex-m", "executor-thread", "executor-interrupt", "defmt", "integrated-timers"] }
|
||||
embassy-time = { version = "0.1.2", path = "../../embassy-time", features = ["defmt", "defmt-timestamp-uptime", "unstable-traits", "tick-hz-32_768"] }
|
||||
embassy-usb = { version = "0.1.0", path = "../../embassy-usb", features = ["defmt"] }
|
||||
embassy-net = { version = "0.1.0", path = "../../embassy-net", features = ["defmt", "tcp", "dhcpv4", "medium-ethernet", "nightly"] }
|
||||
|
||||
|
@ -40,10 +40,13 @@ async fn main(_spawner: Spawner) {
|
||||
|
||||
can.as_mut()
|
||||
.modify_config()
|
||||
.set_bit_timing(0x001c0003) // http://www.bittiming.can-wiki.info/
|
||||
.set_loopback(true) // Receive own frames
|
||||
.set_silent(true)
|
||||
.enable();
|
||||
.leave_disabled();
|
||||
|
||||
can.set_bitrate(1_000_000);
|
||||
|
||||
can.enable().await;
|
||||
|
||||
let mut i: u8 = 0;
|
||||
loop {
|
||||
|
@ -14,11 +14,11 @@ async fn main(_spawner: Spawner) -> ! {
|
||||
info!("Hello World, dude!");
|
||||
|
||||
let mut dac = DacCh1::new(p.DAC, NoDma, p.PA4);
|
||||
unwrap!(dac.set_trigger_enable(false));
|
||||
|
||||
loop {
|
||||
for v in 0..=255 {
|
||||
unwrap!(dac.set(Value::Bit8(to_sine_wave(v))));
|
||||
dac.trigger();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -4,9 +4,9 @@
|
||||
|
||||
use defmt::*;
|
||||
use embassy_executor::Spawner;
|
||||
use embassy_stm32::pwm::simple_pwm::{PwmPin, SimplePwm};
|
||||
use embassy_stm32::pwm::Channel;
|
||||
use embassy_stm32::time::khz;
|
||||
use embassy_stm32::timer::simple_pwm::{PwmPin, SimplePwm};
|
||||
use embassy_stm32::timer::Channel;
|
||||
use embassy_time::{Duration, Timer};
|
||||
use {defmt_rtt as _, panic_probe as _};
|
||||
|
||||
|
@ -4,10 +4,10 @@
|
||||
|
||||
use defmt::*;
|
||||
use embassy_executor::Spawner;
|
||||
use embassy_stm32::pwm::complementary_pwm::{ComplementaryPwm, ComplementaryPwmPin};
|
||||
use embassy_stm32::pwm::simple_pwm::PwmPin;
|
||||
use embassy_stm32::pwm::Channel;
|
||||
use embassy_stm32::time::khz;
|
||||
use embassy_stm32::timer::complementary_pwm::{ComplementaryPwm, ComplementaryPwmPin};
|
||||
use embassy_stm32::timer::simple_pwm::PwmPin;
|
||||
use embassy_stm32::timer::Channel;
|
||||
use embassy_time::{Duration, Timer};
|
||||
use {defmt_rtt as _, panic_probe as _};
|
||||
|
||||
|
@ -5,10 +5,11 @@ version = "0.1.0"
|
||||
license = "MIT OR Apache-2.0"
|
||||
|
||||
[dependencies]
|
||||
# Change stm32f767zi to your chip name, if necessary.
|
||||
embassy-stm32 = { version = "0.1.0", path = "../../embassy-stm32", features = ["nightly", "defmt", "stm32f767zi", "memory-x", "unstable-pac", "time-driver-any", "exti"] }
|
||||
embassy-sync = { version = "0.2.0", path = "../../embassy-sync", features = ["defmt"] }
|
||||
embassy-executor = { version = "0.2.0", path = "../../embassy-executor", features = ["nightly", "arch-cortex-m", "executor-thread", "defmt", "integrated-timers"] }
|
||||
embassy-time = { version = "0.1.2", path = "../../embassy-time", features = ["defmt", "defmt-timestamp-uptime", "tick-hz-32_768"] }
|
||||
embassy-stm32 = { version = "0.1.0", path = "../../embassy-stm32", features = ["nightly", "defmt", "stm32f767zi", "unstable-pac", "time-driver-any", "exti"] }
|
||||
embassy-net = { path = "../../embassy-net", features = ["defmt", "nightly", "tcp", "dhcpv4", "medium-ethernet"] }
|
||||
embedded-io = { version = "0.4.0", features = ["async"] }
|
||||
embassy-usb = { version = "0.1.0", path = "../../embassy-usb", features = ["defmt"] }
|
||||
@ -27,3 +28,6 @@ rand_core = "0.6.3"
|
||||
critical-section = "1.1"
|
||||
embedded-storage = "0.3.0"
|
||||
static_cell = { version = "1.1", features = ["nightly"]}
|
||||
|
||||
[profile.release]
|
||||
debug = 2
|
||||
|
@ -1,43 +1,5 @@
|
||||
//! adapted from https://github.com/stm32-rs/stm32f7xx-hal/blob/master/build.rs
|
||||
use std::fs::File;
|
||||
use std::io::prelude::*;
|
||||
use std::path::PathBuf;
|
||||
use std::{env, io};
|
||||
|
||||
#[derive(Debug)]
|
||||
enum Error {
|
||||
Env(env::VarError),
|
||||
Io(io::Error),
|
||||
}
|
||||
|
||||
impl From<env::VarError> for Error {
|
||||
fn from(error: env::VarError) -> Self {
|
||||
Self::Env(error)
|
||||
}
|
||||
}
|
||||
|
||||
impl From<io::Error> for Error {
|
||||
fn from(error: io::Error) -> Self {
|
||||
Self::Io(error)
|
||||
}
|
||||
}
|
||||
|
||||
fn main() -> Result<(), Error> {
|
||||
println!("cargo:rerun-if-changed=build.rs");
|
||||
println!("cargo:rerun-if-changed=memory.x");
|
||||
|
||||
let out_dir = env::var("OUT_DIR")?;
|
||||
let out_dir = PathBuf::from(out_dir);
|
||||
|
||||
let memory_x = include_bytes!("memory.x").as_ref();
|
||||
File::create(out_dir.join("memory.x"))?.write_all(memory_x)?;
|
||||
|
||||
// Tell Cargo where to find the file.
|
||||
println!("cargo:rustc-link-search={}", out_dir.display());
|
||||
|
||||
fn main() {
|
||||
println!("cargo:rustc-link-arg-bins=--nmagic");
|
||||
println!("cargo:rustc-link-arg-bins=-Tlink.x");
|
||||
println!("cargo:rustc-link-arg-bins=-Tdefmt.x");
|
||||
|
||||
Ok(())
|
||||
}
|
||||
|
@ -1,12 +0,0 @@
|
||||
/* For STM32F765,767,768,769,777,778,779 devices */
|
||||
MEMORY
|
||||
{
|
||||
/* NOTE K = KiBi = 1024 bytes */
|
||||
FLASH : ORIGIN = 0x08000000, LENGTH = 2M
|
||||
RAM : ORIGIN = 0x20000000, LENGTH = 368K + 16K
|
||||
}
|
||||
|
||||
/* This is where the call stack will be allocated. */
|
||||
/* The stack is of the full descending type. */
|
||||
/* NOTE Do NOT modify `_stack_start` unless you know what you are doing */
|
||||
_stack_start = ORIGIN(RAM) + LENGTH(RAM);
|
@ -5,10 +5,11 @@ version = "0.1.0"
|
||||
license = "MIT OR Apache-2.0"
|
||||
|
||||
[dependencies]
|
||||
# Change stm32g071rb to your chip name, if necessary.
|
||||
embassy-stm32 = { version = "0.1.0", path = "../../embassy-stm32", features = ["nightly", "defmt", "time-driver-any", "stm32g071rb", "memory-x", "unstable-pac", "exti"] }
|
||||
embassy-sync = { version = "0.2.0", path = "../../embassy-sync", features = ["defmt"] }
|
||||
embassy-executor = { version = "0.2.0", path = "../../embassy-executor", features = ["nightly", "arch-cortex-m", "executor-thread", "defmt", "integrated-timers"] }
|
||||
embassy-time = { version = "0.1.2", path = "../../embassy-time", features = ["defmt", "defmt-timestamp-uptime", "tick-hz-32_768"] }
|
||||
embassy-stm32 = { version = "0.1.0", path = "../../embassy-stm32", features = ["nightly", "defmt", "time-driver-any", "stm32g071rb", "memory-x", "unstable-pac", "exti"] }
|
||||
|
||||
defmt = "0.3"
|
||||
defmt-rtt = "0.4"
|
||||
@ -19,3 +20,6 @@ embedded-hal = "0.2.6"
|
||||
panic-probe = { version = "0.3", features = ["print-defmt"] }
|
||||
futures = { version = "0.3.17", default-features = false, features = ["async-await"] }
|
||||
heapless = { version = "0.7.5", default-features = false }
|
||||
|
||||
[profile.release]
|
||||
debug = 2
|
||||
|
@ -5,11 +5,11 @@ version = "0.1.0"
|
||||
license = "MIT OR Apache-2.0"
|
||||
|
||||
[dependencies]
|
||||
# Change stm32g491re to your chip name, if necessary.
|
||||
embassy-stm32 = { version = "0.1.0", path = "../../embassy-stm32", features = ["nightly", "defmt", "time-driver-any", "stm32g491re", "memory-x", "unstable-pac", "exti"] }
|
||||
embassy-sync = { version = "0.2.0", path = "../../embassy-sync", features = ["defmt"] }
|
||||
embassy-executor = { version = "0.2.0", path = "../../embassy-executor", features = ["nightly", "arch-cortex-m", "executor-thread", "defmt", "integrated-timers"] }
|
||||
embassy-time = { version = "0.1.2", path = "../../embassy-time", features = ["defmt", "defmt-timestamp-uptime", "tick-hz-32_768"] }
|
||||
embassy-stm32 = { version = "0.1.0", path = "../../embassy-stm32", features = ["nightly", "defmt", "time-driver-any", "stm32g491re", "memory-x", "unstable-pac", "exti"] }
|
||||
embassy-hal-common = {version = "0.1.0", path = "../../embassy-hal-common" }
|
||||
embassy-usb = { version = "0.1.0", path = "../../embassy-usb", features = ["defmt"] }
|
||||
|
||||
defmt = "0.3"
|
||||
@ -21,3 +21,6 @@ embedded-hal = "0.2.6"
|
||||
panic-probe = { version = "0.3", features = ["print-defmt"] }
|
||||
futures = { version = "0.3.17", default-features = false, features = ["async-await"] }
|
||||
heapless = { version = "0.7.5", default-features = false }
|
||||
|
||||
[profile.release]
|
||||
debug = 2
|
||||
|
@ -4,9 +4,9 @@
|
||||
|
||||
use defmt::*;
|
||||
use embassy_executor::Spawner;
|
||||
use embassy_stm32::pwm::simple_pwm::{PwmPin, SimplePwm};
|
||||
use embassy_stm32::pwm::Channel;
|
||||
use embassy_stm32::time::khz;
|
||||
use embassy_stm32::timer::simple_pwm::{PwmPin, SimplePwm};
|
||||
use embassy_stm32::timer::Channel;
|
||||
use embassy_time::{Duration, Timer};
|
||||
use {defmt_rtt as _, panic_probe as _};
|
||||
|
||||
|
@ -5,10 +5,11 @@ version = "0.1.0"
|
||||
license = "MIT OR Apache-2.0"
|
||||
|
||||
[dependencies]
|
||||
# Change stm32h563zi to your chip name, if necessary.
|
||||
embassy-stm32 = { version = "0.1.0", path = "../../embassy-stm32", features = ["nightly", "defmt", "stm32h563zi", "memory-x", "time-driver-any", "exti", "unstable-pac", "unstable-traits"] }
|
||||
embassy-sync = { version = "0.2.0", path = "../../embassy-sync", features = ["defmt"] }
|
||||
embassy-executor = { version = "0.2.0", path = "../../embassy-executor", features = ["nightly", "arch-cortex-m", "executor-thread", "defmt", "integrated-timers"] }
|
||||
embassy-time = { version = "0.1.2", path = "../../embassy-time", features = ["defmt", "defmt-timestamp-uptime", "unstable-traits", "tick-hz-32_768"] }
|
||||
embassy-stm32 = { version = "0.1.0", path = "../../embassy-stm32", features = ["nightly", "defmt", "stm32h563zi", "time-driver-any", "exti", "unstable-pac", "unstable-traits"] }
|
||||
embassy-net = { path = "../../embassy-net", features = ["defmt", "nightly", "tcp", "dhcpv4", "medium-ethernet", "unstable-traits", "proto-ipv6"] }
|
||||
embedded-io = { version = "0.4.0", features = ["async"] }
|
||||
embassy-usb = { version = "0.1.0", path = "../../embassy-usb", features = ["defmt"] }
|
||||
|
@ -1,5 +0,0 @@
|
||||
MEMORY
|
||||
{
|
||||
FLASH : ORIGIN = 0x08000000, LENGTH = 0x200000
|
||||
RAM : ORIGIN = 0x20000000, LENGTH = 0x50000
|
||||
}
|
@ -1,5 +1,5 @@
|
||||
[target.thumbv7em-none-eabihf]
|
||||
runner = 'probe-rs run --chip STM32H743ZITx'
|
||||
runner = 'probe-rs run --chip STM32H7A3ZITxQ'
|
||||
|
||||
[build]
|
||||
target = "thumbv7em-none-eabihf" # Cortex-M4F and Cortex-M7F (with FPU)
|
||||
|
@ -5,10 +5,11 @@ version = "0.1.0"
|
||||
license = "MIT OR Apache-2.0"
|
||||
|
||||
[dependencies]
|
||||
# Change stm32h743bi to your chip name, if necessary.
|
||||
embassy-stm32 = { version = "0.1.0", path = "../../embassy-stm32", features = ["nightly", "defmt", "stm32h743bi", "time-driver-any", "exti", "memory-x", "unstable-pac", "unstable-traits"] }
|
||||
embassy-sync = { version = "0.2.0", path = "../../embassy-sync", features = ["defmt"] }
|
||||
embassy-executor = { version = "0.2.0", path = "../../embassy-executor", features = ["nightly", "arch-cortex-m", "executor-thread", "defmt", "integrated-timers"] }
|
||||
embassy-time = { version = "0.1.2", path = "../../embassy-time", features = ["defmt", "defmt-timestamp-uptime", "unstable-traits", "tick-hz-32_768"] }
|
||||
embassy-stm32 = { version = "0.1.0", path = "../../embassy-stm32", features = ["nightly", "defmt", "stm32h743bi", "time-driver-any", "exti", "unstable-pac", "unstable-traits"] }
|
||||
embassy-net = { path = "../../embassy-net", features = ["defmt", "nightly", "tcp", "dhcpv4", "medium-ethernet", "unstable-traits", "proto-ipv6"] }
|
||||
embedded-io = { version = "0.4.0", features = ["async"] }
|
||||
embassy-usb = { version = "0.1.0", path = "../../embassy-usb", features = ["defmt"] }
|
||||
|
@ -1,5 +0,0 @@
|
||||
MEMORY
|
||||
{
|
||||
FLASH : ORIGIN = 0x8000000, LENGTH = 1024K
|
||||
RAM : ORIGIN = 0x24000000, LENGTH = 384K
|
||||
}
|
@ -21,11 +21,11 @@ fn main() -> ! {
|
||||
let p = embassy_stm32::init(config);
|
||||
|
||||
let mut dac = DacCh1::new(p.DAC1, NoDma, p.PA4);
|
||||
unwrap!(dac.set_trigger_enable(false));
|
||||
|
||||
loop {
|
||||
for v in 0..=255 {
|
||||
unwrap!(dac.set(Value::Bit8(to_sine_wave(v))));
|
||||
dac.trigger();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
140
examples/stm32h7/src/bin/dac_dma.rs
Normal file
140
examples/stm32h7/src/bin/dac_dma.rs
Normal file
@ -0,0 +1,140 @@
|
||||
#![no_std]
|
||||
#![no_main]
|
||||
#![feature(type_alias_impl_trait)]
|
||||
|
||||
use defmt::*;
|
||||
use embassy_executor::Spawner;
|
||||
use embassy_stm32::dac::{DacChannel, ValueArray};
|
||||
use embassy_stm32::pac::timer::vals::{Mms, Opm};
|
||||
use embassy_stm32::peripherals::{TIM6, TIM7};
|
||||
use embassy_stm32::rcc::low_level::RccPeripheral;
|
||||
use embassy_stm32::time::{mhz, Hertz};
|
||||
use embassy_stm32::timer::low_level::Basic16bitInstance;
|
||||
use micromath::F32Ext;
|
||||
use {defmt_rtt as _, panic_probe as _};
|
||||
|
||||
pub type Dac1Type =
|
||||
embassy_stm32::dac::DacCh1<'static, embassy_stm32::peripherals::DAC1, embassy_stm32::peripherals::DMA1_CH3>;
|
||||
|
||||
pub type Dac2Type =
|
||||
embassy_stm32::dac::DacCh2<'static, embassy_stm32::peripherals::DAC1, embassy_stm32::peripherals::DMA1_CH4>;
|
||||
|
||||
#[embassy_executor::main]
|
||||
async fn main(spawner: Spawner) {
|
||||
let mut config = embassy_stm32::Config::default();
|
||||
config.rcc.sys_ck = Some(mhz(400));
|
||||
config.rcc.hclk = Some(mhz(100));
|
||||
config.rcc.pll1.q_ck = Some(mhz(100));
|
||||
|
||||
// Initialize the board and obtain a Peripherals instance
|
||||
let p: embassy_stm32::Peripherals = embassy_stm32::init(config);
|
||||
|
||||
// Obtain two independent channels (p.DAC1 can only be consumed once, though!)
|
||||
let (dac_ch1, dac_ch2) = embassy_stm32::dac::Dac::new(p.DAC1, p.DMA1_CH3, p.DMA1_CH4, p.PA4, p.PA5).split();
|
||||
|
||||
spawner.spawn(dac_task1(dac_ch1)).ok();
|
||||
spawner.spawn(dac_task2(dac_ch2)).ok();
|
||||
}
|
||||
|
||||
#[embassy_executor::task]
|
||||
async fn dac_task1(mut dac: Dac1Type) {
|
||||
let data: &[u8; 256] = &calculate_array::<256>();
|
||||
|
||||
info!("TIM6 frequency is {}", TIM6::frequency());
|
||||
const FREQUENCY: Hertz = Hertz::hz(200);
|
||||
|
||||
// Compute the reload value such that we obtain the FREQUENCY for the sine
|
||||
let reload: u32 = (TIM6::frequency().0 / FREQUENCY.0) / data.len() as u32;
|
||||
|
||||
// Depends on your clock and on the specific chip used, you may need higher or lower values here
|
||||
if reload < 10 {
|
||||
error!("Reload value {} below threshold!", reload);
|
||||
}
|
||||
|
||||
dac.select_trigger(embassy_stm32::dac::Ch1Trigger::Tim6).unwrap();
|
||||
dac.enable_channel().unwrap();
|
||||
|
||||
TIM6::enable();
|
||||
TIM6::regs().arr().modify(|w| w.set_arr(reload as u16 - 1));
|
||||
TIM6::regs().cr2().modify(|w| w.set_mms(Mms::UPDATE));
|
||||
TIM6::regs().cr1().modify(|w| {
|
||||
w.set_opm(Opm::DISABLED);
|
||||
w.set_cen(true);
|
||||
});
|
||||
|
||||
debug!(
|
||||
"TIM6 Frequency {}, Target Frequency {}, Reload {}, Reload as u16 {}, Samples {}",
|
||||
TIM6::frequency(),
|
||||
FREQUENCY,
|
||||
reload,
|
||||
reload as u16,
|
||||
data.len()
|
||||
);
|
||||
|
||||
// Loop technically not necessary if DMA circular mode is enabled
|
||||
loop {
|
||||
info!("Loop DAC1");
|
||||
if let Err(e) = dac.write(ValueArray::Bit8(data), true).await {
|
||||
error!("Could not write to dac: {}", e);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
#[embassy_executor::task]
|
||||
async fn dac_task2(mut dac: Dac2Type) {
|
||||
let data: &[u8; 256] = &calculate_array::<256>();
|
||||
|
||||
info!("TIM7 frequency is {}", TIM7::frequency());
|
||||
|
||||
const FREQUENCY: Hertz = Hertz::hz(600);
|
||||
let reload: u32 = (TIM7::frequency().0 / FREQUENCY.0) / data.len() as u32;
|
||||
|
||||
if reload < 10 {
|
||||
error!("Reload value {} below threshold!", reload);
|
||||
}
|
||||
|
||||
TIM7::enable();
|
||||
TIM7::regs().arr().modify(|w| w.set_arr(reload as u16 - 1));
|
||||
TIM7::regs().cr2().modify(|w| w.set_mms(Mms::UPDATE));
|
||||
TIM7::regs().cr1().modify(|w| {
|
||||
w.set_opm(Opm::DISABLED);
|
||||
w.set_cen(true);
|
||||
});
|
||||
|
||||
dac.select_trigger(embassy_stm32::dac::Ch2Trigger::Tim7).unwrap();
|
||||
|
||||
debug!(
|
||||
"TIM7 Frequency {}, Target Frequency {}, Reload {}, Reload as u16 {}, Samples {}",
|
||||
TIM7::frequency(),
|
||||
FREQUENCY,
|
||||
reload,
|
||||
reload as u16,
|
||||
data.len()
|
||||
);
|
||||
|
||||
if let Err(e) = dac.write(ValueArray::Bit8(data), true).await {
|
||||
error!("Could not write to dac: {}", e);
|
||||
}
|
||||
}
|
||||
|
||||
fn to_sine_wave(v: u8) -> u8 {
|
||||
if v >= 128 {
|
||||
// top half
|
||||
let r = 3.14 * ((v - 128) as f32 / 128.0);
|
||||
(r.sin() * 128.0 + 127.0) as u8
|
||||
} else {
|
||||
// bottom half
|
||||
let r = 3.14 + 3.14 * (v as f32 / 128.0);
|
||||
(r.sin() * 128.0 + 127.0) as u8
|
||||
}
|
||||
}
|
||||
|
||||
fn calculate_array<const N: usize>() -> [u8; N] {
|
||||
let mut res = [0; N];
|
||||
let mut i = 0;
|
||||
while i < N {
|
||||
res[i] = to_sine_wave(i as u8);
|
||||
i += 1;
|
||||
}
|
||||
res
|
||||
}
|
@ -6,8 +6,8 @@ use defmt::*;
|
||||
use embassy_executor::Spawner;
|
||||
use embassy_stm32::gpio::low_level::AFType;
|
||||
use embassy_stm32::gpio::Speed;
|
||||
use embassy_stm32::pwm::*;
|
||||
use embassy_stm32::time::{khz, mhz, Hertz};
|
||||
use embassy_stm32::timer::*;
|
||||
use embassy_stm32::{into_ref, Config, Peripheral, PeripheralRef};
|
||||
use embassy_time::{Duration, Timer};
|
||||
use {defmt_rtt as _, panic_probe as _};
|
||||
|
@ -4,9 +4,9 @@
|
||||
|
||||
use defmt::*;
|
||||
use embassy_executor::Spawner;
|
||||
use embassy_stm32::pwm::simple_pwm::{PwmPin, SimplePwm};
|
||||
use embassy_stm32::pwm::Channel;
|
||||
use embassy_stm32::time::{khz, mhz};
|
||||
use embassy_stm32::timer::simple_pwm::{PwmPin, SimplePwm};
|
||||
use embassy_stm32::timer::Channel;
|
||||
use embassy_stm32::Config;
|
||||
use embassy_time::{Duration, Timer};
|
||||
use {defmt_rtt as _, panic_probe as _};
|
||||
|
@ -10,10 +10,11 @@ nightly = ["embassy-stm32/nightly", "embassy-time/nightly", "embassy-time/unstab
|
||||
"embassy-lora", "lora-phy", "lorawan-device", "lorawan", "embedded-io/async"]
|
||||
|
||||
[dependencies]
|
||||
# Change stm32l072cz to your chip name, if necessary.
|
||||
embassy-stm32 = { version = "0.1.0", path = "../../embassy-stm32", features = ["defmt", "stm32l072cz", "time-driver-any", "exti", "unstable-traits", "memory-x"] }
|
||||
embassy-sync = { version = "0.2.0", path = "../../embassy-sync", features = ["defmt"] }
|
||||
embassy-executor = { version = "0.2.0", path = "../../embassy-executor", features = ["arch-cortex-m", "executor-thread", "defmt", "integrated-timers"] }
|
||||
embassy-time = { version = "0.1.2", path = "../../embassy-time", features = ["defmt", "defmt-timestamp-uptime", "tick-hz-32_768"] }
|
||||
embassy-stm32 = { version = "0.1.0", path = "../../embassy-stm32", features = ["defmt", "stm32l072cz", "time-driver-any", "exti", "unstable-traits", "memory-x"] }
|
||||
embassy-lora = { version = "0.1.0", path = "../../embassy-lora", features = ["time", "defmt"], optional = true }
|
||||
lora-phy = { version = "1", optional = true }
|
||||
lorawan-device = { version = "0.10.0", default-features = false, features = ["async", "external-lora-phy"], optional = true }
|
||||
@ -33,5 +34,5 @@ heapless = { version = "0.7.5", default-features = false }
|
||||
embedded-hal = "0.2.6"
|
||||
static_cell = "1.1"
|
||||
|
||||
[patch.crates-io]
|
||||
lora-phy = { git = "https://github.com/embassy-rs/lora-phy", rev = "ad289428fd44b02788e2fa2116445cc8f640a265" }
|
||||
[profile.release]
|
||||
debug = 2
|
||||
|
@ -20,3 +20,6 @@ panic-probe = { version = "0.3", features = ["print-defmt"] }
|
||||
futures = { version = "0.3.17", default-features = false, features = ["async-await"] }
|
||||
heapless = { version = "0.7.5", default-features = false }
|
||||
embedded-storage = "0.3.0"
|
||||
|
||||
[profile.release]
|
||||
debug = 2
|
||||
|
@ -5,11 +5,12 @@ version = "0.1.0"
|
||||
license = "MIT OR Apache-2.0"
|
||||
|
||||
[dependencies]
|
||||
# Change stm32l4s5vi to your chip name, if necessary.
|
||||
embassy-stm32 = { version = "0.1.0", path = "../../embassy-stm32", features = ["nightly", "defmt", "unstable-pac", "stm32l4s5vi", "memory-x", "time-driver-any", "exti", "unstable-traits", "chrono"] }
|
||||
embassy-sync = { version = "0.2.0", path = "../../embassy-sync", features = ["defmt"] }
|
||||
embassy-executor = { version = "0.2.0", path = "../../embassy-executor", features = ["nightly", "arch-cortex-m", "executor-thread", "defmt", "integrated-timers"] }
|
||||
embassy-time = { version = "0.1.2", path = "../../embassy-time", features = ["defmt", "defmt-timestamp-uptime", "tick-hz-32_768"] }
|
||||
embassy-embedded-hal = { version = "0.1.0", path = "../../embassy-embedded-hal" }
|
||||
embassy-stm32 = { version = "0.1.0", path = "../../embassy-stm32", features = ["nightly", "defmt", "unstable-pac", "stm32l4s5vi", "time-driver-any", "exti", "unstable-traits", "chrono"] }
|
||||
embassy-usb = { version = "0.1.0", path = "../../embassy-usb", features = ["defmt"] }
|
||||
|
||||
defmt = "0.3"
|
||||
@ -26,3 +27,6 @@ heapless = { version = "0.7.5", default-features = false }
|
||||
chrono = { version = "^0.4", default-features = false }
|
||||
|
||||
micromath = "2.0.0"
|
||||
|
||||
[profile.release]
|
||||
debug = 2
|
||||
|
@ -1,34 +1,4 @@
|
||||
//! This build script copies the `memory.x` file from the crate root into
|
||||
//! a directory where the linker can always find it at build time.
|
||||
//! For many projects this is optional, as the linker always searches the
|
||||
//! project root directory -- wherever `Cargo.toml` is. However, if you
|
||||
//! are using a workspace or have a more complicated build setup, this
|
||||
//! build script becomes required. Additionally, by requesting that
|
||||
//! Cargo re-run the build script whenever `memory.x` is changed,
|
||||
//! updating `memory.x` ensures a rebuild of the application with the
|
||||
//! new memory settings.
|
||||
|
||||
use std::env;
|
||||
use std::fs::File;
|
||||
use std::io::Write;
|
||||
use std::path::PathBuf;
|
||||
|
||||
fn main() {
|
||||
// Put `memory.x` in our output directory and ensure it's
|
||||
// on the linker search path.
|
||||
let out = &PathBuf::from(env::var_os("OUT_DIR").unwrap());
|
||||
File::create(out.join("memory.x"))
|
||||
.unwrap()
|
||||
.write_all(include_bytes!("memory.x"))
|
||||
.unwrap();
|
||||
println!("cargo:rustc-link-search={}", out.display());
|
||||
|
||||
// By default, Cargo will re-run a build script whenever
|
||||
// any file in the project changes. By specifying `memory.x`
|
||||
// here, we ensure the build script is only re-run when
|
||||
// `memory.x` is changed.
|
||||
println!("cargo:rerun-if-changed=memory.x");
|
||||
|
||||
println!("cargo:rustc-link-arg-bins=--nmagic");
|
||||
println!("cargo:rustc-link-arg-bins=-Tlink.x");
|
||||
println!("cargo:rustc-link-arg-bins=-Tdefmt.x");
|
||||
|
@ -1,7 +0,0 @@
|
||||
MEMORY
|
||||
{
|
||||
/* NOTE 1 K = 1 KiBi = 1024 bytes */
|
||||
/* These values correspond to the STM32L4S5 */
|
||||
FLASH : ORIGIN = 0x08000000, LENGTH = 1024K
|
||||
RAM : ORIGIN = 0x20000000, LENGTH = 128K
|
||||
}
|
@ -13,11 +13,11 @@ fn main() -> ! {
|
||||
info!("Hello World!");
|
||||
|
||||
let mut dac = DacCh1::new(p.DAC1, NoDma, p.PA4);
|
||||
unwrap!(dac.set_trigger_enable(false));
|
||||
|
||||
loop {
|
||||
for v in 0..=255 {
|
||||
unwrap!(dac.set(Value::Bit8(to_sine_wave(v))));
|
||||
dac.trigger();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -5,10 +5,11 @@ version = "0.1.0"
|
||||
license = "MIT OR Apache-2.0"
|
||||
|
||||
[dependencies]
|
||||
# Change stm32l552ze to your chip name, if necessary.
|
||||
embassy-stm32 = { version = "0.1.0", path = "../../embassy-stm32", features = ["nightly", "defmt", "unstable-pac", "stm32l552ze", "time-driver-any", "exti", "unstable-traits", "memory-x"] }
|
||||
embassy-sync = { version = "0.2.0", path = "../../embassy-sync", features = ["defmt"] }
|
||||
embassy-executor = { version = "0.2.0", path = "../../embassy-executor", features = ["nightly", "arch-cortex-m", "executor-thread", "defmt", "integrated-timers"] }
|
||||
embassy-time = { version = "0.1.2", path = "../../embassy-time", features = ["defmt", "defmt-timestamp-uptime", "tick-hz-32_768"] }
|
||||
embassy-stm32 = { version = "0.1.0", path = "../../embassy-stm32", features = ["nightly", "defmt", "unstable-pac", "stm32l552ze", "time-driver-any", "exti", "unstable-traits", "memory-x"] }
|
||||
embassy-usb = { version = "0.1.0", path = "../../embassy-usb", features = ["defmt"] }
|
||||
embassy-net = { version = "0.1.0", path = "../../embassy-net", features = ["defmt", "nightly", "tcp", "dhcpv4", "medium-ethernet"] }
|
||||
embassy-futures = { version = "0.1.0", path = "../../embassy-futures" }
|
||||
@ -26,3 +27,6 @@ heapless = { version = "0.7.5", default-features = false }
|
||||
rand_core = { version = "0.6.3", default-features = false }
|
||||
embedded-io = { version = "0.4.0", features = ["async"] }
|
||||
static_cell = { version = "1.1", features = ["nightly"]}
|
||||
|
||||
[profile.release]
|
||||
debug = 2
|
||||
|
@ -5,10 +5,11 @@ version = "0.1.0"
|
||||
license = "MIT OR Apache-2.0"
|
||||
|
||||
[dependencies]
|
||||
# Change stm32u585ai to your chip name, if necessary.
|
||||
embassy-stm32 = { version = "0.1.0", path = "../../embassy-stm32", features = ["nightly", "defmt", "unstable-pac", "stm32u585ai", "time-driver-any", "memory-x" ] }
|
||||
embassy-sync = { version = "0.2.0", path = "../../embassy-sync", features = ["defmt"] }
|
||||
embassy-executor = { version = "0.2.0", path = "../../embassy-executor", features = ["nightly", "arch-cortex-m", "executor-thread", "defmt", "integrated-timers"] }
|
||||
embassy-time = { version = "0.1.2", path = "../../embassy-time", features = ["defmt", "defmt-timestamp-uptime", "tick-hz-32_768"] }
|
||||
embassy-stm32 = { version = "0.1.0", path = "../../embassy-stm32", features = ["nightly", "defmt", "unstable-pac", "stm32u585ai", "time-driver-any", "memory-x" ] }
|
||||
embassy-usb = { version = "0.1.0", path = "../../embassy-usb", features = ["defmt"] }
|
||||
|
||||
defmt = "0.3"
|
||||
@ -22,3 +23,6 @@ futures = { version = "0.3.17", default-features = false, features = ["async-awa
|
||||
heapless = { version = "0.7.5", default-features = false }
|
||||
|
||||
micromath = "2.0.0"
|
||||
|
||||
[profile.release]
|
||||
debug = 2
|
||||
|
@ -5,11 +5,12 @@ version = "0.1.0"
|
||||
license = "MIT OR Apache-2.0"
|
||||
|
||||
[dependencies]
|
||||
# Change stm32wb55rg to your chip name in both dependencies, if necessary.
|
||||
embassy-stm32 = { version = "0.1.0", path = "../../embassy-stm32", features = ["nightly", "defmt", "stm32wb55rg", "time-driver-any", "memory-x", "exti"] }
|
||||
embassy-stm32-wpan = { version = "0.1.0", path = "../../embassy-stm32-wpan", features = ["defmt", "stm32wb55rg"] }
|
||||
embassy-sync = { version = "0.2.0", path = "../../embassy-sync", features = ["defmt"] }
|
||||
embassy-executor = { version = "0.2.0", path = "../../embassy-executor", features = ["nightly", "arch-cortex-m", "executor-thread", "defmt", "integrated-timers"] }
|
||||
embassy-time = { version = "0.1.2", path = "../../embassy-time", features = ["defmt", "defmt-timestamp-uptime", "tick-hz-32_768"] }
|
||||
embassy-stm32 = { version = "0.1.0", path = "../../embassy-stm32", features = ["nightly", "defmt", "stm32wb55rg", "time-driver-any", "memory-x", "exti"] }
|
||||
embassy-stm32-wpan = { version = "0.1.0", path = "../../embassy-stm32-wpan", features = ["defmt", "stm32wb55rg"] }
|
||||
embassy-net = { version = "0.1.0", path = "../../embassy-net", features = ["defmt", "udp", "medium-ieee802154", "nightly"], optional=true }
|
||||
|
||||
defmt = "0.3"
|
||||
@ -50,4 +51,7 @@ required-features = ["ble"]
|
||||
|
||||
[[bin]]
|
||||
name = "gatt_server"
|
||||
required-features = ["ble"]
|
||||
required-features = ["ble"]
|
||||
|
||||
[profile.release]
|
||||
debug = 2
|
||||
|
@ -5,10 +5,11 @@ version = "0.1.0"
|
||||
license = "MIT OR Apache-2.0"
|
||||
|
||||
[dependencies]
|
||||
# Change stm32wl55jc-cm4 to your chip name, if necessary.
|
||||
embassy-stm32 = { version = "0.1.0", path = "../../embassy-stm32", features = ["nightly", "unstable-traits", "defmt", "stm32wl55jc-cm4", "time-driver-any", "memory-x", "unstable-pac", "exti", "chrono"] }
|
||||
embassy-sync = { version = "0.2.0", path = "../../embassy-sync", features = ["defmt"] }
|
||||
embassy-executor = { version = "0.2.0", path = "../../embassy-executor", features = ["nightly", "arch-cortex-m", "executor-thread", "defmt", "integrated-timers"] }
|
||||
embassy-time = { version = "0.1.2", path = "../../embassy-time", features = ["nightly", "unstable-traits", "defmt", "defmt-timestamp-uptime", "tick-hz-32_768"] }
|
||||
embassy-stm32 = { version = "0.1.0", path = "../../embassy-stm32", features = ["nightly", "unstable-traits", "defmt", "stm32wl55jc-cm4", "time-driver-any", "memory-x", "unstable-pac", "exti", "chrono"] }
|
||||
embassy-embedded-hal = { version = "0.1.0", path = "../../embassy-embedded-hal" }
|
||||
embassy-lora = { version = "0.1.0", path = "../../embassy-lora", features = ["stm32wl", "time", "defmt"] }
|
||||
lora-phy = { version = "1" }
|
||||
@ -27,5 +28,5 @@ futures = { version = "0.3.17", default-features = false, features = ["async-awa
|
||||
heapless = { version = "0.7.5", default-features = false }
|
||||
chrono = { version = "^0.4", default-features = false }
|
||||
|
||||
[patch.crates-io]
|
||||
lora-phy = { git = "https://github.com/embassy-rs/lora-phy", rev = "ad289428fd44b02788e2fa2116445cc8f640a265" }
|
||||
[profile.release]
|
||||
debug = 2
|
||||
|
@ -17,3 +17,6 @@ wasm-bindgen = "0.2"
|
||||
web-sys = { version = "0.3", features = ["Document", "Element", "HtmlElement", "Node", "Window" ] }
|
||||
log = "0.4.11"
|
||||
critical-section = { version = "1.1", features = ["std"] }
|
||||
|
||||
[profile.release]
|
||||
debug = 2
|
||||
|
Reference in New Issue
Block a user