Skip to content

Commit

Permalink
Remove Config from prelude
Browse files Browse the repository at this point in the history
  • Loading branch information
bugadani committed Sep 2, 2024
1 parent 84cc8ba commit c109cbd
Show file tree
Hide file tree
Showing 142 changed files with 186 additions and 220 deletions.
2 changes: 1 addition & 1 deletion esp-hal/MIGRATING-0.20.md
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@ Instead of manually grabbing peripherals and setting up clocks, you should now c
- let peripherals = Peripherals::take();
- let system = SystemControl::new(peripherals.SYSTEM);
- let clocks = ClockControl::boot_defaults(system.clock_control).freeze();
+ let (peripherals, clocks) = esp_hal::init(Config::default());
+ let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default());

// ...
}
Expand Down
6 changes: 3 additions & 3 deletions esp-hal/src/clock/mod.rs
Original file line number Diff line number Diff line change
Expand Up @@ -49,14 +49,14 @@
//! # fn main() {
//! // Initialize with the highest possible frequency for this chip
//! let (peripherals, clocks) = esp_hal::init({
//! let mut config = Config::default();
//! let mut config = esp_hal::Config::default();
//! config.cpu_clock = CpuClock::max();
//! config
//! });
//!
//! // Initialize with custom clock frequency
//! // let (peripherals, clocks) = esp_hal::init({
//! // let mut config = Config::default();
//! // let mut config = esp_hal::Config::default();
#![cfg_attr(
not(any(esp32c2, esp32h2)),
doc = "// config.cpu_clock = CpuClock::Clock160MHz;"
Expand All @@ -67,7 +67,7 @@
//! // });
//! //
//! // Initialize with default clock frequency for this chip
//! // let (peripherals, clocks) = esp_hal::init(Config::default());
//! // let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default());
//! # }
//! ```

Expand Down
4 changes: 2 additions & 2 deletions esp-hal/src/lcd_cam/lcd/i8080.rs
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@
//! ```rust, no_run
#![doc = crate::before_snippet!()]
//! # use esp_hal::gpio::Io;
//! # use esp_hal::lcd_cam::{LcdCam, lcd::i8080::{self, I8080, TxEightBits}};
//! # use esp_hal::lcd_cam::{LcdCam, lcd::i8080::{Config, I8080, TxEightBits}};
//! # use esp_hal::dma_buffers;
//! # use esp_hal::dma::{Dma, DmaPriority};
//! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);
Expand Down Expand Up @@ -49,7 +49,7 @@
//! tx_descriptors,
//! tx_pins,
//! 20.MHz(),
//! i8080::Config::default(),
//! Config::default(),
//! &clocks,
//! )
//! .with_ctrl_pins(io.pins.gpio0, io.pins.gpio47);
Expand Down
4 changes: 2 additions & 2 deletions esp-hal/src/lib.rs
Original file line number Diff line number Diff line change
Expand Up @@ -73,7 +73,7 @@
//!
//! #[entry]
//! fn main() -> ! {
//! let (peripherals, clocks) = esp_hal::init(Config::default());
//! let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default());
//!
//! // Set GPIO0 as an output, and set its state high initially.
//! let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);
Expand Down Expand Up @@ -625,7 +625,7 @@ macro_rules! before_snippet {
# loop {}
# }
# fn main() {
# let (peripherals, clocks) = esp_hal::init(Config::default());
# let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default());
"#
};
}
Expand Down
1 change: 0 additions & 1 deletion esp-hal/src/mcpwm/operator.rs
Original file line number Diff line number Diff line change
Expand Up @@ -486,7 +486,6 @@ impl<'d, Pin: OutputPin, PWM: PwmPeripheral, const OP: u8, const IS_A: bool>
/// # use esp_hal::mcpwm::{McPwm, PeripheralClockConfig};
/// # use esp_hal::mcpwm::operator::{DeadTimeCfg, PwmPinConfig, PWMStream};
/// # use esp_hal::gpio::Io;
/// let (peripherals, clocks) = esp_hal::init(Config::default());
/// # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);
/// // active high complementary using PWMA input
/// let bridge_active = DeadTimeCfg::new_ahc();
Expand Down
2 changes: 1 addition & 1 deletion esp-hal/src/prelude.rs
Original file line number Diff line number Diff line change
Expand Up @@ -38,4 +38,4 @@ pub use crate::timer::timg::{
pub use crate::timer::Timer as _esp_hal_timer_Timer;
#[cfg(any(uart0, uart1, uart2))]
pub use crate::uart::Instance as _esp_hal_uart_Instance;
pub use crate::{clock::CpuClock, entry, macros::*, Config, InterruptConfigurable};
pub use crate::{clock::CpuClock, entry, macros::*, InterruptConfigurable};
8 changes: 4 additions & 4 deletions esp-hal/src/uart.rs
Original file line number Diff line number Diff line change
Expand Up @@ -56,12 +56,12 @@
//! ### Sending and Receiving Data
//! ```rust, no_run
#![doc = crate::before_snippet!()]
//! # use esp_hal::uart::{self, Uart};
//! # use esp_hal::uart::{config::Config, Uart};
//! # use esp_hal::gpio::Io;
//! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);
//! # let mut uart1 = Uart::new_with_config(
//! # peripherals.UART1,
//! # uart::config::Config::default(),
//! # Config::default(),
//! # &clocks,
//! # io.pins.gpio1,
//! # io.pins.gpio2,
Expand All @@ -74,12 +74,12 @@
//! ### Splitting the UART into TX and RX Components
//! ```rust, no_run
#![doc = crate::before_snippet!()]
//! # use esp_hal::uart::{self, Uart};
//! # use esp_hal::uart::{config::Config, Uart};
//! # use esp_hal::gpio::Io;
//! # let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);
//! # let mut uart1 = Uart::new_with_config(
//! # peripherals.UART1,
//! # uart::config::Config::default(),
//! # Config::default(),
//! # &clocks,
//! # io.pins.gpio1,
//! # io.pins.gpio2,
Expand Down
2 changes: 1 addition & 1 deletion examples/src/bin/adc.rs
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@ use esp_println::println;

#[entry]
fn main() -> ! {
let (peripherals, clocks) = esp_hal::init(Config::default());
let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default());

let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);
cfg_if::cfg_if! {
Expand Down
2 changes: 1 addition & 1 deletion examples/src/bin/adc_cal.rs
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@ use esp_println::println;

#[entry]
fn main() -> ! {
let (peripherals, clocks) = esp_hal::init(Config::default());
let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default());

let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);
cfg_if::cfg_if! {
Expand Down
2 changes: 1 addition & 1 deletion examples/src/bin/advanced_serial.rs
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@ use nb::block;

#[entry]
fn main() -> ! {
let (peripherals, clocks) = esp_hal::init(Config::default());
let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default());

let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);

