Skip to content

Commit

Permalink
Merge pull request #865 from jannic/fix-beta-clippy
Browse files Browse the repository at this point in the history
  • Loading branch information
thejpster authored Oct 19, 2024
2 parents 00785b0 + 0d79844 commit 379530d
Show file tree
Hide file tree
Showing 25 changed files with 82 additions and 82 deletions.
3 changes: 3 additions & 0 deletions rp2040-hal-examples/Cargo.toml
Original file line number Diff line number Diff line change
Expand Up @@ -42,3 +42,6 @@ static_cell = "2.1.0"

[target.'cfg( target_arch = "arm" )'.dependencies]
embassy-executor = {version = "0.5", features = ["arch-cortex-m", "executor-thread"]}

[lints.clippy]
too_long_first_doc_paragraph = "allow"
2 changes: 1 addition & 1 deletion rp2040-hal-examples/src/bin/alloc.rs
Original file line number Diff line number Diff line change
Expand Up @@ -65,7 +65,7 @@ fn main() -> ! {
use core::mem::MaybeUninit;
const HEAP_SIZE: usize = 1024;
static mut HEAP: [MaybeUninit<u8>; HEAP_SIZE] = [MaybeUninit::uninit(); HEAP_SIZE];
unsafe { ALLOCATOR.init(HEAP.as_ptr() as usize, HEAP_SIZE) }
unsafe { ALLOCATOR.init(core::ptr::addr_of_mut!(HEAP) as usize, HEAP_SIZE) }
}

// Grab our singleton objects
Expand Down
1 change: 1 addition & 0 deletions rp2040-hal-examples/src/bin/gpio_irq_example.rs
Original file line number Diff line number Diff line change
Expand Up @@ -149,6 +149,7 @@ fn main() -> ! {
}
}

