Skip to content

Commit

Permalink
Fix warnings in recent nightly.
Browse files Browse the repository at this point in the history
  • Loading branch information
Dirbaio committed Mar 20, 2024
1 parent 3d842da commit eca9aac
Show file tree
Hide file tree
Showing 49 changed files with 59 additions and 124 deletions.
1 change: 0 additions & 1 deletion embassy-executor-macros/src/util/ctxt.rs
Original file line number Diff line number Diff line change
Expand Up @@ -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.
///
Expand Down
2 changes: 1 addition & 1 deletion embassy-executor/src/raw/mod.rs
Original file line number Diff line number Diff line change
Expand Up @@ -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;

Expand Down
7 changes: 3 additions & 4 deletions embassy-net-enc28j60/src/lib.rs
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down Expand Up @@ -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 {
Expand All @@ -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 })
}

Expand Down
2 changes: 1 addition & 1 deletion embassy-net-tuntap/src/lib.rs
Original file line number Diff line number Diff line change
Expand Up @@ -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.
Expand Down
2 changes: 2 additions & 0 deletions embassy-nrf/src/gpio.rs
Original file line number Diff line number Diff line change
Expand Up @@ -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 {
Expand Down
2 changes: 2 additions & 0 deletions embassy-nrf/src/gpiote.rs
Original file line number Diff line number Diff line change
Expand Up @@ -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;

Expand Down
2 changes: 0 additions & 2 deletions embassy-nrf/src/timer.rs
Original file line number Diff line number Diff line change
Expand Up @@ -21,8 +21,6 @@ pub(crate) mod sealed {
fn regs() -> &'static pac::timer0::RegisterBlock;
}
pub trait ExtendedInstance {}

pub trait TimerType {}
}

/// Basic Timer instance.
Expand Down
2 changes: 1 addition & 1 deletion embassy-rp/src/dma.rs
Original file line number Diff line number Diff line change
Expand Up @@ -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(),
Expand Down
2 changes: 0 additions & 2 deletions embassy-rp/src/flash.rs
Original file line number Diff line number Diff line change
Expand Up @@ -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;

Expand Down
1 change: 1 addition & 0 deletions embassy-rp/src/float/mod.rs
Original file line number Diff line number Diff line change
Expand Up @@ -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
}
Expand Down
2 changes: 0 additions & 2 deletions embassy-rp/src/gpio.rs
Original file line number Diff line number Diff line change
Expand Up @@ -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> {
Expand Down
3 changes: 2 additions & 1 deletion embassy-rp/src/lib.rs
Original file line number Diff line number Diff line change
Expand Up @@ -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)]
Expand Down Expand Up @@ -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;
Expand Down
2 changes: 0 additions & 2 deletions embassy-rp/src/relocate.rs
Original file line number Diff line number Diff line change
@@ -1,5 +1,3 @@
use core::iter::Iterator;

use pio::{Program, SideSet, Wrap};

pub struct CodeIterator<'a, I>
Expand Down
10 changes: 2 additions & 8 deletions embassy-rp/src/uart/buffered.rs
Original file line number Diff line number Diff line change
@@ -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,
Expand Down
11 changes: 0 additions & 11 deletions embassy-rp/src/usb.rs
Original file line number Diff line number Diff line change
Expand Up @@ -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.
Expand All @@ -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.
Expand All @@ -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.
Expand Down
2 changes: 0 additions & 2 deletions embassy-stm32-wpan/src/consts.rs
Original file line number Diff line number Diff line change
@@ -1,5 +1,3 @@
use core::convert::TryFrom;

use crate::evt::CsEvt;
use crate::PacketHeader;

Expand Down
2 changes: 1 addition & 1 deletion embassy-stm32/src/can/bx/mod.rs
Original file line number Diff line number Diff line change
Expand Up @@ -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;

Expand Down
1 change: 0 additions & 1 deletion embassy-stm32/src/can/bxcan.rs
Original file line number Diff line number Diff line change
@@ -1,4 +1,3 @@
use core::convert::AsMut;
use core::future::poll_fn;
use core::marker::PhantomData;
use core::ops::{Deref, DerefMut};
Expand Down
20 changes: 0 additions & 20 deletions embassy-stm32/src/can/fd/message_ram/mod.rs
Original file line number Diff line number Diff line change
Expand Up @@ -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]);
Expand Down
4 changes: 2 additions & 2 deletions embassy-stm32/src/can/fdcan.rs
Original file line number Diff line number Diff line change
Expand Up @@ -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() }
Expand Down
1 change: 1 addition & 0 deletions embassy-stm32/src/dma/mod.rs
Original file line number Diff line number Diff line change
Expand Up @@ -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();
}
}
Expand Down
1 change: 0 additions & 1 deletion embassy-stm32/src/flash/f0.rs
Original file line number Diff line number Diff line change
@@ -1,4 +1,3 @@
use core::convert::TryInto;
use core::ptr::write_volatile;
use core::sync::atomic::{fence, Ordering};

