use core::convert::AsMut;
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_internal::{into_ref, PeripheralRef};
use futures::FutureExt;
use crate::gpio::sealed::AFType;
use crate::interrupt::typelevel::Interrupt;
use crate::pac::can::vals::{Ide, Lec};
use crate::rcc::RccPeripheral;
use crate::time::Hertz;
use crate::{interrupt, peripherals, Peripheral};
#[derive(Debug, Clone, PartialEq, Eq)]
#[cfg_attr(feature = "defmt", derive(defmt::Format))]
pub struct Envelope {
    #[cfg(feature = "time")]
    pub ts: embassy_time::Instant,
    pub frame: bxcan::Frame,
}
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() {
        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() {
        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() {
        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>>,
}
#[allow(missing_docs)]
#[derive(Debug)]
#[cfg_attr(feature = "defmt", derive(defmt::Format))]
pub enum BusError {
    Stuff,
    Form,
    Acknowledge,
    BitRecessive,
    BitDominant,
    Crc,
    Software,
    BusOff,
    BusPassive,
    BusWarning,
}
#[derive(Debug)]
#[cfg_attr(feature = "defmt", derive(defmt::Format))]
pub enum TryReadError {
    BusError(BusError),
    Empty,
}
#[derive(Debug)]
#[cfg_attr(feature = "defmt", derive(defmt::Format))]
pub enum TryWriteError {
    Full,
}
impl<'d, T: Instance> Can<'d, T> {
    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);
        rx.set_as_af(rx.af_num(), AFType::Input);
        tx.set_as_af(tx.af_num(), AFType::OutputPushPull);
        T::enable_and_reset();
        {
            T::regs().ier().write(|w| {
                w.set_errie(true);
                w.set_fmpie(0, true);
                w.set_fmpie(1, true);
                w.set_tmeie(true);
            });
            T::regs().mcr().write(|w| {
                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);
        let can = bxcan::Can::builder(BxcanInstance(peri)).leave_disabled();
        Self { can }
    }
    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();
    }
    pub async fn enable(&mut self) {
        while self.enable_non_blocking().is_err() {
            embassy_futures::yield_now().await;
        }
    }
    pub async fn write(&mut self, frame: &Frame) -> bxcan::TransmitStatus {
        self.split().0.write(frame).await
    }
    pub fn try_write(&mut self, frame: &Frame) -> Result<bxcan::TransmitStatus, TryWriteError> {
        self.split().0.try_write(frame)
    }
    pub async fn flush(&self, mb: bxcan::Mailbox) {
        CanTx::<T>::flush_inner(mb).await
    }
    pub async fn flush_any(&self) {
        CanTx::<T>::flush_any_inner().await
    }
    pub async fn flush_all(&self) {
        CanTx::<T>::flush_all_inner().await
    }
    pub async fn read(&mut self) -> Result<Envelope, BusError> {
        self.split().1.read().await
    }
    pub fn try_read(&mut self) -> Result<Envelope, TryReadError> {
        self.split().1.try_read()
    }
    pub async fn wait_not_empty(&mut self) {
        self.split().1.wait_not_empty().await
    }
    unsafe fn receive_fifo(fifo: RxFifo) {
        #[cfg(feature = "time")]
        let ts = embassy_time::Instant::now();
        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 rfr.read().fmp() == 0 {
                return;
            }
            let rir = fifo.rir().read();
            let id = if rir.ide() == Ide::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);
                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 frame = Frame::new_data(id, Data::new(&data[0..data_len]).unwrap());
            let envelope = Envelope {
                #[cfg(feature = "time")]
                ts,
                frame,
            };
            rfr.modify(|v| v.set_rfom(true));
            let _ = state.rx_queue.try_send(envelope);
        }
    }
    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;
        }
        let max_quanta_per_bit: u8 = if can_bitrate >= 1_000_000 { 10 } else { 17 };
        let prescaler_bs = periph_clock / can_bitrate;
        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; }
            bs1_bs2_sum -= 1;
        }
        let prescaler = prescaler_bs / (1 + bs1_bs2_sum) as u32;
        if (prescaler < 1) || (prescaler > 1024) {
            return None; }
        let mut bs1 = ((7 * bs1_bs2_sum - 1) + 4) / 8; 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 {
            bs1 = (7 * bs1_bs2_sum - 1) / 8;
            bs2 = bs1_bs2_sum - bs1;
        }
        if (bs1 < 1) || (bs1 > BS1_MAX) || (bs2 < 1) || (bs2 > BS2_MAX) {
            return None;
        }
        if can_bitrate != (periph_clock / (prescaler * (1 + bs1 + bs2) as u32)) {
            return None;
        }
        let sjw = 1;
        Some((sjw - 1) << 24 | (bs1 as u32 - 1) << 16 | (bs2 as u32 - 1) << 20 | (prescaler - 1))
    }
    pub fn split<'c>(&'c mut self) -> (CanTx<'c, 'd, T>, CanRx<'c, 'd, T>) {
        let (tx, rx0, rx1) = self.can.split_by_ref();
        (CanTx { tx }, CanRx { rx0, rx1 })
    }
}
impl<'d, T: Instance> AsMut<bxcan::Can<BxcanInstance<'d, T>>> for Can<'d, T> {
    fn as_mut(&mut self) -> &mut bxcan::Can<BxcanInstance<'d, T>> {
        &mut self.can
    }
}
pub struct CanTx<'c, 'd, T: Instance> {
    tx: &'c mut bxcan::Tx<BxcanInstance<'d, T>>,
}
impl<'c, 'd, T: Instance> CanTx<'c, 'd, T> {
    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.tx.transmit(frame) {
                return Poll::Ready(status);
            }
            Poll::Pending
        })
        .await
    }
    pub fn try_write(&mut self, frame: &Frame) -> Result<bxcan::TransmitStatus, TryWriteError> {
        self.tx.transmit(frame).map_err(|_| TryWriteError::Full)
    }
    async fn flush_inner(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;
    }
    pub async fn flush(&self, mb: bxcan::Mailbox) {
        Self::flush_inner(mb).await
    }
    async fn flush_any_inner() {
        poll_fn(|cx| {
            T::state().tx_waker.register(cx.waker());
            let tsr = T::regs().tsr().read();
            if tsr.tme(bxcan::Mailbox::Mailbox0.index())
                || tsr.tme(bxcan::Mailbox::Mailbox1.index())
                || tsr.tme(bxcan::Mailbox::Mailbox2.index())
            {
                return Poll::Ready(());
            }
            Poll::Pending
        })
        .await;
    }
    pub async fn flush_any(&self) {
        Self::flush_any_inner().await
    }
    async fn flush_all_inner() {
        poll_fn(|cx| {
            T::state().tx_waker.register(cx.waker());
            let tsr = T::regs().tsr().read();
            if tsr.tme(bxcan::Mailbox::Mailbox0.index())
                && tsr.tme(bxcan::Mailbox::Mailbox1.index())
                && tsr.tme(bxcan::Mailbox::Mailbox2.index())
            {
                return Poll::Ready(());
            }
            Poll::Pending
        })
        .await;
    }
    pub async fn flush_all(&self) {
        Self::flush_all_inner().await
    }
}
#[allow(dead_code)]
pub struct CanRx<'c, 'd, T: Instance> {
    rx0: &'c mut bxcan::Rx0<BxcanInstance<'d, T>>,
    rx1: &'c mut bxcan::Rx1<BxcanInstance<'d, T>>,
}
impl<'c, 'd, T: Instance> CanRx<'c, 'd, T> {
    pub async fn read(&mut self) -> Result<Envelope, BusError> {
        poll_fn(|cx| {
            T::state().err_waker.register(cx.waker());
            if let Poll::Ready(envelope) = T::state().rx_queue.receive().poll_unpin(cx) {
                return Poll::Ready(Ok(envelope));
            } else if let Some(err) = self.curr_error() {
                return Poll::Ready(Err(err));
            }
            Poll::Pending
        })
        .await
    }
    pub fn try_read(&mut self) -> Result<Envelope, TryReadError> {
        if let Ok(envelope) = T::state().rx_queue.try_receive() {
            return Ok(envelope);
        }
        if let Some(err) = self.curr_error() {
            return Err(TryReadError::BusError(err));
        }
        Err(TryReadError::Empty)
    }
    pub async fn wait_not_empty(&mut self) {
        poll_fn(|cx| T::state().rx_queue.poll_ready_to_receive(cx)).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
    }
}
enum RxFifo {
    Fifo0,
    Fifo1,
}
impl<'d, T: Instance> Drop for Can<'d, T> {
    fn drop(&mut self) {
        T::regs().mcr().write(|w| w.set_reset(true));
        T::disable();
    }
}
impl<'d, T: Instance> Deref for Can<'d, T> {
    type Target = bxcan::Can<BxcanInstance<'d, T>>;
    fn deref(&self) -> &Self::Target {
        &self.can
    }
}
impl<'d, T: Instance> DerefMut for Can<'d, T> {
    fn deref_mut(&mut self) -> &mut Self::Target {
        &mut self.can
    }
}
pub(crate) mod sealed {
    use embassy_sync::blocking_mutex::raw::CriticalSectionRawMutex;
    use embassy_sync::channel::Channel;
    use embassy_sync::waitqueue::AtomicWaker;
    use super::Envelope;
    pub struct State {
        pub tx_waker: AtomicWaker,
        pub err_waker: AtomicWaker,
        pub rx_queue: Channel<CriticalSectionRawMutex, Envelope, 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() -> crate::pac::can::Can;
        fn state() -> &'static State;
    }
}
pub trait Instance: sealed::Instance + RccPeripheral + 'static {
    type TXInterrupt: crate::interrupt::typelevel::Interrupt;
    type RX0Interrupt: crate::interrupt::typelevel::Interrupt;
    type RX1Interrupt: crate::interrupt::typelevel::Interrupt;
    type SCEInterrupt: crate::interrupt::typelevel::Interrupt;
}
pub struct BxcanInstance<'a, T>(PeripheralRef<'a, T>);
unsafe impl<'d, T: Instance> bxcan::Instance for BxcanInstance<'d, T> {
    const REGISTERS: *mut bxcan::RegisterBlock = T::REGISTERS;
}
foreach_peripheral!(
    (can, $inst:ident) => {
        impl sealed::Instance for peripherals::$inst {
            const REGISTERS: *mut bxcan::RegisterBlock = crate::pac::$inst.as_ptr() as *mut _;
            fn regs() -> 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 {
            type TXInterrupt = crate::_generated::peripheral_interrupts::$inst::TX;
            type RX0Interrupt = crate::_generated::peripheral_interrupts::$inst::RX0;
            type RX1Interrupt = crate::_generated::peripheral_interrupts::$inst::RX1;
            type SCEInterrupt = crate::_generated::peripheral_interrupts::$inst::SCE;
        }
    };
);
foreach_peripheral!(
    (can, CAN) => {
        unsafe impl<'d> bxcan::FilterOwner for BxcanInstance<'d, peripherals::CAN> {
            const NUM_FILTER_BANKS: u8 = 14;
        }
    };
    (can, CAN1) => {
        cfg_if::cfg_if! {
            if #[cfg(all(
                any(stm32l4, stm32f72, stm32f73),
                not(any(stm32l49, stm32l4a))
            ))] {
                unsafe impl<'d> bxcan::FilterOwner for BxcanInstance<'d, peripherals::CAN1> {
                    const NUM_FILTER_BANKS: u8 = 14;
                }
            } else {
                unsafe impl<'d> bxcan::FilterOwner for BxcanInstance<'d, peripherals::CAN1> {
                    const NUM_FILTER_BANKS: u8 = 28;
                }
                unsafe impl<'d> bxcan::MasterInstance for BxcanInstance<'d, peripherals::CAN1> {}
            }
        }
    };
    (can, CAN3) => {
        unsafe impl<'d> bxcan::FilterOwner for BxcanInstance<'d, peripherals::CAN3> {
            const NUM_FILTER_BANKS: u8 = 14;
        }
    };
);
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,
        }
    }
}