mirror of
https://github.com/embassy-rs/embassy.git
synced 2024-11-21 14:22:33 +00:00
Fix warnings in recent nightly.
This commit is contained in:
parent
3d842dac85
commit
eca9aac194
@ -7,7 +7,6 @@ use std::thread;
|
||||
|
||||
use proc_macro2::TokenStream;
|
||||
use quote::{quote, ToTokens};
|
||||
use syn;
|
||||
|
||||
/// A type to collect errors together and format them.
|
||||
///
|
||||
|
@ -30,7 +30,7 @@ use core::ptr::NonNull;
|
||||
use core::task::{Context, Poll};
|
||||
|
||||
#[cfg(feature = "integrated-timers")]
|
||||
use embassy_time_driver::{self, AlarmHandle};
|
||||
use embassy_time_driver::AlarmHandle;
|
||||
#[cfg(feature = "rtos-trace")]
|
||||
use rtos_trace::trace;
|
||||
|
||||
|
@ -17,7 +17,6 @@ mod phy;
|
||||
mod traits;
|
||||
|
||||
use core::cmp;
|
||||
use core::convert::TryInto;
|
||||
|
||||
use embassy_net_driver::{Capabilities, HardwareAddress, LinkState};
|
||||
use embassy_time::Duration;
|
||||
@ -645,8 +644,8 @@ where
|
||||
Self: 'a;
|
||||
|
||||
fn receive(&mut self, cx: &mut core::task::Context) -> Option<(Self::RxToken<'_>, Self::TxToken<'_>)> {
|
||||
let rx_buf = unsafe { &mut RX_BUF };
|
||||
let tx_buf = unsafe { &mut TX_BUF };
|
||||
let rx_buf = unsafe { &mut *core::ptr::addr_of_mut!(RX_BUF) };
|
||||
let tx_buf = unsafe { &mut *core::ptr::addr_of_mut!(TX_BUF) };
|
||||
if let Some(n) = self.receive(rx_buf) {
|
||||
Some((RxToken { buf: &mut rx_buf[..n] }, TxToken { buf: tx_buf, eth: self }))
|
||||
} else {
|
||||
@ -656,7 +655,7 @@ where
|
||||
}
|
||||
|
||||
fn transmit(&mut self, _cx: &mut core::task::Context) -> Option<Self::TxToken<'_>> {
|
||||
let tx_buf = unsafe { &mut TX_BUF };
|
||||
let tx_buf = unsafe { &mut *core::ptr::addr_of_mut!(TX_BUF) };
|
||||
Some(TxToken { buf: tx_buf, eth: self })
|
||||
}
|
||||
|
||||
|
@ -6,7 +6,7 @@ use std::os::unix::io::{AsRawFd, RawFd};
|
||||
use std::task::Context;
|
||||
|
||||
use async_io::Async;
|
||||
use embassy_net_driver::{self, Capabilities, Driver, HardwareAddress, LinkState};
|
||||
use embassy_net_driver::{Capabilities, Driver, HardwareAddress, LinkState};
|
||||
use log::*;
|
||||
|
||||
/// Get the MTU of the given interface.
|
||||
|
@ -473,10 +473,12 @@ impl sealed::Pin for AnyPin {
|
||||
|
||||
// ====================
|
||||
|
||||
#[cfg(not(feature = "_nrf51"))]
|
||||
pub(crate) trait PselBits {
|
||||
fn psel_bits(&self) -> u32;
|
||||
}
|
||||
|
||||
#[cfg(not(feature = "_nrf51"))]
|
||||
impl<'a, P: Pin> PselBits for Option<PeripheralRef<'a, P>> {
|
||||
#[inline]
|
||||
fn psel_bits(&self) -> u32 {
|
||||
|
@ -167,8 +167,10 @@ unsafe fn handle_gpiote_interrupt() {
|
||||
}
|
||||
}
|
||||
|
||||
#[cfg(not(feature = "_nrf51"))]
|
||||
struct BitIter(u32);
|
||||
|
||||
#[cfg(not(feature = "_nrf51"))]
|
||||
impl Iterator for BitIter {
|
||||
type Item = u32;
|
||||
|
||||
|
@ -21,8 +21,6 @@ pub(crate) mod sealed {
|
||||
fn regs() -> &'static pac::timer0::RegisterBlock;
|
||||
}
|
||||
pub trait ExtendedInstance {}
|
||||
|
||||
pub trait TimerType {}
|
||||
}
|
||||
|
||||
/// Basic Timer instance.
|
||||
|
@ -96,7 +96,7 @@ pub unsafe fn write_repeated<'a, C: Channel, W: Word>(
|
||||
) -> Transfer<'a, C> {
|
||||
copy_inner(
|
||||
ch,
|
||||
&mut DUMMY as *const u32,
|
||||
core::ptr::addr_of_mut!(DUMMY) as *const u32,
|
||||
to as *mut u32,
|
||||
len,
|
||||
W::size(),
|
||||
|
@ -420,8 +420,6 @@ impl<'d, T: Instance, const FLASH_SIZE: usize> embedded_storage_async::nor_flash
|
||||
|
||||
#[allow(dead_code)]
|
||||
mod ram_helpers {
|
||||
use core::marker::PhantomData;
|
||||
|
||||
use super::*;
|
||||
use crate::rom_data;
|
||||
|
||||
|
@ -89,6 +89,7 @@ pub(crate) trait Float:
|
||||
}
|
||||
|
||||
/// Returns true if `self` is infinity
|
||||
#[allow(unused)]
|
||||
fn is_infinity(self) -> bool {
|
||||
(self.repr() & (Self::EXPONENT_MASK | Self::SIGNIFICAND_MASK)) == Self::EXPONENT_MASK
|
||||
}
|
||||
|
@ -976,8 +976,6 @@ impl_pin!(PIN_QSPI_SD3, Bank::Qspi, 5);
|
||||
// ====================
|
||||
|
||||
mod eh02 {
|
||||
use core::convert::Infallible;
|
||||
|
||||
use super::*;
|
||||
|
||||
impl<'d> embedded_hal_02::digital::v2::InputPin for Input<'d> {
|
||||
|
@ -274,7 +274,7 @@ pub fn install_core0_stack_guard() -> Result<(), ()> {
|
||||
extern "C" {
|
||||
static mut _stack_end: usize;
|
||||
}
|
||||
unsafe { install_stack_guard(&mut _stack_end as *mut usize) }
|
||||
unsafe { install_stack_guard(core::ptr::addr_of_mut!(_stack_end)) }
|
||||
}
|
||||
|
||||
#[inline(always)]
|
||||
@ -354,6 +354,7 @@ pub fn init(config: config::Config) -> Peripherals {
|
||||
|
||||
/// Extension trait for PAC regs, adding atomic xor/bitset/bitclear writes.
|
||||
trait RegExt<T: Copy> {
|
||||
#[allow(unused)]
|
||||
fn write_xor<R>(&self, f: impl FnOnce(&mut T) -> R) -> R;
|
||||
fn write_set<R>(&self, f: impl FnOnce(&mut T) -> R) -> R;
|
||||
fn write_clear<R>(&self, f: impl FnOnce(&mut T) -> R) -> R;
|
||||
|
@ -1,5 +1,3 @@
|
||||
use core::iter::Iterator;
|
||||
|
||||
use pio::{Program, SideSet, Wrap};
|
||||
|
||||
pub struct CodeIterator<'a, I>
|
||||
|
@ -1,17 +1,11 @@
|
||||
//! Buffered UART driver.
|
||||
use core::future::{poll_fn, Future};
|
||||
use core::future::Future;
|
||||
use core::slice;
|
||||
use core::task::Poll;
|
||||
|
||||
use atomic_polyfill::{AtomicU8, Ordering};
|
||||
use atomic_polyfill::AtomicU8;
|
||||
use embassy_hal_internal::atomic_ring_buffer::RingBuffer;
|
||||
use embassy_sync::waitqueue::AtomicWaker;
|
||||
use embassy_time::Timer;
|
||||
|
||||
use super::*;
|
||||
use crate::clocks::clk_peri_freq;
|
||||
use crate::interrupt::typelevel::{Binding, Interrupt};
|
||||
use crate::{interrupt, RegExt};
|
||||
|
||||
pub struct State {
|
||||
tx_waker: AtomicWaker,
|
||||
|
@ -465,7 +465,6 @@ impl<'d, T: Instance> driver::Bus for Bus<'d, T> {
|
||||
|
||||
trait Dir {
|
||||
fn dir() -> Direction;
|
||||
fn waker(i: usize) -> &'static AtomicWaker;
|
||||
}
|
||||
|
||||
/// Type for In direction.
|
||||
@ -474,11 +473,6 @@ impl Dir for In {
|
||||
fn dir() -> Direction {
|
||||
Direction::In
|
||||
}
|
||||
|
||||
#[inline]
|
||||
fn waker(i: usize) -> &'static AtomicWaker {
|
||||
&EP_IN_WAKERS[i]
|
||||
}
|
||||
}
|
||||
|
||||
/// Type for Out direction.
|
||||
@ -487,11 +481,6 @@ impl Dir for Out {
|
||||
fn dir() -> Direction {
|
||||
Direction::Out
|
||||
}
|
||||
|
||||
#[inline]
|
||||
fn waker(i: usize) -> &'static AtomicWaker {
|
||||
&EP_OUT_WAKERS[i]
|
||||
}
|
||||
}
|
||||
|
||||
/// Endpoint for RP USB driver.
|
||||
|
@ -1,5 +1,3 @@
|
||||
use core::convert::TryFrom;
|
||||
|
||||
use crate::evt::CsEvt;
|
||||
use crate::PacketHeader;
|
||||
|
||||
|
@ -28,7 +28,7 @@ pub mod filter;
|
||||
|
||||
#[allow(clippy::all)] // generated code
|
||||
use core::cmp::{Ord, Ordering};
|
||||
use core::convert::{Infallible, Into, TryInto};
|
||||
use core::convert::Infallible;
|
||||
use core::marker::PhantomData;
|
||||
use core::mem;
|
||||
|
||||
|
@ -1,4 +1,3 @@
|
||||
use core::convert::AsMut;
|
||||
use core::future::poll_fn;
|
||||
use core::marker::PhantomData;
|
||||
use core::ops::{Deref, DerefMut};
|
||||
|
@ -140,26 +140,6 @@ pub(crate) struct _TxBufferElement;
|
||||
impl generic::Readable for TxBufferElementHeader {}
|
||||
impl generic::Writable for TxBufferElementHeader {}
|
||||
|
||||
/// FdCan Message RAM instance.
|
||||
///
|
||||
/// # Safety
|
||||
///
|
||||
/// It is only safe to implement this trait, when:
|
||||
///
|
||||
/// * The implementing type has ownership of the Message RAM, preventing any
|
||||
/// other accesses to the register block.
|
||||
/// * `MSG_RAM` is a pointer to the Message RAM block and can be safely accessed
|
||||
/// for as long as ownership or a borrow of the implementing type is present.
|
||||
pub unsafe trait Instance {
|
||||
const MSG_RAM: *mut RegisterBlock;
|
||||
fn msg_ram(&self) -> &RegisterBlock {
|
||||
unsafe { &*Self::MSG_RAM }
|
||||
}
|
||||
fn msg_ram_mut(&mut self) -> &mut RegisterBlock {
|
||||
unsafe { &mut *Self::MSG_RAM }
|
||||
}
|
||||
}
|
||||
|
||||
// Ensure the RegisterBlock is the same size as on pg 1957 of RM0440.
|
||||
static_assertions::assert_eq_size!(Filters, [u32; 28 + 16]);
|
||||
static_assertions::assert_eq_size!(Receive, [u32; 54]);
|
||||
|
@ -883,9 +883,9 @@ macro_rules! impl_fdcan {
|
||||
fn ram() -> &'static crate::pac::fdcanram::Fdcanram {
|
||||
&crate::pac::$msg_ram_inst
|
||||
}
|
||||
unsafe fn mut_state() -> & 'static mut sealed::State {
|
||||
unsafe fn mut_state() -> &'static mut sealed::State {
|
||||
static mut STATE: sealed::State = sealed::State::new();
|
||||
& mut STATE
|
||||
&mut *core::ptr::addr_of_mut!(STATE)
|
||||
}
|
||||
fn state() -> &'static sealed::State {
|
||||
unsafe { peripherals::$inst::mut_state() }
|
||||
|
@ -44,6 +44,7 @@ pub(crate) mod sealed {
|
||||
fn id(&self) -> u8;
|
||||
}
|
||||
pub trait ChannelInterrupt {
|
||||
#[cfg_attr(not(feature = "rt"), allow(unused))]
|
||||
unsafe fn on_irq();
|
||||
}
|
||||
}
|
||||
|
@ -1,4 +1,3 @@
|
||||
use core::convert::TryInto;
|
||||
use core::ptr::write_volatile;
|
||||
use core::sync::atomic::{fence, Ordering};
|
||||
|
||||
|
@ -1,4 +1,3 @@
|
||||
use core::convert::TryInto;
|
||||
use core::ptr::write_volatile;
|
||||
use core::sync::atomic::{fence, Ordering};
|
||||
|
||||
|
@ -1,4 +1,3 @@
|
||||
use core::convert::TryInto;
|
||||
use core::ptr::write_volatile;
|
||||
use core::sync::atomic::{fence, AtomicBool, Ordering};
|
||||
|
||||
|
@ -1,4 +1,3 @@
|
||||
use core::convert::TryInto;
|
||||
use core::ptr::write_volatile;
|
||||
use core::sync::atomic::{fence, Ordering};
|
||||
|
||||
|
@ -1,4 +1,3 @@
|
||||
use core::convert::TryInto;
|
||||
use core::ptr::write_volatile;
|
||||
use core::sync::atomic::{fence, Ordering};
|
||||
|
||||
|
@ -1,4 +1,3 @@
|
||||
use core::convert::TryInto;
|
||||
use core::ptr::write_volatile;
|
||||
use core::sync::atomic::{fence, Ordering};
|
||||
|
||||
|
@ -1,4 +1,3 @@
|
||||
use core::convert::TryInto;
|
||||
use core::ptr::write_volatile;
|
||||
use core::sync::atomic::{fence, Ordering};
|
||||
|
||||
|
@ -15,7 +15,6 @@ use embedded_hal_1::i2c::Operation;
|
||||
use super::*;
|
||||
use crate::dma::Transfer;
|
||||
use crate::pac::i2c;
|
||||
use crate::time::Hertz;
|
||||
|
||||
// /!\ /!\
|
||||
// /!\ Implementation note! /!\
|
||||
|
@ -9,7 +9,6 @@ use embedded_hal_1::i2c::Operation;
|
||||
use super::*;
|
||||
use crate::dma::Transfer;
|
||||
use crate::pac::i2c;
|
||||
use crate::time::Hertz;
|
||||
|
||||
pub(crate) unsafe fn on_interrupt<T: Instance>() {
|
||||
let regs = T::regs();
|
||||
|
@ -1,8 +1,5 @@
|
||||
#[cfg(feature = "chrono")]
|
||||
use core::convert::From;
|
||||
|
||||
#[cfg(feature = "chrono")]
|
||||
use chrono::{self, Datelike, NaiveDate, Timelike, Weekday};
|
||||
use chrono::{Datelike, NaiveDate, Timelike, Weekday};
|
||||
|
||||
#[cfg(any(feature = "defmt", feature = "time"))]
|
||||
use crate::peripherals::RTC;
|
||||
|
@ -1427,8 +1427,6 @@ pub(crate) mod sealed {
|
||||
fn regs() -> RegBlock;
|
||||
fn state() -> &'static AtomicWaker;
|
||||
}
|
||||
|
||||
pub trait Pins<T: Instance> {}
|
||||
}
|
||||
|
||||
/// SDMMC instance trait.
|
||||
|
@ -1,7 +1,6 @@
|
||||
#![allow(non_snake_case)]
|
||||
|
||||
use core::cell::Cell;
|
||||
use core::convert::TryInto;
|
||||
use core::sync::atomic::{compiler_fence, AtomicU32, AtomicU8, Ordering};
|
||||
use core::{mem, ptr};
|
||||
|
||||
|
@ -10,7 +10,6 @@ use super::*;
|
||||
#[allow(unused_imports)]
|
||||
use crate::gpio::sealed::{AFType, Pin};
|
||||
use crate::gpio::{AnyPin, OutputType};
|
||||
use crate::time::Hertz;
|
||||
use crate::Peripheral;
|
||||
|
||||
/// Complementary PWM pin wrapper.
|
||||
|
@ -8,7 +8,6 @@ use super::*;
|
||||
#[allow(unused_imports)]
|
||||
use crate::gpio::sealed::{AFType, Pin};
|
||||
use crate::gpio::{AnyPin, OutputType};
|
||||
use crate::time::Hertz;
|
||||
use crate::Peripheral;
|
||||
|
||||
/// Channel 1 marker type.
|
||||
|
@ -27,5 +27,5 @@ pub fn uid_hex_bytes() -> &'static [u8; 24] {
|
||||
LOADED = true;
|
||||
}
|
||||
});
|
||||
unsafe { &UID_HEX }
|
||||
unsafe { &*core::ptr::addr_of!(UID_HEX) }
|
||||
}
|
||||
|
@ -1,13 +1,10 @@
|
||||
use core::future::poll_fn;
|
||||
use core::slice;
|
||||
use core::sync::atomic::{AtomicBool, Ordering};
|
||||
use core::task::Poll;
|
||||
use core::sync::atomic::AtomicBool;
|
||||
|
||||
use embassy_hal_internal::atomic_ring_buffer::RingBuffer;
|
||||
use embassy_sync::waitqueue::AtomicWaker;
|
||||
|
||||
use super::*;
|
||||
use crate::interrupt::typelevel::Interrupt;
|
||||
|
||||
/// Interrupt handler.
|
||||
pub struct InterruptHandler<T: BasicInstance> {
|
||||
|
@ -6,8 +6,8 @@ use core::task::Poll;
|
||||
use embassy_hal_internal::{into_ref, Peripheral};
|
||||
use embassy_sync::waitqueue::AtomicWaker;
|
||||
use embassy_usb_driver::{
|
||||
self, Bus as _, Direction, EndpointAddress, EndpointAllocError, EndpointError, EndpointIn, EndpointInfo,
|
||||
EndpointOut, EndpointType, Event, Unsupported,
|
||||
Bus as _, Direction, EndpointAddress, EndpointAllocError, EndpointError, EndpointIn, EndpointInfo, EndpointOut,
|
||||
EndpointType, Event, Unsupported,
|
||||
};
|
||||
use futures::future::poll_fn;
|
||||
|
||||
|
@ -637,7 +637,6 @@ impl<'d, T: Instance> driver::Bus for Bus<'d, T> {
|
||||
|
||||
trait Dir {
|
||||
fn dir() -> Direction;
|
||||
fn waker(i: usize) -> &'static AtomicWaker;
|
||||
}
|
||||
|
||||
/// Marker type for the "IN" direction.
|
||||
@ -646,11 +645,6 @@ impl Dir for In {
|
||||
fn dir() -> Direction {
|
||||
Direction::In
|
||||
}
|
||||
|
||||
#[inline]
|
||||
fn waker(i: usize) -> &'static AtomicWaker {
|
||||
&EP_IN_WAKERS[i]
|
||||
}
|
||||
}
|
||||
|
||||
/// Marker type for the "OUT" direction.
|
||||
@ -659,11 +653,6 @@ impl Dir for Out {
|
||||
fn dir() -> Direction {
|
||||
Direction::Out
|
||||
}
|
||||
|
||||
#[inline]
|
||||
fn waker(i: usize) -> &'static AtomicWaker {
|
||||
&EP_OUT_WAKERS[i]
|
||||
}
|
||||
}
|
||||
|
||||
/// USB endpoint.
|
||||
|
@ -30,10 +30,14 @@ fn main() -> ! {
|
||||
let p = embassy_rp::init(Default::default());
|
||||
let led = Output::new(p.PIN_25, Level::Low);
|
||||
|
||||
spawn_core1(p.CORE1, unsafe { &mut CORE1_STACK }, move || {
|
||||
let executor1 = EXECUTOR1.init(Executor::new());
|
||||
executor1.run(|spawner| unwrap!(spawner.spawn(core1_task(led))));
|
||||
});
|
||||
spawn_core1(
|
||||
p.CORE1,
|
||||
unsafe { &mut *core::ptr::addr_of_mut!(CORE1_STACK) },
|
||||
move || {
|
||||
let executor1 = EXECUTOR1.init(Executor::new());
|
||||
executor1.run(|spawner| unwrap!(spawner.spawn(core1_task(led))));
|
||||
},
|
||||
);
|
||||
|
||||
let executor0 = EXECUTOR0.init(Executor::new());
|
||||
executor0.run(|spawner| unwrap!(spawner.spawn(core0_task())));
|
||||
|
@ -1,5 +1,3 @@
|
||||
use std::default::Default;
|
||||
|
||||
use clap::Parser;
|
||||
use embassy_executor::{Executor, Spawner};
|
||||
use embassy_net::tcp::TcpSocket;
|
||||
|
@ -1,5 +1,3 @@
|
||||
use std::default::Default;
|
||||
|
||||
use clap::Parser;
|
||||
use embassy_executor::{Executor, Spawner};
|
||||
use embassy_net::dns::DnsQueryType;
|
||||
|
@ -1,5 +1,4 @@
|
||||
use core::fmt::Write as _;
|
||||
use std::default::Default;
|
||||
|
||||
use clap::Parser;
|
||||
use embassy_executor::{Executor, Spawner};
|
||||
|
@ -1,8 +1,6 @@
|
||||
#![no_std]
|
||||
#![no_main]
|
||||
|
||||
use core::convert::TryFrom;
|
||||
|
||||
use defmt::*;
|
||||
use embassy_executor::Spawner;
|
||||
use embassy_stm32::time::Hertz;
|
||||
|
@ -78,9 +78,9 @@ async fn main(_spawner: Spawner) {
|
||||
);
|
||||
|
||||
defmt::info!("attempting capture");
|
||||
defmt::unwrap!(dcmi.capture(unsafe { &mut FRAME }).await);
|
||||
defmt::unwrap!(dcmi.capture(unsafe { &mut *core::ptr::addr_of_mut!(FRAME) }).await);
|
||||
|
||||
defmt::info!("captured frame: {:x}", unsafe { &FRAME });
|
||||
defmt::info!("captured frame: {:x}", unsafe { &*core::ptr::addr_of!(FRAME) });
|
||||
|
||||
defmt::info!("main loop running");
|
||||
loop {
|
||||
|
@ -42,7 +42,7 @@ bind_interrupts!(struct Irqs {
|
||||
RNG => rng::InterruptHandler<peripherals::RNG>;
|
||||
});
|
||||
|
||||
use embassy_net_adin1110::{self, Device, Runner, ADIN1110};
|
||||
use embassy_net_adin1110::{Device, Runner, ADIN1110};
|
||||
use embedded_hal_bus::spi::ExclusiveDevice;
|
||||
use hal::gpio::Pull;
|
||||
use hal::i2c::Config as I2C_Config;
|
||||
|
@ -21,10 +21,14 @@ static CHANNEL1: Channel<CriticalSectionRawMutex, (), 1> = Channel::new();
|
||||
#[cortex_m_rt::entry]
|
||||
fn main() -> ! {
|
||||
let p = embassy_rp::init(Default::default());
|
||||
spawn_core1(p.CORE1, unsafe { &mut CORE1_STACK }, move || {
|
||||
let executor1 = EXECUTOR1.init(Executor::new());
|
||||
executor1.run(|spawner| unwrap!(spawner.spawn(core1_task(p.PIN_1))));
|
||||
});
|
||||
spawn_core1(
|
||||
p.CORE1,
|
||||
unsafe { &mut *core::ptr::addr_of_mut!(CORE1_STACK) },
|
||||
move || {
|
||||
let executor1 = EXECUTOR1.init(Executor::new());
|
||||
executor1.run(|spawner| unwrap!(spawner.spawn(core1_task(p.PIN_1))));
|
||||
},
|
||||
);
|
||||
let executor0 = EXECUTOR0.init(Executor::new());
|
||||
executor0.run(|spawner| unwrap!(spawner.spawn(core0_task(p.PIN_0))));
|
||||
}
|
||||
|
@ -210,10 +210,14 @@ async fn controller_task(con: &mut i2c::I2c<'static, I2C0, i2c::Async>) {
|
||||
config.addr = DEV_ADDR as u16;
|
||||
let device = i2c_slave::I2cSlave::new(p.I2C1, d_sda, d_scl, Irqs, config);
|
||||
|
||||
spawn_core1(p.CORE1, unsafe { &mut CORE1_STACK }, move || {
|
||||
let executor1 = EXECUTOR1.init(Executor::new());
|
||||
executor1.run(|spawner| unwrap!(spawner.spawn(device_task(device))));
|
||||
});
|
||||
spawn_core1(
|
||||
p.CORE1,
|
||||
unsafe { &mut *core::ptr::addr_of_mut!(CORE1_STACK) },
|
||||
move || {
|
||||
let executor1 = EXECUTOR1.init(Executor::new());
|
||||
executor1.run(|spawner| unwrap!(spawner.spawn(device_task(device))));
|
||||
},
|
||||
);
|
||||
|
||||
let c_sda = p.PIN_21;
|
||||
let c_scl = p.PIN_20;
|
||||
|
@ -19,10 +19,14 @@ static CHANNEL1: Channel<CriticalSectionRawMutex, bool, 1> = Channel::new();
|
||||
#[cortex_m_rt::entry]
|
||||
fn main() -> ! {
|
||||
let p = embassy_rp::init(Default::default());
|
||||
spawn_core1(p.CORE1, unsafe { &mut CORE1_STACK }, move || {
|
||||
let executor1 = EXECUTOR1.init(Executor::new());
|
||||
executor1.run(|spawner| unwrap!(spawner.spawn(core1_task())));
|
||||
});
|
||||
spawn_core1(
|
||||
p.CORE1,
|
||||
unsafe { &mut *core::ptr::addr_of_mut!(CORE1_STACK) },
|
||||
move || {
|
||||
let executor1 = EXECUTOR1.init(Executor::new());
|
||||
executor1.run(|spawner| unwrap!(spawner.spawn(core1_task())));
|
||||
},
|
||||
);
|
||||
let executor0 = EXECUTOR0.init(Executor::new());
|
||||
executor0.run(|spawner| unwrap!(spawner.spawn(core0_task())));
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user