Expand Down
1 change: 0 additions & 1 deletion embassy-stm32/src/flash/f1f3.rs
Original file line number Diff line number Diff line change
@@ -1,4 +1,3 @@
use core::convert::TryInto;
use core::ptr::write_volatile;
use core::sync::atomic::{fence, Ordering};

Expand Down
1 change: 0 additions & 1 deletion embassy-stm32/src/flash/f4.rs
Original file line number Diff line number Diff line change
@@ -1,4 +1,3 @@
use core::convert::TryInto;
use core::ptr::write_volatile;
use core::sync::atomic::{fence, AtomicBool, Ordering};

Expand Down
1 change: 0 additions & 1 deletion embassy-stm32/src/flash/f7.rs
Original file line number Diff line number Diff line change
@@ -1,4 +1,3 @@
use core::convert::TryInto;
use core::ptr::write_volatile;
use core::sync::atomic::{fence, Ordering};

Expand Down
1 change: 0 additions & 1 deletion embassy-stm32/src/flash/g.rs
Original file line number Diff line number Diff line change
@@ -1,4 +1,3 @@
use core::convert::TryInto;
use core::ptr::write_volatile;
use core::sync::atomic::{fence, Ordering};

Expand Down
1 change: 0 additions & 1 deletion embassy-stm32/src/flash/h7.rs
Original file line number Diff line number Diff line change
@@ -1,4 +1,3 @@
use core::convert::TryInto;
use core::ptr::write_volatile;
use core::sync::atomic::{fence, Ordering};

Expand Down
1 change: 0 additions & 1 deletion embassy-stm32/src/flash/u5.rs
Original file line number Diff line number Diff line change
@@ -1,4 +1,3 @@
use core::convert::TryInto;
use core::ptr::write_volatile;
use core::sync::atomic::{fence, Ordering};

Expand Down
1 change: 0 additions & 1 deletion embassy-stm32/src/i2c/v1.rs
Original file line number Diff line number Diff line change
Expand Up @@ -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! /!\
Expand Down
1 change: 0 additions & 1 deletion embassy-stm32/src/i2c/v2.rs
Original file line number Diff line number Diff line change
Expand Up @@ -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();
Expand Down
5 changes: 1 addition & 4 deletions embassy-stm32/src/rtc/datetime.rs
Original file line number Diff line number Diff line change
@@ -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;
Expand Down
2 changes: 0 additions & 2 deletions embassy-stm32/src/sdmmc/mod.rs
Original file line number Diff line number Diff line change
Expand Up @@ -1427,8 +1427,6 @@ pub(crate) mod sealed {
fn regs() -> RegBlock;
fn state() -> &'static AtomicWaker;
}

pub trait Pins<T: Instance> {}
}

/// SDMMC instance trait.
Expand Down
1 change: 0 additions & 1 deletion embassy-stm32/src/time_driver.rs
Original file line number Diff line number Diff line change
@@ -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};

Expand Down
1 change: 0 additions & 1 deletion embassy-stm32/src/timer/complementary_pwm.rs
Original file line number Diff line number Diff line change
Expand Up @@ -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.
Expand Down
1 change: 0 additions & 1 deletion embassy-stm32/src/timer/simple_pwm.rs
Original file line number Diff line number Diff line change
Expand Up @@ -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.
Expand Down
2 changes: 1 addition & 1 deletion embassy-stm32/src/uid.rs
Original file line number Diff line number Diff line change
Expand Up @@ -27,5 +27,5 @@ pub fn uid_hex_bytes() -> &'static [u8; 24] {
LOADED = true;
}
});
unsafe { &UID_HEX }
unsafe { &*core::ptr::addr_of!(UID_HEX) }
}
5 changes: 1 addition & 4 deletions embassy-stm32/src/usart/buffered.rs
Original file line number Diff line number Diff line change
@@ -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> {
Expand Down
4 changes: 2 additions & 2 deletions embassy-stm32/src/usb/otg.rs
Original file line number Diff line number Diff line change
Expand Up @@ -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;

Expand Down
Loading

0 comments on commit eca9aac

Please sign in to comment.