Merge pull request #2469 from embassy-rs/nrf51-basic-support

feat: add basic support for nRF51 chips to embassy-nrf
This commit is contained in:
Dario Nieuwenhuis 2024-01-31 00:20:40 +00:00 committed by GitHub
commit 68be63c0e8
No known key found for this signature in database
GPG key ID: B5690EEEBB952194
33 changed files with 503 additions and 83 deletions

7
ci.sh
View file

@ -67,6 +67,9 @@ cargo batch \
--- build --release --manifest-path embassy-nrf/Cargo.toml --target thumbv7em-none-eabi --features nrf52840,gpiote,defmt,time \
--- build --release --manifest-path embassy-nrf/Cargo.toml --target thumbv7em-none-eabi --features nrf52840,gpiote,defmt,time-driver-rtc1 \
--- build --release --manifest-path embassy-nrf/Cargo.toml --target thumbv7em-none-eabi --features nrf52840,gpiote,defmt,time,time-driver-rtc1 \
--- build --release --manifest-path embassy-nrf/Cargo.toml --target thumbv6m-none-eabi --features nrf51,defmt,time,time-driver-rtc1 \
--- build --release --manifest-path embassy-nrf/Cargo.toml --target thumbv6m-none-eabi --features nrf51,defmt,time \
--- build --release --manifest-path embassy-nrf/Cargo.toml --target thumbv6m-none-eabi --features nrf51,time \
--- build --release --manifest-path embassy-rp/Cargo.toml --target thumbv6m-none-eabi --features time-driver,defmt \
--- build --release --manifest-path embassy-rp/Cargo.toml --target thumbv6m-none-eabi --features time-driver,log \
--- build --release --manifest-path embassy-rp/Cargo.toml --target thumbv6m-none-eabi --features time-driver,intrinsics \
@ -148,6 +151,7 @@ cargo batch \
--- build --release --manifest-path examples/nrf52840/Cargo.toml --target thumbv7em-none-eabi --out-dir out/examples/nrf52840 \
--- build --release --manifest-path examples/nrf5340/Cargo.toml --target thumbv8m.main-none-eabihf --out-dir out/examples/nrf5340 \
--- build --release --manifest-path examples/nrf9160/Cargo.toml --target thumbv8m.main-none-eabihf --out-dir out/examples/nrf9160 \
--- build --release --manifest-path examples/nrf51/Cargo.toml --target thumbv6m-none-eabi --out-dir out/examples/nrf51 \
--- build --release --manifest-path examples/rp/Cargo.toml --target thumbv6m-none-eabi --out-dir out/examples/rp \
--- build --release --manifest-path examples/stm32f0/Cargo.toml --target thumbv6m-none-eabi --out-dir out/examples/stm32f0 \
--- build --release --manifest-path examples/stm32f1/Cargo.toml --target thumbv7m-none-eabi --out-dir out/examples/stm32f1 \
@ -211,7 +215,8 @@ cargo batch \
--- build --release --manifest-path tests/stm32/Cargo.toml --target thumbv7em-none-eabi --features stm32l496zg --out-dir out/tests/stm32l496zg \
--- build --release --manifest-path tests/stm32/Cargo.toml --target thumbv7em-none-eabi --features stm32wl55jc --out-dir out/tests/stm32wl55jc \
--- build --release --manifest-path tests/rp/Cargo.toml --target thumbv6m-none-eabi --out-dir out/tests/rpi-pico \
--- build --release --manifest-path tests/nrf/Cargo.toml --target thumbv7em-none-eabi --out-dir out/tests/nrf52840-dk \
--- build --release --manifest-path tests/nrf52840/Cargo.toml --target thumbv7em-none-eabi --out-dir out/tests/nrf52840-dk \
--- build --release --manifest-path tests/nrf51422/Cargo.toml --target thumbv6m-none-eabi --out-dir out/tests/nrf51-dk \
--- build --release --manifest-path tests/riscv32/Cargo.toml --target riscv32imac-unknown-none-elf \
$BUILD_EXTRA

View file

