Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions CHANGELOG.md
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,7 @@ and this project adheres to [Semantic Versioning](http://semver.org/).

### Added

- `Serial` support for UART4/5
- Allow to set HSE bypass bit in `RCC` clock configuration register to use an external clock input on the `OSC_IN` pin [#485]
- initial support of `embedded-hal-1.0` [#416]
- Add tools/check.py python script for local check [#467]
Expand Down
2 changes: 1 addition & 1 deletion Cargo.toml
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@ vcell = "0.1.3"

[dependencies.stm32f1]
package = "stm32f1-staging"
version = "0.17.1"
version = "0.19.0"
features = ["atomics"]

[dependencies.embedded-hal-02]
Expand Down
9 changes: 4 additions & 5 deletions examples/can-echo.rs
Original file line number Diff line number Diff line change
Expand Up @@ -29,11 +29,10 @@ fn main() -> ! {
let rx = gpioa.pa11;
let tx = gpioa.pa12;

let can = dp.CAN1.can(
#[cfg(not(feature = "connectivity"))]
dp.USB,
(tx, rx),
);
#[cfg(not(feature = "connectivity"))]
let can = dp.CAN.can(dp.USB, (tx, rx));
#[cfg(feature = "connectivity")]
let can = dp.CAN1.can((tx, rx));

// APB1 (PCLK1): 8MHz, Bit rate: 125kBit/s, Sample Point 87.5%
// Value was calculated with http://www.bittiming.can-wiki.info/
Expand Down
9 changes: 4 additions & 5 deletions examples/can-loopback.rs
Original file line number Diff line number Diff line change
Expand Up @@ -25,11 +25,10 @@ fn main() -> ! {
// resonator must be used.
rcc.cfgr.use_hse(8.MHz()).freeze(&mut flash.acr);

let can = Can::<_, Floating>::new_loopback(
dp.CAN1,
#[cfg(not(feature = "connectivity"))]
dp.USB,
);
#[cfg(not(feature = "connectivity"))]
let can = Can::<_, Floating>::new_loopback(dp.CAN, dp.USB);
#[cfg(feature = "connectivity")]
let can = Can::<_, Floating>::new_loopback(dp.CAN1);

// Use loopback mode: No pins need to be assigned to peripheral.
// APB1 (PCLK1): 8MHz, Bit rate: 500Bit/s, Sample Point 87.5%
Expand Down
8 changes: 6 additions & 2 deletions examples/can-rtic.rs
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,11 @@ mod app {
use super::{enqueue_frame, PriorityFrame};
use bxcan::{filter::Mask32, ExtendedId, Fifo, Frame, Interrupts, Rx0, StandardId, Tx};
use heapless::binary_heap::{BinaryHeap, Max};
use stm32f1xx_hal::{can::Can, pac::CAN1, prelude::*};
#[cfg(not(feature = "connectivity"))]
use stm32f1xx_hal::pac::CAN as CAN1;
#[cfg(feature = "connectivity")]
use stm32f1xx_hal::pac::CAN1;
use stm32f1xx_hal::{can::Can, prelude::*};

#[local]
struct Local {
Expand Down Expand Up @@ -88,7 +92,7 @@ mod app {
let can_tx_pin = gpioa.pa12;

#[cfg(not(feature = "connectivity"))]
let can = Can::new(cx.device.CAN1, cx.device.USB, (can_tx_pin, can_rx_pin));
let can = Can::new(cx.device.CAN, cx.device.USB, (can_tx_pin, can_rx_pin));

#[cfg(feature = "connectivity")]
let can = Can::new(cx.device.CAN1, (can_tx_pin, can_rx_pin));
Expand Down
8 changes: 6 additions & 2 deletions src/afio.rs
Original file line number Diff line number Diff line change
Expand Up @@ -215,7 +215,7 @@ remap! {

#[cfg(feature = "stm32f103")]
remap! {
pac::CAN1: MAPR, u8: can_remap, { 0 | 2 | 3 };
pac::CAN: MAPR, u8: can_remap, { 0 | 2 | 3 };
}

#[cfg(feature = "connectivity")]
Expand Down Expand Up @@ -303,7 +303,11 @@ pub mod can1 {
],
}

impl CanCommon for pac::CAN1 {
#[cfg(not(feature = "connectivity"))]
use pac::CAN as CAN1;
#[cfg(feature = "connectivity")]
use pac::CAN1;
impl CanCommon for CAN1 {
type Tx = Tx;
type Rx<PULL> = Rx<PULL>;
}
Expand Down
15 changes: 10 additions & 5 deletions src/can.rs
Original file line number Diff line number Diff line change
Expand Up @@ -58,7 +58,12 @@ impl<CAN: Instance> CanExt for CAN {
}

pub trait Instance: crate::rcc::Enable + afio::CanCommon {}
impl Instance for pac::CAN1 {}
#[cfg(not(feature = "connectivity"))]
use pac::CAN as CAN1;
#[cfg(feature = "connectivity")]
use pac::CAN1;

impl Instance for CAN1 {}
#[cfg(feature = "connectivity")]
impl Instance for pac::CAN2 {}

Expand Down Expand Up @@ -125,18 +130,18 @@ impl<CAN: Instance, PULL: UpMode> Can<CAN, PULL> {
}
}

unsafe impl<PULL> bxcan::Instance for Can<pac::CAN1, PULL> {
const REGISTERS: *mut bxcan::RegisterBlock = pac::CAN1::ptr() as *mut _;
unsafe impl<PULL> bxcan::Instance for Can<CAN1, PULL> {
const REGISTERS: *mut bxcan::RegisterBlock = CAN1::ptr() as *mut _;
}

#[cfg(feature = "connectivity")]
unsafe impl<PULL> bxcan::Instance for Can<pac::CAN2, PULL> {
const REGISTERS: *mut bxcan::RegisterBlock = pac::CAN2::ptr() as *mut _;
}

unsafe impl<PULL> bxcan::FilterOwner for Can<pac::CAN1, PULL> {
unsafe impl<PULL> bxcan::FilterOwner for Can<CAN1, PULL> {
const NUM_FILTER_BANKS: u8 = 28;
}

#[cfg(feature = "connectivity")]
unsafe impl<PULL> bxcan::MasterInstance for Can<pac::CAN1, PULL> {}
unsafe impl<PULL> bxcan::MasterInstance for Can<CAN1, PULL> {}
4 changes: 2 additions & 2 deletions src/flash.rs
Original file line number Diff line number Diff line change
Expand Up @@ -63,7 +63,7 @@ pub struct FlashWriter<'a> {
flash_sz: FlashSize,
verify: bool,
}
impl<'a> FlashWriter<'a> {
impl FlashWriter<'_> {
fn unlock(&mut self) -> Result<()> {
// Wait for any ongoing operations
while self.flash.sr.sr().read().bsy().bit_is_set() {}
Expand Down Expand Up @@ -245,7 +245,7 @@ impl<'a> FlashWriter<'a> {

// Flash is written 16 bits at a time, so combine two bytes to get a
// half-word
let hword: u16 = (data[idx] as u16) | (data[idx + 1] as u16) << 8;
let hword: u16 = (data[idx] as u16) | ((data[idx + 1] as u16) << 8);

// NOTE(unsafe) Write to FLASH area with no side effects
unsafe { core::ptr::write_volatile(write_address, hword) };
Expand Down
3 changes: 1 addition & 2 deletions src/gpio.rs
Original file line number Diff line number Diff line change
Expand Up @@ -223,7 +223,7 @@ mod sealed {
}
}

use crate::pac::gpioa::crl::{CNF0 as Cnf, MODE0 as Mode};
use crate::pac::gpioa::crl::{CONFIG as Cnf, MODE as Mode};

use sealed::Interruptable;
pub(crate) use sealed::PinMode;
Expand Down Expand Up @@ -519,7 +519,6 @@ impl<const P: char, const N: u8, MODE> Pin<P, N, MODE> {
before changing its mode to an output to avoid
a short spike of an incorrect value
*/

#[inline(always)]
fn _set_state(&mut self, state: PinState) {
match state {
Expand Down
2 changes: 1 addition & 1 deletion src/i2c.rs
Original file line number Diff line number Diff line change
Expand Up @@ -282,7 +282,7 @@ impl<I2C: Instance> I2c<I2C> {
fn send_addr(&self, addr: u8, read: bool) {
self.i2c
.dr()
.write(|w| w.dr().set(addr << 1 | (u8::from(read))));
.write(|w| w.dr().set((addr << 1) | (u8::from(read))));
}

/// Generate STOP condition
Expand Down
15 changes: 15 additions & 0 deletions src/lib.rs
Original file line number Diff line number Diff line change
Expand Up @@ -157,3 +157,18 @@ mod sealed {
pub trait Sealed {}
}
use sealed::Sealed;
use stm32f1::Periph;

pub trait Ptr {
/// RegisterBlock structure
type RB;
/// Return the pointer to the register block
fn ptr() -> *const Self::RB;
}

impl<RB, const ADDR: usize> Ptr for Periph<RB, ADDR> {
type RB = RB;
fn ptr() -> *const Self::RB {
Self::ptr()
}
}
1 change: 0 additions & 1 deletion src/rcc.rs
Original file line number Diff line number Diff line change
Expand Up @@ -187,7 +187,6 @@ impl CFGR {
/// let mut rcc = dp.RCC.constrain();
/// let clocks = rcc.cfgr.freeze(&mut flash.acr);
/// ```

#[inline(always)]
pub fn freeze(self, acr: &mut ACR) -> Clocks {
let cfg = Config::from_cfgr(self);
Expand Down
2 changes: 1 addition & 1 deletion src/rcc/enable.rs
Original file line number Diff line number Diff line change
Expand Up @@ -65,7 +65,7 @@ macro_rules! ahb_bus {
#[cfg(feature = "stm32f103")]
bus! {
ADC2 => (APB2, 10),
CAN1 => (APB1, 25),
CAN => (APB1, 25),
}
#[cfg(feature = "connectivity")]
bus! {
Expand Down
3 changes: 1 addition & 2 deletions src/rtc.rs
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,6 @@ pub enum RestoredOrNewRtc<CS> {
[examples/rtc.rs]: https://github.com/stm32-rs/stm32f1xx-hal/blob/v0.7.0/examples/rtc.rs
[examples/blinky_rtc.rs]: https://github.com/stm32-rs/stm32f1xx-hal/blob/v0.7.0/examples/blinky_rtc.rs
*/

pub struct Rtc<CS = RtcClkLse> {
regs: RTC,
_clock_source: PhantomData<CS>,
Expand Down Expand Up @@ -360,7 +359,7 @@ impl<CS> Rtc<CS> {
// Wait for the APB1 interface to be ready
while !self.regs.crl().read().rsf().bit() {}

self.regs.cnth().read().bits() << 16 | self.regs.cntl().read().bits()
(self.regs.cnth().read().bits() << 16) | self.regs.cntl().read().bits()
}

/// Enables triggering the RTC interrupt every time the RTC counter is increased
Expand Down
76 changes: 58 additions & 18 deletions src/serial.rs
Original file line number Diff line number Diff line change
Expand Up @@ -96,15 +96,20 @@ use core::sync::atomic::{self, Ordering};
use embedded_dma::{ReadBuffer, WriteBuffer};

use crate::afio::{self, RInto, Rmp};
#[cfg(any(all(feature = "stm32f103", feature = "high"), feature = "connectivity"))]
use crate::dma::dma2;
use crate::dma::{self, dma1, CircBuffer, RxDma, Transfer, TxDma};
use crate::gpio::{Floating, PushPull, UpMode};
use crate::pac::{self, RCC};
use crate::rcc::{BusClock, Clocks, Enable, Reset};
use crate::time::{Bps, U32Ext};

pub mod ext;
mod hal_02;
mod hal_1;

use ext::{SrR, UartExt};

pub trait SerialExt: Sized + Instance {
fn serial<Otype, PULL: UpMode>(
self,
Expand Down Expand Up @@ -159,28 +164,56 @@ impl<USART: Instance> SerialExt for USART {
}
}

use crate::pac::usart1 as uart_base;
pub trait RBExt: UartExt {
fn set_stopbits(&self, bits: StopBits);
}

impl RBExt for pac::usart1::RegisterBlock {
fn set_stopbits(&self, bits: StopBits) {
use crate::pac::usart1::cr2::STOP;

self.cr2().write(|w| {
w.stop().variant(match bits {
StopBits::STOP0P5 => STOP::Stop0p5,
StopBits::STOP1 => STOP::Stop1,
StopBits::STOP1P5 => STOP::Stop1p5,
StopBits::STOP2 => STOP::Stop2,
})
});
}
}

#[cfg(any(all(feature = "stm32f103", feature = "high"), feature = "connectivity"))]
impl RBExt for pac::uart4::RegisterBlock {
fn set_stopbits(&self, bits: StopBits) {
use crate::pac::uart4::cr2::STOP;

// StopBits::STOP0P5 and StopBits::STOP1P5 aren't supported when using UART
// STOP_A::STOP1 and STOP_A::STOP2 will be used, respectively
self.cr2().write(|w| {
w.stop().variant(match bits {
StopBits::STOP0P5 | StopBits::STOP1 => STOP::Stop1,
StopBits::STOP1P5 | StopBits::STOP2 => STOP::Stop2,
})
});
}
}

pub trait Instance:
crate::Sealed
+ Deref<Target = uart_base::RegisterBlock>
+ crate::Ptr<RB: RBExt>
+ Deref<Target = Self::RB>
+ Enable
+ Reset
+ BusClock
+ afio::SerialAsync
{
#[doc(hidden)]
fn ptr() -> *const uart_base::RegisterBlock;
}

macro_rules! inst {
($($USARTX:ty;)+) => {
$(
impl Instance for $USARTX {
fn ptr() -> *const uart_base::RegisterBlock {
<$USARTX>::ptr()
}
}
impl Instance for $USARTX { }
)+
};
}
Expand All @@ -190,6 +223,11 @@ inst! {
pac::USART2;
pac::USART3;
}
#[cfg(any(all(feature = "stm32f103", feature = "high"), feature = "connectivity"))]
inst! {
pac::UART4;
pac::UART5;
}

/// Serial error
#[derive(Debug)]
Expand Down Expand Up @@ -519,7 +557,7 @@ fn apply_config<USART: Instance>(config: Config, clocks: &Clocks) {
// Configure baud rate
let brr = USART::clock(clocks).raw() / config.baudrate.0;
assert!(brr >= 16, "impossible baud rate");
usart.brr().write(|w| unsafe { w.bits(brr) });
usart.brr().write(|w| unsafe { w.bits(brr as u16) });

// Configure word
usart.cr1().modify(|_r, w| {
Expand All @@ -537,13 +575,7 @@ fn apply_config<USART: Instance>(config: Config, clocks: &Clocks) {
});

// Configure stop bits
let stop_bits = match config.stopbits {
StopBits::STOP1 => 0b00,
StopBits::STOP0P5 => 0b01,
StopBits::STOP2 => 0b10,
StopBits::STOP1P5 => 0b11,
};
usart.cr2().modify(|_r, w| w.stop().set(stop_bits));
usart.set_stopbits(config.stopbits);
}

/// Reconfigure the USART instance.
Expand Down Expand Up @@ -657,7 +689,7 @@ impl<USART: Instance> Rx<USART> {
Some(Error::Parity)
} else if sr.fe().bit_is_set() {
Some(Error::FrameFormat)
} else if sr.ne().bit_is_set() {
} else if sr.nf().bit_is_set() {
Some(Error::Noise)
} else if sr.ore().bit_is_set() {
Some(Error::Overrun)
Expand Down Expand Up @@ -1002,3 +1034,11 @@ serialdma! {
rx: dma1::C3,
tx: dma1::C2
}
#[cfg(any(all(feature = "stm32f103", feature = "high"), feature = "connectivity"))]
serialdma! {
pac::UART4,
RxDma4,
TxDma4,
rx: dma2::C3,
tx: dma2::C5
}
Loading
Loading