stm32/can: add hw test and cleanup
This commit is contained in:
parent
f8d35806dc
commit
16bfbd4e99
@ -39,6 +39,7 @@ pub struct Rx0InterruptHandler<T: Instance> {
|
||||
|
||||
impl<T: Instance> interrupt::Handler<T::RX0Interrupt> for Rx0InterruptHandler<T> {
|
||||
unsafe fn on_interrupt() {
|
||||
// info!("rx0 irq");
|
||||
Can::<T>::receive_fifo(RxFifo::Fifo0);
|
||||
}
|
||||
}
|
||||
@ -49,6 +50,7 @@ pub struct Rx1InterruptHandler<T: Instance> {
|
||||
|
||||
impl<T: Instance> interrupt::Handler<T::RX1Interrupt> for Rx1InterruptHandler<T> {
|
||||
unsafe fn on_interrupt() {
|
||||
// info!("rx1 irq");
|
||||
Can::<T>::receive_fifo(RxFifo::Fifo1);
|
||||
}
|
||||
}
|
||||
@ -59,6 +61,7 @@ pub struct SceInterruptHandler<T: Instance> {
|
||||
|
||||
impl<T: Instance> interrupt::Handler<T::SCEInterrupt> for SceInterruptHandler<T> {
|
||||
unsafe fn on_interrupt() {
|
||||
// info!("sce irq");
|
||||
let msr = T::regs().msr();
|
||||
let msr_val = msr.read();
|
||||
|
||||
@ -87,36 +90,10 @@ pub enum BusError {
|
||||
BusWarning,
|
||||
}
|
||||
|
||||
pub enum FrameOrError {
|
||||
Frame(Frame),
|
||||
Error(BusError),
|
||||
}
|
||||
|
||||
impl<'d, T: Instance> Can<'d, T> {
|
||||
/// Creates a new Bxcan instance, blocking for 11 recessive bits to sync with the CAN bus.
|
||||
pub fn new(
|
||||
peri: impl Peripheral<P = T> + 'd,
|
||||
rx: impl Peripheral<P = impl RxPin<T>> + 'd,
|
||||
tx: impl Peripheral<P = impl TxPin<T>> + 'd,
|
||||
) -> Self {
|
||||
into_ref!(peri, rx, tx);
|
||||
|
||||
unsafe {
|
||||
rx.set_as_af(rx.af_num(), AFType::Input);
|
||||
tx.set_as_af(tx.af_num(), AFType::OutputPushPull);
|
||||
}
|
||||
|
||||
T::enable();
|
||||
T::reset();
|
||||
|
||||
Self {
|
||||
can: bxcan::Can::builder(BxcanInstance(peri)).enable(),
|
||||
}
|
||||
}
|
||||
|
||||
/// Creates a new Bxcan instance, keeping the peripheral in sleep mode.
|
||||
/// You must call [Can::enable_non_blocking] to use the peripheral.
|
||||
pub fn new_disabled(
|
||||
pub fn new(
|
||||
peri: impl Peripheral<P = T> + 'd,
|
||||
rx: impl Peripheral<P = impl RxPin<T>> + 'd,
|
||||
tx: impl Peripheral<P = impl TxPin<T>> + 'd,
|
||||
@ -136,6 +113,25 @@ impl<'d, T: Instance> Can<'d, T> {
|
||||
T::enable();
|
||||
T::reset();
|
||||
|
||||
unsafe {
|
||||
use crate::pac::can::vals::{Errie, Fmpie, Tmeie};
|
||||
|
||||
T::regs().ier().write(|w| {
|
||||
// TODO: fix metapac
|
||||
|
||||
w.set_errie(Errie(1));
|
||||
w.set_fmpie(0, Fmpie(1));
|
||||
w.set_fmpie(1, Fmpie(1));
|
||||
w.set_tmeie(Tmeie(1));
|
||||
});
|
||||
|
||||
T::regs().mcr().write(|w| {
|
||||
// Enable timestamps on rx messages
|
||||
|
||||
w.set_ttcm(true);
|
||||
})
|
||||
}
|
||||
|
||||
unsafe {
|
||||
T::TXInterrupt::steal().unpend();
|
||||
T::TXInterrupt::steal().enable();
|
||||
@ -159,12 +155,8 @@ impl<'d, T: Instance> Can<'d, T> {
|
||||
self.can.modify_config().set_bit_timing(bit_timing).leave_disabled();
|
||||
}
|
||||
|
||||
pub async fn transmit(&mut self, frame: &Frame) {
|
||||
let tx_status = self.queue_transmit(frame).await;
|
||||
self.wait_transission(tx_status.mailbox()).await;
|
||||
}
|
||||
|
||||
async fn queue_transmit(&mut self, frame: &Frame) -> bxcan::TransmitStatus {
|
||||
/// Queues the message to be sent but exerts backpressure
|
||||
pub async fn write(&mut self, frame: &Frame) -> bxcan::TransmitStatus {
|
||||
poll_fn(|cx| {
|
||||
if let Ok(status) = self.can.transmit(frame) {
|
||||
return Poll::Ready(status);
|
||||
@ -175,7 +167,7 @@ impl<'d, T: Instance> Can<'d, T> {
|
||||
.await
|
||||
}
|
||||
|
||||
async fn wait_transission(&self, mb: bxcan::Mailbox) {
|
||||
pub async fn flush(&self, mb: bxcan::Mailbox) {
|
||||
poll_fn(|cx| unsafe {
|
||||
if T::regs().tsr().read().tme(mb.index()) {
|
||||
return Poll::Ready(());
|
||||
@ -186,12 +178,13 @@ impl<'d, T: Instance> Can<'d, T> {
|
||||
.await;
|
||||
}
|
||||
|
||||
pub async fn receive_frame_or_error(&mut self) -> FrameOrError {
|
||||
/// Returns a tuple of the time the message was received and the message frame
|
||||
pub async fn read(&mut self) -> Result<(u16, bxcan::Frame), BusError> {
|
||||
poll_fn(|cx| {
|
||||
if let Poll::Ready(frame) = T::state().rx_queue.recv().poll_unpin(cx) {
|
||||
return Poll::Ready(FrameOrError::Frame(frame));
|
||||
if let Poll::Ready((time, frame)) = T::state().rx_queue.recv().poll_unpin(cx) {
|
||||
return Poll::Ready(Ok((time, frame)));
|
||||
} else if let Some(err) = self.curr_error() {
|
||||
return Poll::Ready(FrameOrError::Error(err));
|
||||
return Poll::Ready(Err(err));
|
||||
}
|
||||
T::state().err_waker.register(cx.waker());
|
||||
Poll::Pending
|
||||
@ -240,6 +233,7 @@ impl<'d, T: Instance> Can<'d, T> {
|
||||
data[0..4].copy_from_slice(&fifo.rdlr().read().0.to_ne_bytes());
|
||||
data[4..8].copy_from_slice(&fifo.rdhr().read().0.to_ne_bytes());
|
||||
|
||||
let time = fifo.rdtr().read().time();
|
||||
let frame = Frame::new_data(id, Data::new(&data[0..data_len]).unwrap());
|
||||
|
||||
rfr.modify(|v| v.set_rfom(true));
|
||||
@ -247,11 +241,11 @@ impl<'d, T: Instance> Can<'d, T> {
|
||||
/*
|
||||
NOTE: consensus was reached that if rx_queue is full, packets should be dropped
|
||||
*/
|
||||
let _ = state.rx_queue.try_send(frame);
|
||||
let _ = state.rx_queue.try_send((time, frame));
|
||||
}
|
||||
}
|
||||
|
||||
pub fn calc_bxcan_timings(periph_clock: Hertz, can_bitrate: u32) -> Option<u32> {
|
||||
pub const fn calc_bxcan_timings(periph_clock: Hertz, can_bitrate: u32) -> Option<u32> {
|
||||
const BS1_MAX: u8 = 16;
|
||||
const BS2_MAX: u8 = 8;
|
||||
const MAX_SAMPLE_POINT_PERMILL: u16 = 900;
|
||||
@ -316,7 +310,7 @@ impl<'d, T: Instance> Can<'d, T> {
|
||||
// - With rounding to zero
|
||||
let mut bs1 = ((7 * bs1_bs2_sum - 1) + 4) / 8; // Trying rounding to nearest first
|
||||
let mut bs2 = bs1_bs2_sum - bs1;
|
||||
assert!(bs1_bs2_sum > bs1);
|
||||
core::assert!(bs1_bs2_sum > bs1);
|
||||
|
||||
let sample_point_permill = 1000 * ((1 + bs1) / (1 + bs1 + bs2)) as u16;
|
||||
if sample_point_permill > MAX_SAMPLE_POINT_PERMILL {
|
||||
@ -379,7 +373,7 @@ pub(crate) mod sealed {
|
||||
pub struct State {
|
||||
pub tx_waker: AtomicWaker,
|
||||
pub err_waker: AtomicWaker,
|
||||
pub rx_queue: Channel<CriticalSectionRawMutex, bxcan::Frame, 32>,
|
||||
pub rx_queue: Channel<CriticalSectionRawMutex, (u16, bxcan::Frame), 32>,
|
||||
}
|
||||
|
||||
impl State {
|
||||
|
@ -7,7 +7,7 @@ autobins = false
|
||||
|
||||
[features]
|
||||
stm32f103c8 = ["embassy-stm32/stm32f103c8", "not-gpdma"] # Blue Pill
|
||||
stm32f429zi = ["embassy-stm32/stm32f429zi", "sdmmc", "chrono", "not-gpdma"] # Nucleo
|
||||
stm32f429zi = ["embassy-stm32/stm32f429zi", "sdmmc", "chrono", "can", "not-gpdma"] # Nucleo
|
||||
stm32g071rb = ["embassy-stm32/stm32g071rb", "not-gpdma"] # Nucleo
|
||||
stm32c031c6 = ["embassy-stm32/stm32c031c6", "not-gpdma"] # Nucleo
|
||||
stm32g491re = ["embassy-stm32/stm32g491re", "not-gpdma"] # Nucleo
|
||||
@ -19,6 +19,7 @@ stm32u585ai = ["embassy-stm32/stm32u585ai"] # IoT board
|
||||
sdmmc = []
|
||||
chrono = ["embassy-stm32/chrono", "dep:chrono"]
|
||||
ble = []
|
||||
can = []
|
||||
not-gpdma = []
|
||||
|
||||
[dependencies]
|
||||
@ -49,6 +50,11 @@ name = "ble"
|
||||
path = "src/bin/ble.rs"
|
||||
required-features = [ "ble",]
|
||||
|
||||
[[bin]]
|
||||
name = "can"
|
||||
path = "src/bin/can.rs"
|
||||
required-features = [ "can",]
|
||||
|
||||
[[bin]]
|
||||
name = "gpio"
|
||||
path = "src/bin/gpio.rs"
|
||||
|
78
tests/stm32/src/bin/can.rs
Normal file
78
tests/stm32/src/bin/can.rs
Normal file
@ -0,0 +1,78 @@
|
||||
#![no_std]
|
||||
#![no_main]
|
||||
#![feature(type_alias_impl_trait)]
|
||||
|
||||
// required-features: can
|
||||
|
||||
#[path = "../example_common.rs"]
|
||||
mod example_common;
|
||||
use embassy_executor::Spawner;
|
||||
use embassy_stm32::bind_interrupts;
|
||||
use embassy_stm32::can::bxcan::filter::Mask32;
|
||||
use embassy_stm32::can::bxcan::{Fifo, Frame, StandardId};
|
||||
use embassy_stm32::can::{Can, Rx0InterruptHandler, Rx1InterruptHandler, SceInterruptHandler, TxInterruptHandler};
|
||||
use embassy_stm32::gpio::{Input, Pull};
|
||||
use embassy_stm32::peripherals::CAN1;
|
||||
use example_common::*;
|
||||
use {defmt_rtt as _, panic_probe as _};
|
||||
|
||||
bind_interrupts!(struct Irqs {
|
||||
CAN1_RX0 => Rx0InterruptHandler<CAN1>;
|
||||
CAN1_RX1 => Rx1InterruptHandler<CAN1>;
|
||||
CAN1_SCE => SceInterruptHandler<CAN1>;
|
||||
CAN1_TX => TxInterruptHandler<CAN1>;
|
||||
});
|
||||
|
||||
#[embassy_executor::main]
|
||||
async fn main(_spawner: Spawner) {
|
||||
let mut p = embassy_stm32::init(config());
|
||||
info!("Hello World!");
|
||||
|
||||
// HW is connected as follows:
|
||||
// PB13 -> PD0
|
||||
// PB12 -> PD1
|
||||
|
||||
// The next two lines are a workaround for testing without transceiver.
|
||||
// To synchronise to the bus the RX input needs to see a high level.
|
||||
// Use `mem::forget()` to release the borrow on the pin but keep the
|
||||
// pull-up resistor enabled.
|
||||
let rx_pin = Input::new(&mut p.PD0, Pull::Up);
|
||||
core::mem::forget(rx_pin);
|
||||
|
||||
let mut can = Can::new(p.CAN1, p.PD0, p.PD1, Irqs);
|
||||
|
||||
info!("Configuring can...");
|
||||
|
||||
can.modify_filters().enable_bank(0, Fifo::Fifo0, Mask32::accept_all());
|
||||
|
||||
can.set_bitrate(1_000_000);
|
||||
can.modify_config()
|
||||
.set_loopback(true) // Receive own frames
|
||||
.set_silent(true)
|
||||
// .set_bit_timing(0x001c0003)
|
||||
.enable();
|
||||
|
||||
info!("Can configured");
|
||||
|
||||
let mut i: u8 = 0;
|
||||
loop {
|
||||
let tx_frame = Frame::new_data(unwrap!(StandardId::new(i as _)), [i]);
|
||||
|
||||
info!("Transmitting frame...");
|
||||
can.write(&tx_frame).await;
|
||||
|
||||
info!("Receiving frame...");
|
||||
let (time, rx_frame) = can.read().await.unwrap();
|
||||
|
||||
info!("loopback time {}", time);
|
||||
info!("loopback frame {=u8}", rx_frame.data().unwrap()[0]);
|
||||
|
||||
i += 1;
|
||||
if i > 10 {
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
info!("Test OK");
|
||||
cortex_m::asm::bkpt();
|
||||
}
|
Loading…
Reference in New Issue
Block a user