@ -15,6 +15,7 @@ src_base_git = "https://github.com/embassy-rs/embassy/blob/$COMMIT/embassy-nrf/s
features = ["time", "defmt", "unstable-pac", "gpiote", "time-driver-rtc1"]
flavors = [
{ regex_feature = "nrf51", target = "thumbv6m-none-eabi" },
{ regex_feature = "nrf52.*", target = "thumbv7em-none-eabihf" },
{ regex_feature = "nrf53.*", target = "thumbv8m.main-none-eabihf" },
{ regex_feature = "nrf91.*", target = "thumbv8m.main-none-eabihf" },
@ -28,6 +29,7 @@ rustdoc-args = ["--cfg", "docsrs"]
default = ["rt"]
## Cortex-M runtime (enabled by default)
rt = [
"nrf51-pac?/rt",
"nrf52805-pac?/rt",
"nrf52810-pac?/rt",
"nrf52811-pac?/rt",
@ -71,6 +73,8 @@ reset-pin-as-gpio = []
qspi-multiwrite-flash = []
#! ### Chip selection features
## nRF51
nrf51 = ["nrf51-pac", "_nrf51"]
## nRF52805
nrf52805 = ["nrf52805-pac", "_nrf52"]
## nRF52810
@ -104,6 +108,7 @@ _nrf5340-net = ["_nrf5340", "nrf5340-net-pac"]
_nrf5340 = ["_gpio-p1", "_dppi"]
_nrf9160 = ["nrf9160-pac", "_dppi"]
_nrf52 = ["_ppi"]
_nrf51 = ["_ppi"]
_time-driver = ["dep:embassy-time-driver", "embassy-time-driver?/tick-hz-32_768"]
@ -144,6 +149,7 @@ embedded-storage-async = "0.4.0"
cfg-if = "1.0.0"
document-features = "0.2.7"
nrf51-pac = { version = "0.12.0", optional = true }
nrf52805-pac = { version = "0.12.0", optional = true }
nrf52810-pac = { version = "0.12.0", optional = true }
nrf52811-pac = { version = "0.12.0", optional = true }

View file

@ -14,11 +14,12 @@ For a complete list of available peripherals and features, see the [embassy-nrf
The `embassy-nrf` HAL supports most variants of the nRF family:
* nRF51 ([examples](https://github.com/embassy-rs/embassy/tree/main/examples/nrf51))
* nRF52 ([examples](https://github.com/embassy-rs/embassy/tree/main/examples/nrf52840))
* nRF53 ([examples](https://github.com/embassy-rs/embassy/tree/main/examples/nrf5340))
* nRF91 ([examples](https://github.com/embassy-rs/embassy/tree/main/examples/nrf9160))
Most peripherals are supported. To check what's available, make sure to pick the MCU you're targeting in the top menu in the [documentation](https://docs.embassy.dev/embassy-nrf).
Most peripherals are supported, but can vary between chip families. To check what's available, make sure to pick the MCU you're targeting in the top menu in the [documentation](https://docs.embassy.dev/embassy-nrf).
For MCUs with TrustZone support, both Secure (S) and Non-Secure (NS) modes are supported. Running in Secure mode
allows running Rust code without a SPM or TF-M binary, saving flash space and simplifying development.

View file

@ -0,0 +1,169 @@
pub use nrf51_pac as pac;
/// The maximum buffer size that the EasyDMA can send/recv in one operation.
pub const EASY_DMA_SIZE: usize = (1 << 14) - 1;
pub const FLASH_SIZE: usize = 128 * 1024;
embassy_hal_internal::peripherals! {
// RTC
RTC0,
RTC1,
// WDT
WDT,
// NVMC
NVMC,
// RNG
RNG,
// UARTE
UART0,
// SPI/TWI
TWI0,
SPI0,
// ADC
ADC,
// TIMER
TIMER0,
TIMER1,
TIMER2,
// GPIOTE
GPIOTE_CH0,
GPIOTE_CH1,
GPIOTE_CH2,
GPIOTE_CH3,
// PPI
PPI_CH0,
PPI_CH1,
PPI_CH2,
PPI_CH3,
PPI_CH4,
PPI_CH5,
PPI_CH6,
PPI_CH7,
PPI_CH8,
PPI_CH9,
PPI_CH10,
PPI_CH11,
PPI_CH12,
PPI_CH13,
PPI_CH14,
PPI_CH15,
PPI_GROUP0,
PPI_GROUP1,
PPI_GROUP2,
PPI_GROUP3,
// GPIO port 0
P0_00,
P0_01,
P0_02,
P0_03,
P0_04,
P0_05,
P0_06,
P0_07,
P0_08,
P0_09,
P0_10,
P0_11,
P0_12,
P0_13,
P0_14,
P0_15,
P0_16,
P0_17,
P0_18,
P0_19,
P0_20,
P0_21,
P0_22,
P0_23,
P0_24,
P0_25,
P0_26,
P0_27,
P0_28,
P0_29,
P0_30,
P0_31,
// TEMP
TEMP,
}
impl_timer!(TIMER0, TIMER0, TIMER0);
impl_timer!(TIMER1, TIMER1, TIMER1);
impl_timer!(TIMER2, TIMER2, TIMER2);
impl_rng!(RNG, RNG, RNG);
impl_pin!(P0_00, 0, 0);
impl_pin!(P0_01, 0, 1);
impl_pin!(P0_02, 0, 2);
impl_pin!(P0_03, 0, 3);
impl_pin!(P0_04, 0, 4);
impl_pin!(P0_05, 0, 5);
impl_pin!(P0_06, 0, 6);
impl_pin!(P0_07, 0, 7);
impl_pin!(P0_08, 0, 8);
impl_pin!(P0_09, 0, 9);
impl_pin!(P0_10, 0, 10);
impl_pin!(P0_11, 0, 11);
impl_pin!(P0_12, 0, 12);
impl_pin!(P0_13, 0, 13);
impl_pin!(P0_14, 0, 14);
impl_pin!(P0_15, 0, 15);
impl_pin!(P0_16, 0, 16);
impl_pin!(P0_17, 0, 17);
impl_pin!(P0_18, 0, 18);
impl_pin!(P0_19, 0, 19);
impl_pin!(P0_20, 0, 20);
impl_pin!(P0_21, 0, 21);
impl_pin!(P0_22, 0, 22);
impl_pin!(P0_23, 0, 23);
impl_pin!(P0_24, 0, 24);
impl_pin!(P0_25, 0, 25);
impl_pin!(P0_26, 0, 26);
impl_pin!(P0_27, 0, 27);
impl_pin!(P0_28, 0, 28);
impl_pin!(P0_29, 0, 29);
impl_pin!(P0_30, 0, 30);
impl_pin!(P0_31, 0, 31);
embassy_hal_internal::interrupt_mod!(
POWER_CLOCK,
RADIO,
UART0,
SPI0_TWI0,
SPI1_TWI1,
GPIOTE,
ADC,
TIMER0,
TIMER1,
TIMER2,
RTC0,
TEMP,
RNG,
ECB,
CCM_AAR,
WDT,
RTC1,
QDEC,
LPCOMP,
SWI0,
SWI1,
SWI2,
SWI3,
SWI4,
SWI5,
);

View file

@ -8,7 +8,13 @@ use cfg_if::cfg_if;
use embassy_hal_internal::{impl_peripheral, into_ref, PeripheralRef};
use self::sealed::Pin as _;
#[cfg(feature = "nrf51")]
use crate::pac::gpio;
#[cfg(feature = "nrf51")]
use crate::pac::gpio::pin_cnf::{DRIVE_A, PULL_A};
#[cfg(not(feature = "nrf51"))]
use crate::pac::p0 as gpio;
#[cfg(not(feature = "nrf51"))]
use crate::pac::p0::pin_cnf::{DRIVE_A, PULL_A};
use crate::{pac, Peripheral};
@ -376,6 +382,9 @@ pub(crate) mod sealed {
fn block(&self) -> &gpio::RegisterBlock {
unsafe {
match self.pin_port() / 32 {
#[cfg(feature = "nrf51")]
0 => &*pac::GPIO::ptr(),
#[cfg(not(feature = "nrf51"))]
0 => &*pac::P0::ptr(),
#[cfg(feature = "_gpio-p1")]
1 => &*pac::P1::ptr(),
@ -478,6 +487,7 @@ impl<'a, P: Pin> PselBits for Option<PeripheralRef<'a, P>> {
}
}
#[allow(dead_code)]
pub(crate) fn deconfigure_pin(psel_bits: u32) {
if psel_bits & 0x8000_0000 != 0 {
return;

View file

@ -40,6 +40,7 @@ pub(crate) mod util;
#[cfg(feature = "_time-driver")]
mod time_driver;
#[cfg(not(feature = "nrf51"))]
pub mod buffered_uarte;
pub mod gpio;
#[cfg(feature = "gpiote")]
@ -58,7 +59,12 @@ pub mod nvmc;
))]
pub mod pdm;
pub mod ppi;
#[cfg(not(any(feature = "nrf52805", feature = "nrf52820", feature = "_nrf5340-net")))]
#[cfg(not(any(
feature = "nrf51",
feature = "nrf52805",
feature = "nrf52820",
feature = "_nrf5340-net"
)))]
pub mod pwm;
#[cfg(not(any(feature = "nrf51", feature = "_nrf9160", feature = "_nrf5340-net")))]
pub mod qdec;
@ -66,15 +72,20 @@ pub mod qdec;
pub mod qspi;
#[cfg(not(any(feature = "_nrf5340-app", feature = "_nrf9160")))]
pub mod rng;
#[cfg(not(any(feature = "nrf52820", feature = "_nrf5340-net")))]
#[cfg(not(any(feature = "nrf51", feature = "nrf52820", feature = "_nrf5340-net")))]
pub mod saadc;
#[cfg(not(feature = "nrf51"))]
pub mod spim;
#[cfg(not(feature = "nrf51"))]
pub mod spis;
#[cfg(not(any(feature = "_nrf5340", feature = "_nrf9160")))]
pub mod temp;
pub mod timer;
#[cfg(not(feature = "nrf51"))]
pub mod twim;
#[cfg(not(feature = "nrf51"))]
pub mod twis;
#[cfg(not(feature = "nrf51"))]
pub mod uarte;
#[cfg(any(
feature = "_nrf5340-app",
@ -87,6 +98,7 @@ pub mod usb;
pub mod wdt;
// This mod MUST go last, so that it sees all the `impl_foo!` macros
#[cfg_attr(feature = "nrf51", path = "chips/nrf51.rs")]
#[cfg_attr(feature = "nrf52805", path = "chips/nrf52805.rs")]
#[cfg_attr(feature = "nrf52810", path = "chips/nrf52810.rs")]
#[cfg_attr(feature = "nrf52811", path = "chips/nrf52811.rs")]
@ -324,6 +336,7 @@ mod consts {
pub const APPROTECT_DISABLED: u32 = 0x0000_005a;
}
#[cfg(not(feature = "nrf51"))]
#[derive(Debug, Copy, Clone, Eq, PartialEq)]
#[cfg_attr(feature = "defmt", derive(defmt::Format))]
enum WriteResult {
@ -335,10 +348,12 @@ enum WriteResult {
Failed,
}
#[cfg(not(feature = "nrf51"))]
unsafe fn uicr_write(address: *mut u32, value: u32) -> WriteResult {
uicr_write_masked(address, value, 0xFFFF_FFFF)
}
#[cfg(not(feature = "nrf51"))]
unsafe fn uicr_write_masked(address: *mut u32, value: u32, mask: u32) -> WriteResult {
let curr_val = address.read_volatile();
if curr_val & mask == value & mask {
@ -371,9 +386,11 @@ pub fn init(config: config::Config) -> Peripherals {
// before doing anything important.
let peripherals = Peripherals::take();
#[allow(unused_mut)]
let mut needs_reset = false;
// Setup debug protection.
#[cfg(not(feature = "nrf51"))]
match config.debug {
config::Debug::Allowed => {
#[cfg(feature = "_nrf52")]
@ -489,7 +506,7 @@ pub fn init(config: config::Config) -> Peripherals {
}
// Configure LFCLK.
#[cfg(not(any(feature = "_nrf5340", feature = "_nrf9160")))]
#[cfg(not(any(feature = "nrf51", feature = "_nrf5340", feature = "_nrf9160")))]
match config.lfclk_source {
config::LfclkSource::InternalRC => r.lfclksrc.write(|w| w.src().rc()),
config::LfclkSource::Synthesized => r.lfclksrc.write(|w| w.src().synth()),

View file

@ -284,6 +284,7 @@ impl ConfigurableChannel for AnyConfigurableChannel {
}
}
#[cfg(not(feature = "nrf51"))]
macro_rules! impl_ppi_channel {
($type:ident, $number:expr) => {
impl crate::ppi::sealed::Channel for peripherals::$type {}

View file

@ -1,6 +1,6 @@
use embassy_hal_internal::into_ref;
use super::{Channel, ConfigurableChannel, Event, Ppi, StaticChannel, Task};
use super::{Channel, ConfigurableChannel, Event, Ppi, Task};
use crate::{pac, Peripheral};
impl<'d> Task<'d> {
@ -19,7 +19,7 @@ pub(crate) fn regs() -> &'static pac::ppi::RegisterBlock {
}
#[cfg(not(feature = "nrf51"))] // Not for nrf51 because of the fork task
impl<'d, C: StaticChannel> Ppi<'d, C, 0, 1> {
impl<'d, C: super::StaticChannel> Ppi<'d, C, 0, 1> {
/// Configure PPI channel to trigger `task`.
pub fn new_zero_to_one(ch: impl Peripheral<P = C> + 'd, task: Task) -> Self {
into_ref!(ch);
@ -84,6 +84,7 @@ impl<'d, C: Channel, const EVENT_COUNT: usize, const TASK_COUNT: usize> Drop for
let n = self.ch.number();
r.ch[n].eep.write(|w| unsafe { w.bits(0) });
r.ch[n].tep.write(|w| unsafe { w.bits(0) });
#[cfg(not(feature = "nrf51"))]
r.fork[n].tep.write(|w| unsafe { w.bits(0) });
}
}

View file

@ -5,12 +5,10 @@
use core::future::poll_fn;
use core::marker::PhantomData;
use core::ptr;
use core::sync::atomic::{AtomicPtr, Ordering};
use core::task::Poll;
use embassy_hal_internal::drop::OnDrop;
use embassy_hal_internal::{into_ref, PeripheralRef};
use embassy_sync::waitqueue::AtomicWaker;
use crate::interrupt::typelevel::Interrupt;
use crate::{interrupt, Peripheral};
@ -22,7 +20,6 @@ pub struct InterruptHandler<T: Instance> {
impl<T: Instance> interrupt::typelevel::Handler<T::Interrupt> for InterruptHandler<T> {
unsafe fn on_interrupt() {
let s = T::state();
let r = T::regs();
// Clear the event.
@ -30,46 +27,25 @@ impl<T: Instance> interrupt::typelevel::Handler<T::Interrupt> for InterruptHandl
// Mutate the slice within a critical section,
// so that the future isn't dropped in between us loading the pointer and actually dereferencing it.
let (ptr, end) = critical_section::with(|_| {
let ptr = s.ptr.load(Ordering::Relaxed);
critical_section::with(|cs| {
let mut state = T::state().borrow_mut(cs);
// We need to make sure we haven't already filled the whole slice,
// in case the interrupt fired again before the executor got back to the future.
let end = s.end.load(Ordering::Relaxed);
if !ptr.is_null() && ptr != end {
if !state.ptr.is_null() && state.ptr != state.end {
// If the future was dropped, the pointer would have been set to null,
// so we're still good to mutate the slice.
// The safety contract of `Rng::new` means that the future can't have been dropped
// without calling its destructor.
unsafe {
*ptr = r.value.read().value().bits();
*state.ptr = r.value.read().value().bits();
state.ptr = state.ptr.add(1);
}
if state.ptr == state.end {
state.waker.wake();
}
}
(ptr, end)
});
if ptr.is_null() || ptr == end {
// If the future was dropped, there's nothing to do.
// If `ptr == end`, we were called by mistake, so return.
return;
}
let new_ptr = unsafe { ptr.add(1) };
match s
.ptr
.compare_exchange(ptr, new_ptr, Ordering::Relaxed, Ordering::Relaxed)
{
Ok(_) => {
let end = s.end.load(Ordering::Relaxed);
// It doesn't matter if `end` was changed under our feet, because then this will just be false.
if new_ptr == end {
s.waker.wake();
}
}
Err(_) => {
// If the future was dropped or finished, there's no point trying to wake it.
// It will have already stopped the RNG, so there's no need to do that either.
}
}
}
}
@ -136,13 +112,14 @@ impl<'d, T: Instance> Rng<'d, T> {
return; // Nothing to fill
}
let s = T::state();
let range = dest.as_mut_ptr_range();
// Even if we've preempted the interrupt, it can't preempt us again,
// so we don't need to worry about the order we write these in.
s.ptr.store(range.start, Ordering::Relaxed);
s.end.store(range.end, Ordering::Relaxed);
critical_section::with(|cs| {
let mut state = T::state().borrow_mut(cs);
state.ptr = range.start;
state.end = range.end;
});
self.enable_irq();
self.start();
@ -151,24 +128,24 @@ impl<'d, T: Instance> Rng<'d, T> {
self.stop();
self.disable_irq();
// The interrupt is now disabled and can't preempt us anymore, so the order doesn't matter here.
s.ptr.store(ptr::null_mut(), Ordering::Relaxed);
s.end.store(ptr::null_mut(), Ordering::Relaxed);
critical_section::with(|cs| {
let mut state = T::state().borrow_mut(cs);
state.ptr = ptr::null_mut();
state.end = ptr::null_mut();
});
});
poll_fn(|cx| {
s.waker.register(cx.waker());
// The interrupt will never modify `end`, so load it first and then get the most up-to-date `ptr`.
let end = s.end.load(Ordering::Relaxed);
let ptr = s.ptr.load(Ordering::Relaxed);
if ptr == end {
// We're done.
Poll::Ready(())
} else {
Poll::Pending
}
critical_section::with(|cs| {
let mut s = T::state().borrow_mut(cs);
s.waker.register(cx.waker());
if s.ptr == s.end {
// We're done.
Poll::Ready(())
} else {
Poll::Pending
}
})
})
.await;
@ -194,9 +171,11 @@ impl<'d, T: Instance> Rng<'d, T> {
impl<'d, T: Instance> Drop for Rng<'d, T> {
fn drop(&mut self) {
self.stop();
let s = T::state();
s.ptr.store(ptr::null_mut(), Ordering::Relaxed);
s.end.store(ptr::null_mut(), Ordering::Relaxed);
critical_section::with(|cs| {
let mut state = T::state().borrow_mut(cs);
state.ptr = ptr::null_mut();
state.end = ptr::null_mut();
});
}
}
@ -227,21 +206,48 @@ impl<'d, T: Instance> rand_core::RngCore for Rng<'d, T> {
impl<'d, T: Instance> rand_core::CryptoRng for Rng<'d, T> {}
pub(crate) mod sealed {
use core::cell::{Ref, RefCell, RefMut};
use critical_section::{CriticalSection, Mutex};
use embassy_sync::waitqueue::WakerRegistration;
use super::*;
/// Peripheral static state
pub struct State {
pub ptr: AtomicPtr<u8>,
pub end: AtomicPtr<u8>,
pub waker: AtomicWaker,
inner: Mutex<RefCell<InnerState>>,
}
pub struct InnerState {
pub ptr: *mut u8,
pub end: *mut u8,
pub waker: WakerRegistration,
}
unsafe impl Send for InnerState {}
impl State {
pub const fn new() -> Self {
Self {
ptr: AtomicPtr::new(ptr::null_mut()),
end: AtomicPtr::new(ptr::null_mut()),
waker: AtomicWaker::new(),
inner: Mutex::new(RefCell::new(InnerState::new())),
}
}
pub fn borrow<'cs>(&'cs self, cs: CriticalSection<'cs>) -> Ref<'cs, InnerState> {
self.inner.borrow(cs).borrow()
}
pub fn borrow_mut<'cs>(&'cs self, cs: CriticalSection<'cs>) -> RefMut<'cs, InnerState> {
self.inner.borrow(cs).borrow_mut()
}
}
impl InnerState {
pub const fn new() -> Self {
Self {
ptr: ptr::null_mut(),
end: ptr::null_mut(),
waker: WakerRegistration::new(),
}
}
}

View file

@ -171,7 +171,8 @@ impl RtcDriver {
fn next_period(&self) {
critical_section::with(|cs| {
let r = rtc();
let period = self.period.fetch_add(1, Ordering::Relaxed) + 1;
let period = self.period.load(Ordering::Relaxed) + 1;
self.period.store(period, Ordering::Relaxed);
let t = (period as u64) << 23;
for n in 0..ALARM_COUNT {
@ -219,18 +220,15 @@ impl Driver for RtcDriver {
}
unsafe fn allocate_alarm(&self) -> Option<AlarmHandle> {
let id = self.alarm_count.fetch_update(Ordering::AcqRel, Ordering::Acquire, |x| {
if x < ALARM_COUNT as u8 {
Some(x + 1)
critical_section::with(|_| {
let id = self.alarm_count.load(Ordering::Relaxed);
if id < ALARM_COUNT as u8 {
self.alarm_count.store(id + 1, Ordering::Relaxed);
Some(AlarmHandle::new(id))
} else {
None
}
});
match id {
Ok(id) => Some(AlarmHandle::new(id)),
Err(_) => None,
}
})
}
fn set_alarm_callback(&self, alarm: AlarmHandle, callback: fn(*mut ()), ctx: *mut ()) {

View file

@ -111,7 +111,7 @@ impl<'d, T: Instance> Timer<'d, T> {
Self::new_inner(timer, true)
}
fn new_inner(timer: impl Peripheral<P = T> + 'd, is_counter: bool) -> Self {
fn new_inner(timer: impl Peripheral<P = T> + 'd, _is_counter: bool) -> Self {
into_ref!(timer);
let regs = T::regs();
@ -122,12 +122,16 @@ impl<'d, T: Instance> Timer<'d, T> {
// since changing BITMODE while running can cause 'unpredictable behaviour' according to the specification.
this.stop();
if is_counter {
#[cfg(not(feature = "nrf51"))]
if _is_counter {
regs.mode.write(|w| w.mode().low_power_counter());
} else {
regs.mode.write(|w| w.mode().timer());
}
#[cfg(feature = "nrf51")]
regs.mode.write(|w| w.mode().timer());
// Make the counter's max value as high as possible.
// TODO: is there a reason someone would want to set this lower?
regs.bitmode.write(|w| w.bitmode()._32bit());
@ -238,7 +242,11 @@ pub struct Cc<'d, T: Instance> {
impl<'d, T: Instance> Cc<'d, T> {
/// Get the current value stored in the register.
pub fn read(&self) -> u32 {
T::regs().cc[self.n].read().cc().bits()
#[cfg(not(feature = "nrf51"))]
return T::regs().cc[self.n].read().cc().bits();
#[cfg(feature = "nrf51")]
return T::regs().cc[self.n].read().bits();
}
/// Set the value stored in the register.
@ -246,7 +254,11 @@ impl<'d, T: Instance> Cc<'d, T> {
/// `event_compare` will fire when the timer's counter reaches this value.
pub fn write(&self, value: u32) {
// SAFETY: there are no invalid values for the CC register.
T::regs().cc[self.n].write(|w| unsafe { w.cc().bits(value) })
#[cfg(not(feature = "nrf51"))]
T::regs().cc[self.n].write(|w| unsafe { w.cc().bits(value) });
#[cfg(feature = "nrf51")]
T::regs().cc[self.n].write(|w| unsafe { w.bits(value) });
}
/// Capture the current value of the timer's counter in this register, and return it.

View file

@ -1,3 +1,4 @@
#![allow(dead_code)]
use core::mem;
const SRAM_LOWER: usize = 0x2000_0000;

View file

@ -0,0 +1,9 @@
[target.'cfg(all(target_arch = "arm", target_os = "none"))']
# replace nRF51422_xxAA with your chip as listed in `probe-rs chip list`
runner = "probe-rs run --chip nRF51422_xxAA"
[build]
target = "thumbv6m-none-eabi"
[env]
DEFMT_LOG = "trace"

20
examples/nrf51/Cargo.toml Normal file
View file

@ -0,0 +1,20 @@
[package]
edition = "2021"
name = "embassy-nrf51-examples"
version = "0.1.0"
license = "MIT OR Apache-2.0"
[dependencies]
embassy-executor = { version = "0.5.0", path = "../../embassy-executor", features = ["task-arena-size-4096", "arch-cortex-m", "executor-thread", "executor-interrupt", "defmt", "integrated-timers"] }
embassy-time = { version = "0.3.0", path = "../../embassy-time", features = ["defmt", "defmt-timestamp-uptime"] }
embassy-nrf = { version = "0.1.0", path = "../../embassy-nrf", features = ["defmt", "nrf51", "time-driver-rtc1", "unstable-pac", "time", "rt"] }
defmt = "0.3"
defmt-rtt = "0.4"
cortex-m = { version = "0.7.6", features = ["inline-asm", "critical-section-single-core"] }
cortex-m-rt = "0.7"
panic-probe = { version = "0.3", features = ["print-defmt"] }
[profile.release]
debug = 2

35
examples/nrf51/build.rs Normal file
View file

@ -0,0 +1,35 @@
//! 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");
}

5
examples/nrf51/memory.x Normal file
View file

@ -0,0 +1,5 @@
MEMORY
{
FLASH : ORIGIN = 0x00000000, LENGTH = 128K
RAM : ORIGIN = 0x20000000, LENGTH = 16K
}

View file

@ -0,0 +1,20 @@
#![no_std]
#![no_main]
use embassy_executor::Spawner;
use embassy_nrf::gpio::{Level, Output, OutputDrive};
use embassy_time::Timer;
use {defmt_rtt as _, panic_probe as _};
#[embassy_executor::main]
async fn main(_spawner: Spawner) {
let p = embassy_nrf::init(Default::default());
let mut led = Output::new(p.P0_21, Level::Low, OutputDrive::Standard);
loop {
led.set_high();
Timer::after_millis(300).await;
led.set_low();
Timer::after_millis(300).await;
}
}

View file

@ -0,0 +1,9 @@
[target.'cfg(all(target_arch = "arm", target_os = "none"))']
#runner = "teleprobe local run --chip nRF51422_xxAA --elf"
runner = "teleprobe client run"
[build]
target = "thumbv6m-none-eabi"
[env]
DEFMT_LOG = "trace,embassy_hal_internal=debug"

22
tests/nrf51422/Cargo.toml Normal file
View file

@ -0,0 +1,22 @@
[package]
edition = "2021"
name = "embassy-nrf51-tests"
version = "0.1.0"
license = "MIT OR Apache-2.0"
[dependencies]
teleprobe-meta = "1"
embassy-sync = { version = "0.5.0", path = "../../embassy-sync", features = ["defmt", ] }
embassy-executor = { version = "0.5.0", path = "../../embassy-executor", features = ["arch-cortex-m", "executor-thread", "defmt", "task-arena-size-128", "integrated-timers"] }
embassy-time = { version = "0.3.0", path = "../../embassy-time", features = ["defmt", "defmt-timestamp-uptime"] }
embassy-nrf = { version = "0.1.0", path = "../../embassy-nrf", features = ["defmt", "nrf51", "time-driver-rtc1", "unstable-pac", "time"] }
embedded-io-async = { version = "0.6.1", features = ["defmt-03"] }
embedded-hal-async = { version = "1.0" }
defmt = "0.3"
defmt-rtt = "0.4"
cortex-m = { version = "0.7.6", features = ["critical-section-single-core"] }
cortex-m-rt = "0.7.0"
panic-probe = { version = "0.3", features = ["print-defmt"] }

17
tests/nrf51422/build.rs Normal file
View file

@ -0,0 +1,17 @@
use std::error::Error;
use std::path::PathBuf;
use std::{env, fs};
fn main() -> Result<(), Box<dyn Error>> {
let out = PathBuf::from(env::var("OUT_DIR").unwrap());
fs::write(out.join("memory.x"), include_bytes!("memory.x")).unwrap();
println!("cargo:rustc-link-search={}", out.display());
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");
println!("cargo:rustc-link-arg-bins=-Tteleprobe.x");
Ok(())
}

5
tests/nrf51422/memory.x Normal file
View file

@ -0,0 +1,5 @@
MEMORY
{
FLASH : ORIGIN = 0x00000000, LENGTH = 128K
RAM : ORIGIN = 0x20000000, LENGTH = 16K
}

View file

@ -0,0 +1,28 @@
#![no_std]
#![no_main]
teleprobe_meta::target!(b"nrf51-dk");
use defmt::{assert, info};
use embassy_executor::Spawner;
use embassy_nrf::gpio::{Input, Level, Output, OutputDrive, Pull};
use embassy_time::Timer;
use {defmt_rtt as _, panic_probe as _};
#[embassy_executor::main]
async fn main(_spawner: Spawner) {
let p = embassy_nrf::init(Default::default());
let input = Input::new(p.P0_13, Pull::Up);
let mut output = Output::new(p.P0_14, Level::Low, OutputDrive::Standard);
output.set_low();
Timer::after_millis(10).await;
assert!(input.is_low());
output.set_high();
Timer::after_millis(10).await;
assert!(input.is_high());
info!("Test OK");
cortex_m::asm::bkpt();
}

View file

@ -0,0 +1,24 @@
#![no_std]
#![no_main]
teleprobe_meta::target!(b"nrf51-dk");
use defmt::{assert, info};
use embassy_executor::Spawner;
use embassy_time::{Instant, Timer};
use {defmt_rtt as _, panic_probe as _};
#[embassy_executor::main]
async fn main(_spawner: Spawner) {
let _p = embassy_nrf::init(Default::default());
info!("Hello World!");
let start = Instant::now();
Timer::after_millis(100).await;
let end = Instant::now();
let ms = (end - start).as_millis();
info!("slept for {} ms", ms);
assert!(ms >= 99);
info!("Test OK");
cortex_m::asm::bkpt();
}

View file

@ -18,7 +18,6 @@ async fn main(_spawner: Spawner) {
let ms = (end - start).as_millis();
info!("slept for {} ms", ms);
assert!(ms >= 99);
assert!(ms < 110);
info!("Test OK");
cortex_m::asm::bkpt();