Expand Down
2 changes: 1 addition & 1 deletion examples/src/bin/blinky.rs
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@ use esp_hal::{

#[entry]
fn main() -> ! {
let (peripherals, clocks) = esp_hal::init(Config::default());
let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default());

// Set GPIO0 as an output, and set its state high initially.
let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);
Expand Down
2 changes: 1 addition & 1 deletion examples/src/bin/blinky_erased_pins.rs
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@ use esp_hal::{

#[entry]
fn main() -> ! {
let (peripherals, clocks) = esp_hal::init(Config::default());
let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default());

let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);

Expand Down
2 changes: 1 addition & 1 deletion examples/src/bin/dac.rs
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@ use esp_hal::{analog::dac::Dac, delay::Delay, gpio::Io, prelude::*};

#[entry]
fn main() -> ! {
let (peripherals, clocks) = esp_hal::init(Config::default());
let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default());

let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);

Expand Down
2 changes: 1 addition & 1 deletion examples/src/bin/debug_assist.rs
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@ static DA: Mutex<RefCell<Option<DebugAssist>>> = Mutex::new(RefCell::new(None));

#[entry]
fn main() -> ! {
let (peripherals, _clocks) = esp_hal::init(Config::default());
let (peripherals, _clocks) = esp_hal::init(esp_hal::Config::default());

let mut da = DebugAssist::new(peripherals.ASSIST_DEBUG);
da.set_interrupt_handler(interrupt_handler);
Expand Down
2 changes: 1 addition & 1 deletion examples/src/bin/dma_extmem2mem.rs
Original file line number Diff line number Diff line change
Expand Up @@ -62,7 +62,7 @@ fn init_heap(psram: impl esp_hal::peripheral::Peripheral<P = esp_hal::peripheral
fn main() -> ! {
esp_println::logger::init_logger(log::LevelFilter::Info);

let (peripherals, clocks) = esp_hal::init(Config::default());
let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default());

init_heap(peripherals.PSRAM);
let delay = Delay::new(&clocks);
Expand Down
2 changes: 1 addition & 1 deletion examples/src/bin/dma_mem2mem.rs
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@ const DATA_SIZE: usize = 1024 * 10;
fn main() -> ! {
esp_println::logger::init_logger(log::LevelFilter::Info);

let (peripherals, clocks) = esp_hal::init(Config::default());
let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default());

let delay = Delay::new(&clocks);

Expand Down
4 changes: 2 additions & 2 deletions examples/src/bin/embassy_hello_world.rs
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@
use embassy_executor::Spawner;
use embassy_time::{Duration, Timer};
use esp_backtrace as _;
use esp_hal::{prelude::*, timer::timg::TimerGroup};
use esp_hal::timer::timg::TimerGroup;

#[embassy_executor::task]
async fn run() {
Expand All @@ -25,7 +25,7 @@ async fn run() {
#[esp_hal_embassy::main]
async fn main(spawner: Spawner) {
esp_println::logger::init_logger_from_env();
let (peripherals, clocks) = esp_hal::init(Config::default());
let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default());

esp_println::println!("Init!");

Expand Down
2 changes: 1 addition & 1 deletion examples/src/bin/embassy_i2c.rs
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@ use lis3dh_async::{Lis3dh, Range, SlaveAddr};

#[esp_hal_embassy::main]
async fn main(_spawner: Spawner) {
let (peripherals, clocks) = esp_hal::init(Config::default());
let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default());

let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks);
esp_hal_embassy::init(&clocks, timg0.timer0);
Expand Down
2 changes: 1 addition & 1 deletion examples/src/bin/embassy_i2c_bmp180_calibration_data.rs
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@ use esp_hal::{gpio::Io, i2c::I2C, prelude::*, timer::timg::TimerGroup};

#[esp_hal_embassy::main]
async fn main(_spawner: Spawner) {
let (peripherals, clocks) = esp_hal::init(Config::default());
let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default());

let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks);
esp_hal_embassy::init(&clocks, timg0.timer0);
Expand Down
2 changes: 1 addition & 1 deletion examples/src/bin/embassy_i2s_read.rs
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@ use esp_println::println;
#[esp_hal_embassy::main]
async fn main(_spawner: Spawner) {
println!("Init!");
let (peripherals, clocks) = esp_hal::init(Config::default());
let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default());

let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks);
esp_hal_embassy::init(&clocks, timg0.timer0);
Expand Down
2 changes: 1 addition & 1 deletion examples/src/bin/embassy_i2s_sound.rs
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,7 @@ const SINE: [i16; 64] = [
#[esp_hal_embassy::main]
async fn main(_spawner: Spawner) {
println!("Init!");
let (peripherals, clocks) = esp_hal::init(Config::default());
let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default());

let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks);
esp_hal_embassy::init(&clocks, timg0.timer0);
Expand Down
3 changes: 1 addition & 2 deletions examples/src/bin/embassy_multicore.rs
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,6 @@ use esp_hal::{
cpu_control::{CpuControl, Stack},
get_core,
gpio::{AnyOutput, Io, Level},
prelude::*,
timer::{timg::TimerGroup, ErasedTimer},
};
use esp_hal_embassy::Executor;
Expand Down Expand Up @@ -52,7 +51,7 @@ async fn control_led(

#[esp_hal_embassy::main]
async fn main(_spawner: Spawner) {
let (peripherals, clocks) = esp_hal::init(Config::default());
let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default());

let io = Io::new(peripherals.GPIO, peripherals.IO_MUX);

Expand Down
2 changes: 1 addition & 1 deletion examples/src/bin/embassy_multicore_interrupt.rs
Original file line number Diff line number Diff line change
Expand Up @@ -71,7 +71,7 @@ async fn enable_disable_led(control: &'static Signal<CriticalSectionRawMutex, bo

#[entry]
fn main() -> ! {
let (peripherals, clocks) = esp_hal::init(Config::default());
let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default());

let sw_ints = SoftwareInterruptControl::new(peripherals.SW_INTERRUPT);

Expand Down
3 changes: 1 addition & 2 deletions examples/src/bin/embassy_multiprio.rs
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,6 @@ use embassy_time::{Duration, Instant, Ticker, Timer};
use esp_backtrace as _;
use esp_hal::{
interrupt::{software::SoftwareInterruptControl, Priority},
prelude::*,
timer::{timg::TimerGroup, ErasedTimer},
};
use esp_hal_embassy::InterruptExecutor;
Expand Down Expand Up @@ -72,7 +71,7 @@ async fn main(low_prio_spawner: Spawner) {
esp_println::logger::init_logger_from_env();
println!("Init!");

let (peripherals, clocks) = esp_hal::init(Config::default());
let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default());

let sw_ints = SoftwareInterruptControl::new(peripherals.SW_INTERRUPT);

Expand Down
2 changes: 1 addition & 1 deletion examples/src/bin/embassy_parl_io_rx.rs
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@ use esp_println::println;
#[esp_hal_embassy::main]
async fn main(_spawner: Spawner) {
esp_println::println!("Init!");
let (peripherals, clocks) = esp_hal::init(Config::default());
let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default());

let systimer = SystemTimer::new(peripherals.SYSTIMER).split::<Target>();
esp_hal_embassy::init(&clocks, systimer.alarm0);
Expand Down
2 changes: 1 addition & 1 deletion examples/src/bin/embassy_parl_io_tx.rs
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@ use esp_println::println;
#[esp_hal_embassy::main]
async fn main(_spawner: Spawner) {
esp_println::println!("Init!");
let (peripherals, clocks) = esp_hal::init(Config::default());
let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default());

let systimer = SystemTimer::new(peripherals.SYSTIMER).split::<Target>();
esp_hal_embassy::init(&clocks, systimer.alarm0);
Expand Down
2 changes: 1 addition & 1 deletion examples/src/bin/embassy_rmt_rx.rs
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@ async fn signal_task(mut pin: Output<'static, Gpio5>) {
#[esp_hal_embassy::main]
async fn main(spawner: Spawner) {
println!("Init!");
let (peripherals, clocks) = esp_hal::init(Config::default());
let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default());

let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks);
esp_hal_embassy::init(&clocks, timg0.timer0);
Expand Down
2 changes: 1 addition & 1 deletion examples/src/bin/embassy_rmt_tx.rs
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@ use esp_println::println;
#[esp_hal_embassy::main]
async fn main(_spawner: Spawner) {
println!("Init!");
let (peripherals, clocks) = esp_hal::init(Config::default());
let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default());

let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks);
esp_hal_embassy::init(&clocks, timg0.timer0);
Expand Down
7 changes: 3 additions & 4 deletions examples/src/bin/embassy_serial.rs
Original file line number Diff line number Diff line change
Expand Up @@ -15,10 +15,9 @@ use esp_backtrace as _;
use esp_hal::{
gpio::Io,
peripherals::UART0,
prelude::*,
timer::timg::TimerGroup,
uart::{
config::{AtCmdConfig, Config as UartConfig},
config::{AtCmdConfig, Config},
Uart,
UartRx,
UartTx,
Expand Down Expand Up @@ -79,7 +78,7 @@ async fn reader(
#[esp_hal_embassy::main]
async fn main(spawner: Spawner) {
esp_println::println!("Init!");
let (peripherals, clocks) = esp_hal::init(Config::default());
let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default());

let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks);
esp_hal_embassy::init(&clocks, timg0.timer0);
Expand All @@ -103,7 +102,7 @@ async fn main(spawner: Spawner) {
}
}

let config = UartConfig::default().rx_fifo_full_threshold(READ_BUF_SIZE as u16);
let config = Config::default().rx_fifo_full_threshold(READ_BUF_SIZE as u16);

let mut uart0 =
Uart::new_async_with_config(peripherals.UART0, config, &clocks, tx_pin, rx_pin).unwrap();
Expand Down
2 changes: 1 addition & 1 deletion examples/src/bin/embassy_spi.rs
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@ use esp_hal::{
#[esp_hal_embassy::main]
async fn main(_spawner: Spawner) {
esp_println::println!("Init!");
let (peripherals, clocks) = esp_hal::init(Config::default());
let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default());

let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks);
esp_hal_embassy::init(&clocks, timg0.timer0);
Expand Down
3 changes: 1 addition & 2 deletions examples/src/bin/embassy_touch.rs
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,6 @@ use embassy_time::{Duration, Timer};
use esp_backtrace as _;
use esp_hal::{
gpio::Io,
prelude::*,
rtc_cntl::Rtc,
timer::timg::TimerGroup,
touch::{Touch, TouchConfig, TouchPad},
Expand All @@ -28,7 +27,7 @@ use esp_println::println;
#[esp_hal_embassy::main]
async fn main(_spawner: Spawner) {
esp_println::logger::init_logger_from_env();
let (peripherals, clocks) = esp_hal::init(Config::default());
let (peripherals, clocks) = esp_hal::init(esp_hal::Config::default());

let timg0 = TimerGroup::new(peripherals.TIMG0, &clocks);
esp_hal_embassy::init(&clocks, timg0.timer0);
Expand Down
Loading

0 comments on commit c109cbd

Please sign in to comment.