#[allow(static_mut_refs)] // See https://github.com/rust-embedded/cortex-m/pull/561
#[interrupt]
fn IO_IRQ_BANK0() {
// The `#[interrupt]` attribute covertly converts this to `&'static mut Option<LedAndButton>`
Expand Down
1 change: 1 addition & 0 deletions rp2040-hal-examples/src/bin/multicore_fifo_blink.rs
Original file line number Diff line number Diff line change
Expand Up @@ -115,6 +115,7 @@ fn main() -> ! {
let mut mc = Multicore::new(&mut pac.PSM, &mut pac.PPB, &mut sio.fifo);
let cores = mc.cores();
let core1 = &mut cores[1];
#[allow(static_mut_refs)]
let _test = core1.spawn(unsafe { &mut CORE1_STACK.mem }, move || {
core1_task(sys_freq)
});
Expand Down
1 change: 1 addition & 0 deletions rp2040-hal-examples/src/bin/multicore_polyblink.rs
Original file line number Diff line number Diff line change
Expand Up @@ -105,6 +105,7 @@ fn main() -> ! {
let mut mc = Multicore::new(&mut pac.PSM, &mut pac.PPB, &mut sio.fifo);
let cores = mc.cores();
let core1 = &mut cores[1];
#[allow(static_mut_refs)]
core1
.spawn(unsafe { &mut CORE1_STACK.mem }, move || {
// Get the second core's copy of the `CorePeripherals`, which are per-core.
Expand Down
5 changes: 3 additions & 2 deletions rp2040-hal-examples/src/bin/pwm_irq_input.rs
Original file line number Diff line number Diff line change
Expand Up @@ -47,7 +47,7 @@ pub static BOOT2: [u8; 256] = rp2040_boot2::BOOT_LOADER_GENERIC_03H;

/// 50 Hz PWM servo signals have a pulse width between 1000 us and 2000 us with
/// 1500 us as the centre point. us is the abbreviation for micro seconds.

///
/// The PWM threshold value for turning off the LED in us
const LOW_US: u16 = 1475;

Expand All @@ -60,7 +60,7 @@ const XTAL_FREQ_HZ: u32 = 12_000_000u32;

/// Pin types quickly become very long!
/// We'll create some type aliases using `type` to help with that

///
/// This pin will be our output - it will drive an LED if you run this on a Pico
type LedPin = gpio::Pin<gpio::bank0::Gpio25, gpio::FunctionSio<gpio::SioOutput>, gpio::PullNone>;

Expand Down Expand Up @@ -164,6 +164,7 @@ fn main() -> ! {
}
}

#[allow(static_mut_refs)] // See https://github.com/rust-embedded/cortex-m/pull/561
#[interrupt]
fn IO_IRQ_BANK0() {
// The `#[interrupt]` attribute covertly converts this to `&'static mut Option<LedAndInput>`
Expand Down
1 change: 1 addition & 0 deletions rp2040-hal-examples/src/bin/rtc_irq_example.rs
Original file line number Diff line number Diff line change
Expand Up @@ -144,6 +144,7 @@ fn main() -> ! {
}

#[allow(non_snake_case)]
#[allow(static_mut_refs)] // See https://github.com/rust-embedded/cortex-m/pull/561
#[interrupt]
fn RTC_IRQ() {
// The `#[interrupt]` attribute covertly converts this to `&'static mut Option<LedAndRtc>`
Expand Down
43 changes: 19 additions & 24 deletions rp2040-hal-examples/src/bin/vector_table.rs
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@ use rp2040_hal as hal;

// A shorter alias for the Peripheral Access Crate
use hal::pac;
use static_cell::ConstStaticCell;

// Some traits we need
use core::cell::RefCell;
Expand All @@ -29,7 +30,7 @@ use rp2040_hal::timer::Alarm;
use rp2040_hal::vector_table::VectorTable;

// Memory that will hold our vector table in RAM
static mut RAM_VTABLE: VectorTable = VectorTable::new();
static RAM_VTABLE: ConstStaticCell<VectorTable> = ConstStaticCell::new(VectorTable::new());

// Give our LED and Alarm a type alias to make it easier to refer to them
type LedAndAlarm = (
Expand All @@ -38,7 +39,7 @@ type LedAndAlarm = (
);

// Place our LED and Alarm type in a static variable, so we can access it from interrupts
static mut LED_AND_ALARM: Mutex<RefCell<Option<LedAndAlarm>>> = Mutex::new(RefCell::new(None));
static LED_AND_ALARM: Mutex<RefCell<Option<LedAndAlarm>>> = Mutex::new(RefCell::new(None));

// Period that each of the alarms will be set for - 1 second and 300ms respectively
const SLOW_BLINK_INTERVAL_US: MicrosDurationU32 = MicrosDurationU32::secs(1);
Expand Down Expand Up @@ -76,12 +77,12 @@ fn main() -> ! {

// Need to make a reference to the Peripheral Base at this scope to avoid confusing the borrow checker
let ppb = &mut pac.PPB;
unsafe {
// Copy the vector table that cortex_m_rt produced into the RAM vector table
RAM_VTABLE.init(ppb);
// Replace the function that is called on Alarm0 interrupts with a new one
RAM_VTABLE.register_handler(pac::Interrupt::TIMER_IRQ_0 as usize, timer_irq0_replacement);
}

let ram_vtable = RAM_VTABLE.take();
// Copy the vector table that cortex_m_rt produced into the RAM vector table
ram_vtable.init(ppb);
// Replace the function that is called on Alarm0 interrupts with a new one
ram_vtable.register_handler(pac::Interrupt::TIMER_IRQ_0 as usize, timer_irq0_replacement);

// Configure the clocks
let clocks = hal::clocks::init_clocks_and_plls(
Expand Down Expand Up @@ -117,9 +118,7 @@ fn main() -> ! {
// Enable generating an interrupt on alarm
alarm.enable_interrupt();
// Move alarm into ALARM, so that it can be accessed from interrupts
unsafe {
LED_AND_ALARM.borrow(cs).replace(Some((led_pin, alarm)));
}
LED_AND_ALARM.borrow(cs).replace(Some((led_pin, alarm)));
});
// Unmask the timer0 IRQ so that it will generate an interrupt
unsafe {
Expand All @@ -130,7 +129,7 @@ fn main() -> ! {
delay.delay_ms(5000);
unsafe {
critical_section::with(|_| {
RAM_VTABLE.activate(ppb);
ram_vtable.activate(ppb);
});
}

Expand All @@ -146,7 +145,7 @@ fn main() -> ! {
fn TIMER_IRQ_0() {
critical_section::with(|cs| {
// Temporarily take our LED_AND_ALARM
let ledalarm = unsafe { LED_AND_ALARM.borrow(cs).take() };
let ledalarm = LED_AND_ALARM.borrow(cs).take();
if let Some((mut led, mut alarm)) = ledalarm {
// Clear the alarm interrupt or this interrupt service routine will keep firing
alarm.clear_interrupt();
Expand All @@ -155,31 +154,27 @@ fn TIMER_IRQ_0() {
// Blink the LED so we know we hit this interrupt
led.toggle().unwrap();
// Return LED_AND_ALARM into our static variable
unsafe {
LED_AND_ALARM
.borrow(cs)
.replace_with(|_| Some((led, alarm)));
}
LED_AND_ALARM
.borrow(cs)
.replace_with(|_| Some((led, alarm)));
}
});
}

// This is the function we will use to replace TIMER_IRQ_0 in our RAM Vector Table
extern "C" fn timer_irq0_replacement() {
critical_section::with(|cs| {
let ledalarm = unsafe { LED_AND_ALARM.borrow(cs).take() };
let ledalarm = LED_AND_ALARM.borrow(cs).take();
if let Some((mut led, mut alarm)) = ledalarm {
// Clear the alarm interrupt or this interrupt service routine will keep firing
alarm.clear_interrupt();
// Schedule a new alarm after FAST_BLINK_INTERVAL_US have passed (300 milliseconds)
let _ = alarm.schedule(FAST_BLINK_INTERVAL_US);
led.toggle().unwrap();
// Return LED_AND_ALARM into our static variable
unsafe {
LED_AND_ALARM
.borrow(cs)
.replace_with(|_| Some((led, alarm)));
}
LED_AND_ALARM
.borrow(cs)
.replace_with(|_| Some((led, alarm)));
}
});
}
Expand Down
4 changes: 2 additions & 2 deletions rp2040-hal/src/adc.rs
Original file line number Diff line number Diff line change
Expand Up @@ -813,14 +813,14 @@ impl<'a, Word> AdcFifo<'a, Word> {
}
}

impl<'a> AdcFifo<'a, u16> {
impl AdcFifo<'_, u16> {
/// Read a single value from the fifo (u16 version, not shifted)
pub fn read(&mut self) -> u16 {
self.read_from_fifo()
}
}

impl<'a> AdcFifo<'a, u8> {
impl AdcFifo<'_, u8> {
/// Read a single value from the fifo (u8 version, shifted)
///
/// Also see [`AdcFifoBuilder::shift_8bit`].
Expand Down
4 changes: 2 additions & 2 deletions rp2040-hal/src/async_utils.rs
Original file line number Diff line number Diff line change
Expand Up @@ -128,8 +128,8 @@ where
r
}
}
impl<'periph, Periph, PFn, EnIrqFn, CancelFn, OutputTy> Drop
for CancellablePollFn<'periph, Periph, PFn, EnIrqFn, CancelFn, OutputTy>
impl<Periph, PFn, EnIrqFn, CancelFn, OutputTy> Drop
for CancellablePollFn<'_, Periph, PFn, EnIrqFn, CancelFn, OutputTy>
where
Periph: sealed::Wakeable,
CancelFn: FnMut(&mut Periph),
Expand Down
8 changes: 4 additions & 4 deletions rp2040-hal/src/gpio/mod.rs
Original file line number Diff line number Diff line change
Expand Up @@ -947,8 +947,8 @@ where
}
}

impl<'a, I: PinId, F: func::Function, P: PullType> embedded_hal_0_2::digital::v2::InputPin
for AsInputPin<'a, I, F, P>
impl<I: PinId, F: func::Function, P: PullType> embedded_hal_0_2::digital::v2::InputPin
for AsInputPin<'_, I, F, P>
{
type Error = core::convert::Infallible;

Expand Down Expand Up @@ -1527,7 +1527,7 @@ mod eh1 {
}
}

impl<'a, I, F, P> ErrorType for AsInputPin<'a, I, F, P>
impl<I, F, P> ErrorType for AsInputPin<'_, I, F, P>
where
I: PinId,
F: func::Function,
Expand All @@ -1536,7 +1536,7 @@ mod eh1 {
type Error = Error;
}

impl<'a, I: PinId, F: func::Function, P: PullType> InputPin for AsInputPin<'a, I, F, P> {
impl<I: PinId, F: func::Function, P: PullType> InputPin for AsInputPin<'_, I, F, P> {
fn is_high(&mut self) -> Result<bool, Self::Error> {
Ok(self.0._is_high())
}
Expand Down
2 changes: 1 addition & 1 deletion rp2040-hal/src/multicore.rs
Original file line number Diff line number Diff line change
Expand Up @@ -141,7 +141,7 @@ pub struct Core<'p> {
)>,
}

impl<'p> Core<'p> {
impl Core<'_> {
/// Get the id of this core.
pub fn id(&self) -> u8 {
match self.inner {
Expand Down
6 changes: 3 additions & 3 deletions rp2040-hal/src/pio.rs
Original file line number Diff line number Diff line change
Expand Up @@ -1243,7 +1243,7 @@ impl<'sm, P: PIOExt, SM: StateMachineIndex> Synchronize<'sm, (P, SM)> {
}
}

impl<'sm, SM: ValidStateMachine> Drop for Synchronize<'sm, SM> {
impl<SM: ValidStateMachine> Drop for Synchronize<'_, SM> {
fn drop(&mut self) {
// Restart the clocks of all state machines specified by the mask.
// Bits 11:8 of CTRL contain CLKDIV_RESTART.
Expand Down Expand Up @@ -1666,13 +1666,13 @@ pub struct Interrupt<'a, P: PIOExt, const IRQ: usize> {
}

// Safety: `Interrupt` provides exclusive access to interrupt registers.
unsafe impl<'a, P: PIOExt, const IRQ: usize> Send for Interrupt<'a, P, IRQ> {}
unsafe impl<P: PIOExt, const IRQ: usize> Send for Interrupt<'_, P, IRQ> {}

// Safety: `Interrupt` is marked Send so ensure all accesses remain atomic and no new concurrent
// accesses are added.
// `Interrupt` provides exclusive access to `irq_intf` to `irq_inte` for it's state machine, this
// must remain true to satisfy Send.
impl<'a, P: PIOExt, const IRQ: usize> Interrupt<'a, P, IRQ> {
impl<P: PIOExt, const IRQ: usize> Interrupt<'_, P, IRQ> {
/// Enable interrupts raised by state machines.
///
/// The PIO peripheral has 4 outside visible interrupts that can be raised by the state machines. Note that this
Expand Down
1 change: 0 additions & 1 deletion rp2040-hal/src/pwm/mod.rs
Original file line number Diff line number Diff line change
Expand Up @@ -888,7 +888,6 @@ pub struct SliceDmaWriteCc<S: SliceId, M: ValidSliceMode<S>> {
///
/// let dma_conf = double_buffer::Config::new((dma.ch0, dma.ch1), buf, dma_pwm.top);
/// ```

pub struct SliceDmaWriteTop<S: SliceId, M: ValidSliceMode<S>> {
slice: PhantomData<S>,
mode: PhantomData<M>,
Expand Down
2 changes: 1 addition & 1 deletion rp235x-hal-examples/src/bin/alloc.rs
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,7 @@ fn main() -> ! {
use core::mem::MaybeUninit;
const HEAP_SIZE: usize = 1024;
static mut HEAP: [MaybeUninit<u8>; HEAP_SIZE] = [MaybeUninit::uninit(); HEAP_SIZE];
unsafe { ALLOCATOR.init(HEAP.as_ptr() as usize, HEAP_SIZE) }
unsafe { ALLOCATOR.init(core::ptr::addr_of_mut!(HEAP) as usize, HEAP_SIZE) }
}

// Grab our singleton objects
Expand Down
1 change: 1 addition & 0 deletions rp235x-hal-examples/src/bin/gpio_irq_example.rs
Original file line number Diff line number Diff line change
Expand Up @@ -142,6 +142,7 @@ fn main() -> ! {
}
}

#[allow(static_mut_refs)] // See https://github.com/rust-embedded/cortex-m/pull/561
#[interrupt]
fn IO_IRQ_BANK0() {
// The `#[interrupt]` attribute covertly converts this to `&'static mut Option<LedAndButton>`
Expand Down
1 change: 1 addition & 0 deletions rp235x-hal-examples/src/bin/multicore_fifo_blink.rs
Original file line number Diff line number Diff line change
Expand Up @@ -107,6 +107,7 @@ fn main() -> ! {
let mut mc = Multicore::new(&mut pac.PSM, &mut pac.PPB, &mut sio.fifo);
let cores = mc.cores();
let core1 = &mut cores[1];
#[allow(static_mut_refs)]
let _test = core1.spawn(unsafe { &mut CORE1_STACK.mem }, move || {
core1_task(sys_freq)
});
Expand Down
1 change: 1 addition & 0 deletions rp235x-hal-examples/src/bin/multicore_polyblink.rs
Original file line number Diff line number Diff line change
Expand Up @@ -99,6 +99,7 @@ fn main() -> ! {
let mut mc = Multicore::new(&mut pac.PSM, &mut pac.PPB, &mut sio.fifo);
let cores = mc.cores();
let core1 = &mut cores[1];
#[allow(static_mut_refs)]
core1
.spawn(unsafe { &mut CORE1_STACK.mem }, move || {
// Get the second core's copy of the `CorePeripherals`, which are per-core.
Expand Down
5 changes: 3 additions & 2 deletions rp235x-hal-examples/src/bin/pwm_irq_input.rs
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,7 @@ pub static IMAGE_DEF: hal::block::ImageDef = hal::block::ImageDef::secure_exe();

/// 50 Hz PWM servo signals have a pulse width between 1000 us and 2000 us with
/// 1500 us as the centre point. us is the abbreviation for micro seconds.

///
/// The PWM threshold value for turning off the LED in us
const LOW_US: u16 = 1475;

Expand All @@ -53,7 +53,7 @@ const XTAL_FREQ_HZ: u32 = 12_000_000u32;

/// Pin types quickly become very long!
/// We'll create some type aliases using `type` to help with that

///
/// This pin will be our output - it will drive an LED if you run this on a Pico
type LedPin = gpio::Pin<gpio::bank0::Gpio25, gpio::FunctionSio<gpio::SioOutput>, gpio::PullNone>;

Expand Down Expand Up @@ -157,6 +157,7 @@ fn main() -> ! {
}
}

#[allow(static_mut_refs)] // See https://github.com/rust-embedded/cortex-m/pull/561
#[interrupt]
fn IO_IRQ_BANK0() {
// The `#[interrupt]` attribute covertly converts this to `&'static mut Option<LedAndInput>`
Expand Down
Loading

0 comments on commit 379530d

Please sign in to comment.