Merge pull request #1501 from xoviat/can

async can
This commit is contained in:
Dario Nieuwenhuis 2023-06-20 22:57:31 +00:00 committed by GitHub
commit 2e625138ff
No known key found for this signature in database
GPG key ID: 4AEE18F83AFDEB23
4 changed files with 511 additions and 22 deletions

View file

@ -1,22 +1,106 @@
use core::future::poll_fn;
use core::marker::PhantomData;
use core::ops::{Deref, DerefMut};
use core::task::Poll;
pub use bxcan;
use bxcan::{Data, ExtendedId, Frame, Id, StandardId};
use embassy_hal_common::{into_ref, PeripheralRef};
use futures::FutureExt;
use crate::gpio::sealed::AFType;
use crate::interrupt::typelevel::Interrupt;
use crate::pac::can::vals::{Lec, RirIde};
use crate::rcc::RccPeripheral;
use crate::{peripherals, Peripheral};
use crate::time::Hertz;
use crate::{interrupt, peripherals, Peripheral};
/// Interrupt handler.
pub struct TxInterruptHandler<T: Instance> {
_phantom: PhantomData<T>,
}
impl<T: Instance> interrupt::typelevel::Handler<T::TXInterrupt> for TxInterruptHandler<T> {
unsafe fn on_interrupt() {
T::regs().tsr().write(|v| {
v.set_rqcp(0, true);
v.set_rqcp(1, true);
v.set_rqcp(2, true);
});
T::state().tx_waker.wake();
}
}
pub struct Rx0InterruptHandler<T: Instance> {
_phantom: PhantomData<T>,
}
impl<T: Instance> interrupt::typelevel::Handler<T::RX0Interrupt> for Rx0InterruptHandler<T> {
unsafe fn on_interrupt() {
// info!("rx0 irq");
Can::<T>::receive_fifo(RxFifo::Fifo0);
}
}
pub struct Rx1InterruptHandler<T: Instance> {
_phantom: PhantomData<T>,
}
impl<T: Instance> interrupt::typelevel::Handler<T::RX1Interrupt> for Rx1InterruptHandler<T> {
unsafe fn on_interrupt() {
// info!("rx1 irq");
Can::<T>::receive_fifo(RxFifo::Fifo1);
}
}
pub struct SceInterruptHandler<T: Instance> {
_phantom: PhantomData<T>,
}
impl<T: Instance> interrupt::typelevel::Handler<T::SCEInterrupt> for SceInterruptHandler<T> {
unsafe fn on_interrupt() {
// info!("sce irq");
let msr = T::regs().msr();
let msr_val = msr.read();
if msr_val.erri() {
msr.modify(|v| v.set_erri(true));
T::state().err_waker.wake();
}
}
}
pub struct Can<'d, T: Instance> {
can: bxcan::Can<BxcanInstance<'d, T>>,
}
#[derive(Debug)]
pub enum BusError {
Stuff,
Form,
Acknowledge,
BitRecessive,
BitDominant,
Crc,
Software,
BusOff,
BusPassive,
BusWarning,
}
impl<'d, T: Instance> Can<'d, T> {
/// Creates a new Bxcan instance, blocking for 11 recessive bits to sync with the CAN bus.
/// 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(
peri: impl Peripheral<P = T> + 'd,
rx: impl Peripheral<P = impl RxPin<T>> + 'd,
tx: impl Peripheral<P = impl TxPin<T>> + 'd,
_irqs: impl interrupt::typelevel::Binding<T::TXInterrupt, TxInterruptHandler<T>>
+ interrupt::typelevel::Binding<T::RX0Interrupt, Rx0InterruptHandler<T>>
+ interrupt::typelevel::Binding<T::RX1Interrupt, Rx1InterruptHandler<T>>
+ interrupt::typelevel::Binding<T::SCEInterrupt, SceInterruptHandler<T>>
+ 'd,
) -> Self {
into_ref!(peri, rx, tx);
@ -26,30 +110,242 @@ impl<'d, T: Instance> Can<'d, T> {
T::enable();
T::reset();
Self {
can: bxcan::Can::builder(BxcanInstance(peri)).enable(),
}
}
{
use crate::pac::can::vals::{Errie, Fmpie, Tmeie};
/// 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(
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);
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::unpend();
T::TXInterrupt::enable();
T::RX0Interrupt::unpend();
T::RX0Interrupt::enable();
T::RX1Interrupt::unpend();
T::RX1Interrupt::enable();
T::SCEInterrupt::unpend();
T::SCEInterrupt::enable();
}
rx.set_as_af(rx.af_num(), AFType::Input);
tx.set_as_af(tx.af_num(), AFType::OutputPushPull);
T::enable();
T::reset();
let can = bxcan::Can::builder(BxcanInstance(peri)).leave_disabled();
Self { can }
}
Self {
can: bxcan::Can::builder(BxcanInstance(peri)).leave_disabled(),
pub fn set_bitrate(&mut self, bitrate: u32) {
let bit_timing = Self::calc_bxcan_timings(T::frequency(), bitrate).unwrap();
self.can.modify_config().set_bit_timing(bit_timing).leave_disabled();
}
/// Queues the message to be sent but exerts backpressure
pub async fn write(&mut self, frame: &Frame) -> bxcan::TransmitStatus {
poll_fn(|cx| {
T::state().tx_waker.register(cx.waker());
if let Ok(status) = self.can.transmit(frame) {
return Poll::Ready(status);
}
Poll::Pending
})
.await
}
pub async fn flush(&self, mb: bxcan::Mailbox) {
poll_fn(|cx| {
T::state().tx_waker.register(cx.waker());
if T::regs().tsr().read().tme(mb.index()) {
return Poll::Ready(());
}
Poll::Pending
})
.await;
}
/// 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| {
T::state().err_waker.register(cx.waker());
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(Err(err));
}
Poll::Pending
})
.await
}
fn curr_error(&self) -> Option<BusError> {
let err = { T::regs().esr().read() };
if err.boff() {
return Some(BusError::BusOff);
} else if err.epvf() {
return Some(BusError::BusPassive);
} else if err.ewgf() {
return Some(BusError::BusWarning);
} else if let Some(err) = err.lec().into_bus_err() {
return Some(err);
}
None
}
unsafe fn receive_fifo(fifo: RxFifo) {
let state = T::state();
let regs = T::regs();
let fifo_idx = match fifo {
RxFifo::Fifo0 => 0usize,
RxFifo::Fifo1 => 1usize,
};
let rfr = regs.rfr(fifo_idx);
let fifo = regs.rx(fifo_idx);
loop {
// If there are no pending messages, there is nothing to do
if rfr.read().fmp() == 0 {
return;
}
let rir = fifo.rir().read();
let id = if rir.ide() == RirIde::STANDARD {
Id::from(StandardId::new_unchecked(rir.stid()))
} else {
let stid = (rir.stid() & 0x7FF) as u32;
let exid = rir.exid() & 0x3FFFF;
let id = (stid << 18) | (exid as u32);
Id::from(ExtendedId::new_unchecked(id))
};
let data_len = fifo.rdtr().read().dlc() as usize;
let mut data: [u8; 8] = [0; 8];
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));
/*
NOTE: consensus was reached that if rx_queue is full, packets should be dropped
*/
let _ = state.rx_queue.try_send((time, frame));
}
}
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;
let periph_clock = periph_clock.0;
if can_bitrate < 1000 {
return None;
}
// Ref. "Automatic Baudrate Detection in CANopen Networks", U. Koppe, MicroControl GmbH & Co. KG
// CAN in Automation, 2003
//
// According to the source, optimal quanta per bit are:
// Bitrate Optimal Maximum
// 1000 kbps 8 10
// 500 kbps 16 17
// 250 kbps 16 17
// 125 kbps 16 17
let max_quanta_per_bit: u8 = if can_bitrate >= 1_000_000 { 10 } else { 17 };
// Computing (prescaler * BS):
// BITRATE = 1 / (PRESCALER * (1 / PCLK) * (1 + BS1 + BS2)) -- See the Reference Manual
// BITRATE = PCLK / (PRESCALER * (1 + BS1 + BS2)) -- Simplified
// let:
// BS = 1 + BS1 + BS2 -- Number of time quanta per bit
// PRESCALER_BS = PRESCALER * BS
// ==>
// PRESCALER_BS = PCLK / BITRATE
let prescaler_bs = periph_clock / can_bitrate;
// Searching for such prescaler value so that the number of quanta per bit is highest.
let mut bs1_bs2_sum = max_quanta_per_bit - 1;
while (prescaler_bs % (1 + bs1_bs2_sum) as u32) != 0 {
if bs1_bs2_sum <= 2 {
return None; // No solution
}
bs1_bs2_sum -= 1;
}
let prescaler = prescaler_bs / (1 + bs1_bs2_sum) as u32;
if (prescaler < 1) || (prescaler > 1024) {
return None; // No solution
}
// Now we have a constraint: (BS1 + BS2) == bs1_bs2_sum.
// We need to find such values so that the sample point is as close as possible to the optimal value,
// which is 87.5%, which is 7/8.
//
// Solve[(1 + bs1)/(1 + bs1 + bs2) == 7/8, bs2] (* Where 7/8 is 0.875, the recommended sample point location *)
// {{bs2 -> (1 + bs1)/7}}
//
// Hence:
// bs2 = (1 + bs1) / 7
// bs1 = (7 * bs1_bs2_sum - 1) / 8
//
// Sample point location can be computed as follows:
// Sample point location = (1 + bs1) / (1 + bs1 + bs2)
//
// Since the optimal solution is so close to the maximum, we prepare two solutions, and then pick the best one:
// - With rounding to nearest
// - 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;
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 {
// Nope, too far; now rounding to zero
bs1 = (7 * bs1_bs2_sum - 1) / 8;
bs2 = bs1_bs2_sum - bs1;
}
// Check is BS1 and BS2 are in range
if (bs1 < 1) || (bs1 > BS1_MAX) || (bs2 < 1) || (bs2 > BS2_MAX) {
return None;
}
// Check if final bitrate matches the requested
if can_bitrate != (periph_clock / (prescaler * (1 + bs1 + bs2) as u32)) {
return None;
}
// One is recommended by DS-015, CANOpen, and DeviceNet
let sjw = 1;
// Pack into BTR register values
Some((sjw - 1) << 24 | (bs1 as u32 - 1) << 16 | (bs2 as u32 - 1) << 20 | (prescaler as u32 - 1))
}
}
enum RxFifo {
Fifo0,
Fifo1,
}
impl<'d, T: Instance> Drop for Can<'d, T> {
@ -76,14 +372,52 @@ impl<'d, T: Instance> DerefMut for Can<'d, T> {
}
pub(crate) mod sealed {
use embassy_sync::blocking_mutex::raw::CriticalSectionRawMutex;
use embassy_sync::channel::Channel;
use embassy_sync::waitqueue::AtomicWaker;
pub struct State {
pub tx_waker: AtomicWaker,
pub err_waker: AtomicWaker,
pub rx_queue: Channel<CriticalSectionRawMutex, (u16, bxcan::Frame), 32>,
}
impl State {
pub const fn new() -> Self {
Self {
tx_waker: AtomicWaker::new(),
err_waker: AtomicWaker::new(),
rx_queue: Channel::new(),
}
}
}
pub trait Instance {
const REGISTERS: *mut bxcan::RegisterBlock;
fn regs() -> &'static crate::pac::can::Can;
fn state() -> &'static State;
}
}
pub trait Instance: sealed::Instance + RccPeripheral {}
pub trait TXInstance {
type TXInterrupt: crate::interrupt::typelevel::Interrupt;
}
pub trait RX0Instance {
type RX0Interrupt: crate::interrupt::typelevel::Interrupt;
}
pub trait RX1Instance {
type RX1Interrupt: crate::interrupt::typelevel::Interrupt;
}
pub trait SCEInstance {
type SCEInterrupt: crate::interrupt::typelevel::Interrupt;
}
pub trait InterruptableInstance: TXInstance + RX0Instance + RX1Instance + SCEInstance {}
pub trait Instance: sealed::Instance + RccPeripheral + InterruptableInstance + 'static {}
pub struct BxcanInstance<'a, T>(PeripheralRef<'a, T>);
@ -99,10 +433,39 @@ foreach_peripheral!(
fn regs() -> &'static crate::pac::can::Can {
&crate::pac::$inst
}
fn state() -> &'static sealed::State {
static STATE: sealed::State = sealed::State::new();
&STATE
}
}
impl Instance for peripherals::$inst {}
foreach_interrupt!(
($inst,can,CAN,TX,$irq:ident) => {
impl TXInstance for peripherals::$inst {
type TXInterrupt = crate::interrupt::typelevel::$irq;
}
};
($inst,can,CAN,RX0,$irq:ident) => {
impl RX0Instance for peripherals::$inst {
type RX0Interrupt = crate::interrupt::typelevel::$irq;
}
};
($inst,can,CAN,RX1,$irq:ident) => {
impl RX1Instance for peripherals::$inst {
type RX1Interrupt = crate::interrupt::typelevel::$irq;
}
};
($inst,can,CAN,SCE,$irq:ident) => {
impl SCEInstance for peripherals::$inst {
type SCEInterrupt = crate::interrupt::typelevel::$irq;
}
};
);
impl InterruptableInstance for peripherals::$inst {}
};
);
@ -143,3 +506,36 @@ foreach_peripheral!(
pin_trait!(RxPin, Instance);
pin_trait!(TxPin, Instance);
trait Index {
fn index(&self) -> usize;
}
impl Index for bxcan::Mailbox {
fn index(&self) -> usize {
match self {
bxcan::Mailbox::Mailbox0 => 0,
bxcan::Mailbox::Mailbox1 => 1,
bxcan::Mailbox::Mailbox2 => 2,
}
}
}
trait IntoBusError {
fn into_bus_err(self) -> Option<BusError>;
}
impl IntoBusError for Lec {
fn into_bus_err(self) -> Option<BusError> {
match self {
Lec::STUFF => Some(BusError::Stuff),
Lec::FORM => Some(BusError::Form),
Lec::ACK => Some(BusError::Acknowledge),
Lec::BITRECESSIVE => Some(BusError::BitRecessive),
Lec::BITDOMINANT => Some(BusError::BitDominant),
Lec::CRC => Some(BusError::Crc),
Lec::CUSTOM => Some(BusError::Software),
_ => None,
}
}
}

View file

@ -4,12 +4,21 @@
use cortex_m_rt::entry;
use defmt::*;
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;
use embassy_stm32::can::{Can, Rx0InterruptHandler, Rx1InterruptHandler, SceInterruptHandler, TxInterruptHandler};
use embassy_stm32::gpio::{Input, Pull};
use embassy_stm32::peripherals::CAN1;
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>;
});
#[entry]
fn main() -> ! {
info!("Hello World!");
@ -23,7 +32,7 @@ fn main() -> ! {
let rx_pin = Input::new(&mut p.PA11, Pull::Up);
core::mem::forget(rx_pin);
let mut can = Can::new(p.CAN1, p.PA11, p.PA12);
let mut can = Can::new(p.CAN1, p.PA11, p.PA12, Irqs);
can.modify_filters().enable_bank(0, Fifo::Fifo0, Mask32::accept_all());

View file

@ -7,7 +7,7 @@ autobins = false
[features]
stm32f103c8 = ["embassy-stm32/stm32f103c8", "not-gpdma"] # Blue Pill
stm32f429zi = ["embassy-stm32/stm32f429zi", "chrono", "not-gpdma"] # Nucleo "sdmmc"
stm32f429zi = ["embassy-stm32/stm32f429zi", "chrono", "can", "not-gpdma"] # Nucleo "sdmmc"
stm32g071rb = ["embassy-stm32/stm32g071rb", "not-gpdma"] # Nucleo
stm32c031c6 = ["embassy-stm32/stm32c031c6", "not-gpdma"] # Nucleo
stm32g491re = ["embassy-stm32/stm32g491re", "not-gpdma"] # Nucleo
@ -18,6 +18,7 @@ stm32u585ai = ["embassy-stm32/stm32u585ai"] # IoT board
sdmmc = []
chrono = ["embassy-stm32/chrono", "dep:chrono"]
can = []
ble = ["dep:embassy-stm32-wpan"]
not-gpdma = []
@ -52,6 +53,11 @@ name = "tl_mbox"
path = "src/bin/tl_mbox.rs"
required-features = [ "ble",]
[[bin]]
name = "can"
path = "src/bin/can.rs"
required-features = [ "can",]
[[bin]]
name = "gpio"
path = "src/bin/gpio.rs"

View file

@ -0,0 +1,78 @@
#![no_std]
#![no_main]
#![feature(type_alias_impl_trait)]
// required-features: can
#[path = "../common.rs"]
mod common;
use 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 {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();
}