From aa3b1116acce737f3e95fdbbdb08e9d6467b4c9e Mon Sep 17 00:00:00 2001 From: Niklas Hauser Date: Sat, 4 Apr 2020 12:44:35 +0200 Subject: [PATCH] [delay] Refactor all deprecated usage of delay --- examples/arduino_uno/basic/blink/main.cpp | 4 +-- examples/avr/1-wire/ds18b20/main.cpp | 9 ++--- examples/avr/adc/basic/main.cpp | 3 +- examples/avr/app_can2usb/main.cpp | 3 +- examples/avr/assert/main.cpp | 6 ++-- .../avr/display/dogm128/caged_ball/main.cpp | 3 +- examples/avr/display/dogm128/image/main.cpp | 5 +-- examples/avr/display/dogm128/text/main.cpp | 5 +-- examples/avr/display/dogm128/touch/main.cpp | 5 +-- examples/avr/display/hd44780/main.cpp | 5 +-- examples/avr/gpio/blinking/main.cpp | 3 +- examples/avr/ports/main.cpp | 4 +-- examples/avr/xpcc/receiver/main.cpp | 3 +- examples/avr/xpcc/sender/main.cpp | 3 +- examples/generic/blinky/main.cpp | 2 +- examples/linux/xpcc/basic/main.cpp | 3 +- examples/nucleo_f042k6/adc/main.cpp | 2 +- examples/nucleo_f042k6/blink/main.cpp | 2 +- examples/nucleo_f103rb/hard_fault/main.cpp | 4 +-- examples/nucleo_f103rb/undefined_irq/main.cpp | 2 +- examples/nucleo_f303k8/blink/main.cpp | 2 +- examples/nucleo_f401re/blink/main.cpp | 2 +- examples/nucleo_f411re/blink/main.cpp | 2 +- .../radio/nrf24-phy-test/main.cpp | 2 +- .../radio/nrf24-scanner/main.cpp | 4 +-- examples/nucleo_f429zi/blink/main.cpp | 2 +- examples/nucleo_f429zi/cmsis_dsp/runner.cpp | 2 +- examples/nucleo_f446re/blink/main.cpp | 2 +- examples/nucleo_g071rb/adc/main.cpp | 2 +- examples/nucleo_g071rb/blink/main.cpp | 2 +- .../nucleo_g071rb/custom_allocator/main.cpp | 2 +- examples/nucleo_g474re/blink/main.cpp | 2 +- examples/nucleo_l152re/blink/main.cpp | 2 +- examples/nucleo_l432kc/blink/main.cpp | 2 +- examples/nucleo_l432kc/comp/main.cpp | 2 +- examples/nucleo_l432kc/pwm/main.cpp | 2 +- examples/nucleo_l432kc/pwm_advanced/main.cpp | 2 +- examples/nucleo_l476rg/adc/main.cpp | 2 +- examples/nucleo_l476rg/blink/main.cpp | 2 +- examples/nucleo_l476rg/i2c_test/main.cpp | 16 ++++----- examples/olimexino_stm32/blink/main.cpp | 2 +- .../stm32f030f4p6_demo_board/blink/main.cpp | 4 +-- examples/stm32f072_discovery/blink/main.cpp | 2 +- .../stm32f072_discovery/hard_fault/main.cpp | 2 +- examples/stm32f072_discovery/uart/main.cpp | 2 +- .../unaligned_access/main.cpp | 4 +-- examples/stm32f0_discovery/blink/main.cpp | 2 +- .../stm32f103c8t6_black_pill/blink/main.cpp | 4 +-- .../stm32f103c8t6_blue_pill/blink/main.cpp | 4 +-- .../stm32f103c8t6_blue_pill/tlc594x/main.cpp | 2 +- examples/stm32f1_discovery/blink/main.cpp | 4 +-- .../stm32f3_discovery/adc/continous/main.cpp | 2 +- .../stm32f3_discovery/adc/interrupt/main.cpp | 2 +- .../stm32f3_discovery/adc/simple/main.cpp | 2 +- examples/stm32f3_discovery/blink/main.cpp | 16 ++++----- examples/stm32f3_discovery/comp/main.cpp | 2 +- .../stm32f3_discovery/timer/basic/main.cpp | 2 +- .../stm32f401ccu_mini_f401/blink/main.cpp | 2 +- .../stm32f411ceu_mini_f411/blink/main.cpp | 2 +- examples/stm32f429_discovery/blink/main.cpp | 4 +-- examples/stm32f469_discovery/display/main.cpp | 2 +- .../exceptions_rtti/main.cpp | 2 +- .../stm32f469_discovery/game_of_life/main.cpp | 3 +- .../stm32f469_discovery/hard_fault/main.cpp | 4 +-- examples/stm32f469_discovery/ports/main.cpp | 4 +-- .../threadsafe_statics/main.cpp | 2 +- .../tlsf-allocator/main.cpp | 2 +- .../stm32f4_discovery/adc/interrupt/main.cpp | 2 +- .../stm32f4_discovery/adc/simple/main.cpp | 2 +- .../app_uart_sniffer/main.cpp | 2 +- examples/stm32f4_discovery/blink/main.cpp | 2 +- examples/stm32f4_discovery/exti/main.cpp | 6 ++-- examples/stm32f4_discovery/fsmc/main.cpp | 2 +- .../stm32f4_discovery/open407v-d/gui/main.cpp | 4 +-- .../open407v-d/touchscreen/main.cpp | 2 +- examples/stm32f4_discovery/sab2/main.cpp | 2 +- .../stm32f4_discovery/timer_test/main.cpp | 4 +-- examples/stm32f4_discovery/uart/main.cpp | 2 +- examples/stm32f746g_discovery/blink/main.cpp | 2 +- examples/stm32f769i_discovery/blink/main.cpp | 2 +- examples/stm32l1_discovery/blink/main.cpp | 2 +- examples/stm32l476_discovery/blink/main.cpp | 2 +- examples/zmq/1_stm32/main.cpp | 2 +- examples/zmq/2_zmq_gateway/main.cpp | 3 +- examples/zmq/3_zmq_app/main.cpp | 3 +- examples/zmq/4_zmq_backtoback/main.cpp | 3 +- src/modm/architecture/interface/gpio.md | 2 +- src/modm/architecture/interface/i2c.hpp | 8 ++--- src/modm/board/board.cpp.in | 5 +-- src/modm/board/board.hpp | 1 + src/modm/board/disco_f469ni/board_dsi.cpp | 6 ++-- src/modm/board/disco_f469ni/board_init.cpp | 4 +-- .../board/disco_f469ni/board_otm8009a.cpp | 12 +++---- src/modm/board/disco_f469ni/board_sdram.cpp | 4 +-- src/modm/board/disco_l152rc/board.hpp | 4 +-- src/modm/board/nucleo_l152re/board.hpp | 2 +- src/modm/driver/adc/ad7280a_impl.hpp | 8 ++--- src/modm/driver/adc/ad7928_impl.hpp | 4 +-- src/modm/driver/adc/hx711_impl.hpp | 12 +++---- .../bus/bitbang_memory_interface_impl.hpp | 26 +++++++-------- src/modm/driver/bus/tft_memory_bus.hpp | 10 +++--- src/modm/driver/can/mcp2515_impl.hpp | 6 ++-- src/modm/driver/dac/mcp4922_impl.hpp | 4 +-- src/modm/driver/display/hd44780_base_impl.hpp | 33 ++++++++++--------- src/modm/driver/display/ks0108.hpp | 7 ++-- src/modm/driver/display/ks0108_impl.hpp | 12 +++---- src/modm/driver/display/nokia6610_impl.hpp | 18 +++++----- src/modm/driver/display/siemens_m55_impl.hpp | 13 ++++---- src/modm/driver/display/siemens_s65_impl.hpp | 17 +++++----- src/modm/driver/display/siemens_s75_impl.hpp | 10 +++--- src/modm/driver/display/st7036_impl.hpp | 4 +-- src/modm/driver/display/st7565_impl.hpp | 2 +- src/modm/driver/fpga/xilinx_spartan3_impl.hpp | 9 +++-- src/modm/driver/fpga/xilinx_spartan6_impl.hpp | 6 ++-- src/modm/driver/gpio/mcp23s08_impl.hpp | 12 +++---- src/modm/driver/motion/adns9800_impl.hpp | 28 ++++++++-------- src/modm/driver/other/ad840x_impl.hpp | 2 +- src/modm/driver/pressure/scp1000_impl.hpp | 6 ++-- src/modm/driver/pwm/max6966_impl.hpp | 2 +- src/modm/driver/pwm/tlc594x_impl.hpp | 2 +- .../driver/radio/nrf24/nrf24_config_impl.hpp | 2 +- .../driver/radio/nrf24/nrf24_phy_impl.hpp | 2 +- src/modm/driver/rtc/ds1302.hpp | 6 ++-- src/modm/driver/rtc/ds1302_impl.hpp | 26 +++++++-------- src/modm/driver/storage/spi_ram_impl.hpp | 4 +-- src/modm/driver/touch/ads7843_impl.hpp | 6 ++-- src/modm/platform/adc/stm32f0/adc_impl.hpp.in | 4 +-- src/modm/platform/adc/stm32f3/adc_impl.hpp.in | 2 +- src/modm/platform/can/stm32/can.cpp.in | 2 +- .../i2c/bitbang/bitbang_i2c_master.hpp.in | 4 +-- .../one_wire/bitbang/bitbang_master.hpp.in | 20 +++++------ .../bitbang/bitbang_master_impl.hpp.in | 22 ++++++------- .../spi/bitbang/bitbang_spi_master_impl.hpp | 2 +- test/all/avr.cpp | 3 +- test/all/stm32.cpp | 3 +- 135 files changed, 350 insertions(+), 325 deletions(-) diff --git a/examples/arduino_uno/basic/blink/main.cpp b/examples/arduino_uno/basic/blink/main.cpp index bfb548cefd..904d97b400 100644 --- a/examples/arduino_uno/basic/blink/main.cpp +++ b/examples/arduino_uno/basic/blink/main.cpp @@ -24,8 +24,8 @@ main() while (true) { LedD13::set(); - modm::delayMilliseconds(1000); + modm::delay(1s); LedD13::reset(); - modm::delayMilliseconds(1000); + modm::delay(1s); } } diff --git a/examples/avr/1-wire/ds18b20/main.cpp b/examples/avr/1-wire/ds18b20/main.cpp index 748494c0c5..839524bec3 100644 --- a/examples/avr/1-wire/ds18b20/main.cpp +++ b/examples/avr/1-wire/ds18b20/main.cpp @@ -17,6 +17,7 @@ using namespace modm::platform; using namespace modm::literals; +using namespace std::chrono_literals; using OneWirePin = GpioC2; using OneWireMaster = BitBangOneWireMaster; @@ -35,14 +36,14 @@ main() modm::IOStream output(device); output << "Welcome" << modm::endl; - modm::delayMilliseconds(100); + modm::delay(100ms); OneWireMaster::connect(); OneWireMaster::initialize(); if (!OneWireMaster::touchReset()) { output << "No devices found!" << modm::endl; - modm::delayMilliseconds(100); + modm::delay(100ms); while (true) { // wait forever } @@ -58,7 +59,7 @@ main() output << rom[i]; } output << modm::ascii << modm::endl; - modm::delayMilliseconds(100); + modm::delay(100ms); } output << "finished!" << modm::endl; @@ -74,7 +75,7 @@ main() int16_t temperature = ds18b20.readTemperature(); output << "Temperature: " << temperature << modm::endl; - modm::delayMilliseconds(100); + modm::delay(100ms); ds18b20.startConversion(); } diff --git a/examples/avr/adc/basic/main.cpp b/examples/avr/adc/basic/main.cpp index 2e83f958f8..99c53a5e21 100644 --- a/examples/avr/adc/basic/main.cpp +++ b/examples/avr/adc/basic/main.cpp @@ -16,6 +16,7 @@ using namespace modm::platform; using namespace modm::literals; +using namespace std::chrono_literals; int main() @@ -62,7 +63,7 @@ main() // receiving the UART output on a PC. If you want to do further // calculations with the results instead of sending it // you do not need this. - modm::delayMilliseconds(300); + modm::delay(300ms); // restart the conversion Adc::setChannel(0); diff --git a/examples/avr/app_can2usb/main.cpp b/examples/avr/app_can2usb/main.cpp index 09ab932f0f..691a768841 100644 --- a/examples/avr/app_can2usb/main.cpp +++ b/examples/avr/app_can2usb/main.cpp @@ -29,6 +29,7 @@ #include using namespace modm::platform; +using namespace std::chrono_literals; // LED1 Status typedef GpioOutputD7 LedStatus; @@ -110,7 +111,7 @@ main() while (true) { - modm::delayMilliseconds(100); + modm::delay(100ms); LedStatus::toggle(); LedRxHigh::toggle(); LedRxLow::toggle(); diff --git a/examples/avr/assert/main.cpp b/examples/avr/assert/main.cpp index 39fc6798c0..3695aa8897 100644 --- a/examples/avr/assert/main.cpp +++ b/examples/avr/assert/main.cpp @@ -32,9 +32,9 @@ modm_abandon(const modm::AssertionInfo &info) Leds::setOutput(); while (true) { Leds::write(1); - modm::delayMilliseconds(20); + modm::delay(20ms); Leds::write(0); - modm::delayMilliseconds(180); + modm::delay(180ms); } } @@ -87,6 +87,6 @@ int main() while (true) { LedD13::toggle(); - modm::delayMilliseconds(500); + modm::delay(500ms); } } diff --git a/examples/avr/display/dogm128/caged_ball/main.cpp b/examples/avr/display/dogm128/caged_ball/main.cpp index 0973bfaf74..171a4dbc24 100644 --- a/examples/avr/display/dogm128/caged_ball/main.cpp +++ b/examples/avr/display/dogm128/caged_ball/main.cpp @@ -17,6 +17,7 @@ using namespace modm::platform; using namespace modm::literals; +using namespace std::chrono_literals; namespace led @@ -82,6 +83,6 @@ main() display.drawCircle(Point(x, y), radius); display.update(); - modm::delayMilliseconds(50); + modm::delay(50ms); } } diff --git a/examples/avr/display/dogm128/image/main.cpp b/examples/avr/display/dogm128/image/main.cpp index ac32bfa6c2..77a9d55fd2 100644 --- a/examples/avr/display/dogm128/image/main.cpp +++ b/examples/avr/display/dogm128/image/main.cpp @@ -28,6 +28,7 @@ using namespace modm::platform; using namespace modm::literals; +using namespace std::chrono_literals; namespace led @@ -218,7 +219,7 @@ main() display.drawImage(modm::glcd::Point(0, 0), modm::accessor::asFlash(bootscreen)); display.update(); - modm::delayMilliseconds(1500); + modm::delay(1.5s); uint8_t units = 0; uint8_t tens = 0; @@ -237,6 +238,6 @@ main() drawNumber(modm::glcd::Point(64, 0), units); display.update(); - modm::delayMilliseconds(200); + modm::delay(200ms); } } diff --git a/examples/avr/display/dogm128/text/main.cpp b/examples/avr/display/dogm128/text/main.cpp index 8110840adb..503f367d9d 100644 --- a/examples/avr/display/dogm128/text/main.cpp +++ b/examples/avr/display/dogm128/text/main.cpp @@ -18,6 +18,7 @@ using namespace modm::platform; using namespace modm::literals; +using namespace std::chrono_literals; // LCD Backlight @@ -76,7 +77,7 @@ main() display << 0 << 12 << 345 << 6789 << "!\"§$%&/()=?`´,;:-<>"; display.update(); - modm::delayMilliseconds(2000); + modm::delay(2s); display.clear(); display.setFont(modm::font::Assertion); @@ -87,7 +88,7 @@ main() display << "0123456789!\"§$%&/()=?`´,;:-<>"; display.update(); - modm::delayMilliseconds(2000); + modm::delay(2s); display.clear(); display.setFont(modm::font::ArcadeClassic); diff --git a/examples/avr/display/dogm128/touch/main.cpp b/examples/avr/display/dogm128/touch/main.cpp index 7367d54fdd..334c3815ed 100644 --- a/examples/avr/display/dogm128/touch/main.cpp +++ b/examples/avr/display/dogm128/touch/main.cpp @@ -18,6 +18,7 @@ using namespace modm::platform; using namespace modm::literals; +using namespace std::chrono_literals; namespace touch { @@ -115,7 +116,7 @@ main() touch::Left::setOutput(); touch::Right::set(); touch::Right::setOutput(); - modm::delayMilliseconds(2); + modm::delay(2ms); int16_t xAdc = Adc::readChannel(0); @@ -128,7 +129,7 @@ main() touch::Bottom::setOutput(); touch::Top::set(); touch::Top::setOutput(); - modm::delayMilliseconds(2); + modm::delay(2ms); int16_t yAdc = Adc::readChannel(1); diff --git a/examples/avr/display/hd44780/main.cpp b/examples/avr/display/hd44780/main.cpp index 1f89fc30fa..61fa7f452a 100644 --- a/examples/avr/display/hd44780/main.cpp +++ b/examples/avr/display/hd44780/main.cpp @@ -15,6 +15,7 @@ #include using namespace modm::platform; +using namespace std::chrono_literals; // define the pins used by the LCD namespace lcd @@ -46,7 +47,7 @@ main() // The LCD needs at least 50ms after power-up until it can be // initialized. To make sure this is met we wait here - modm::delayMilliseconds(50); + modm::delay(50ms); display.initialize(); display.setCursor(0, 0); @@ -64,6 +65,6 @@ main() counter++; - modm::delayMilliseconds(200); + modm::delay(200ms); } } diff --git a/examples/avr/gpio/blinking/main.cpp b/examples/avr/gpio/blinking/main.cpp index d5d1369bcd..912eb2e962 100644 --- a/examples/avr/gpio/blinking/main.cpp +++ b/examples/avr/gpio/blinking/main.cpp @@ -13,6 +13,7 @@ #include using namespace modm::platform; +using namespace std::chrono_literals; typedef GpioOutputB0 Led; @@ -25,7 +26,7 @@ main() { Led::toggle(); - modm::delayMilliseconds(1000); + modm::delay(1s); } } diff --git a/examples/avr/ports/main.cpp b/examples/avr/ports/main.cpp index 9f4731f85e..302f6b3948 100644 --- a/examples/avr/ports/main.cpp +++ b/examples/avr/ports/main.cpp @@ -77,10 +77,10 @@ int main() PinGroup4::setInput(); serialStream << modm::bin << PinGroup4::read() << modm::endl; serialStream << modm::endl; - PinGroup::setOutput(modm::Gpio::High); modm::delayMilliseconds(1000); + PinGroup::setOutput(modm::Gpio::High); modm::delay(1s); const auto fn_report = []() { - serialStream << modm::bin << PinGroup::read() << modm::endl; modm::delayMilliseconds(200); + serialStream << modm::bin << PinGroup::read() << modm::endl; modm::delay(200ms); }; while (true) diff --git a/examples/avr/xpcc/receiver/main.cpp b/examples/avr/xpcc/receiver/main.cpp index 379f37f3c4..e56beac975 100644 --- a/examples/avr/xpcc/receiver/main.cpp +++ b/examples/avr/xpcc/receiver/main.cpp @@ -20,6 +20,7 @@ using namespace modm::platform; using namespace modm::literals; +using namespace std::chrono_literals; // set new log level #undef MODM_LOG_LEVEL @@ -111,6 +112,6 @@ main() component::receiver.update(); - modm::delayMicroseconds(100); + modm::delay(100us); } } diff --git a/examples/avr/xpcc/sender/main.cpp b/examples/avr/xpcc/sender/main.cpp index 19a0f3763b..f00255c8a8 100644 --- a/examples/avr/xpcc/sender/main.cpp +++ b/examples/avr/xpcc/sender/main.cpp @@ -20,6 +20,7 @@ using namespace modm::platform; using namespace modm::literals; +using namespace std::chrono_literals; // set new log level #undef MODM_LOG_LEVEL @@ -111,6 +112,6 @@ main() component::sender.update(); - modm::delayMicroseconds(100); + modm::delay(100us); } } diff --git a/examples/generic/blinky/main.cpp b/examples/generic/blinky/main.cpp index 9f1e44f816..8aed4ca6fd 100644 --- a/examples/generic/blinky/main.cpp +++ b/examples/generic/blinky/main.cpp @@ -18,7 +18,7 @@ int main() while (true) { Board::Leds::toggle(); - modm::delayMilliseconds(Board::Button::read() ? 250 : 500); + modm::delay(Board::Button::read() ? 250ms : 500ms); #ifdef MODM_BOARD_HAS_LOGGER static uint32_t counter(0); MODM_LOG_INFO << "Loop counter: " << (counter++) << modm::endl; diff --git a/examples/linux/xpcc/basic/main.cpp b/examples/linux/xpcc/basic/main.cpp index 1af21576b1..562007436b 100644 --- a/examples/linux/xpcc/basic/main.cpp +++ b/examples/linux/xpcc/basic/main.cpp @@ -12,6 +12,7 @@ // ---------------------------------------------------------------------------- #include +using namespace std::chrono_literals; #include // #include @@ -65,6 +66,6 @@ main() component::receiver.update(); component::sender.update(); - modm::delayMicroseconds(100); + modm::delay(100us); } } diff --git a/examples/nucleo_f042k6/adc/main.cpp b/examples/nucleo_f042k6/adc/main.cpp index a351d0bb17..e6ec485772 100644 --- a/examples/nucleo_f042k6/adc/main.cpp +++ b/examples/nucleo_f042k6/adc/main.cpp @@ -44,7 +44,7 @@ main() while (true) { LedD13::toggle(); - modm::delayMilliseconds(100); + modm::delay(100ms); MODM_LOG_INFO << "mV=" << (Vref * Adc::getValue() / 4095ul) << modm::endl; diff --git a/examples/nucleo_f042k6/blink/main.cpp b/examples/nucleo_f042k6/blink/main.cpp index fe99a871bc..27b5693d5a 100644 --- a/examples/nucleo_f042k6/blink/main.cpp +++ b/examples/nucleo_f042k6/blink/main.cpp @@ -31,7 +31,7 @@ main() while (true) { LedD13::toggle(); - modm::delayMilliseconds(Button::read() ? 100 : 500); + modm::delay(Button::read() ? 100ms : 500ms); MODM_LOG_INFO << "loop: " << counter++ << modm::endl; } diff --git a/examples/nucleo_f103rb/hard_fault/main.cpp b/examples/nucleo_f103rb/hard_fault/main.cpp index 39bae44ab7..ebe6c9b4d1 100644 --- a/examples/nucleo_f103rb/hard_fault/main.cpp +++ b/examples/nucleo_f103rb/hard_fault/main.cpp @@ -37,7 +37,7 @@ void modm_hardfault_entry() // Put hardware in safe mode here Board::Leds::set(); // But do not wait forever - modm::delayMilliseconds(100); + modm::delay(100ms); // Do not depend on interrupts in this function (buffered UART etc!) } @@ -79,7 +79,7 @@ main() function2(23, 43); - modm::delayMilliseconds(250); + modm::delay(250ms); } return 0; diff --git a/examples/nucleo_f103rb/undefined_irq/main.cpp b/examples/nucleo_f103rb/undefined_irq/main.cpp index 2c277df565..e9c7c56d79 100644 --- a/examples/nucleo_f103rb/undefined_irq/main.cpp +++ b/examples/nucleo_f103rb/undefined_irq/main.cpp @@ -72,7 +72,7 @@ int main() NVIC_SetPendingIRQ(IRQn_Type(int(EXTI0_IRQn) + ii)); ii = (ii + 1) % 5; // wait one second for debounce - modm::delayMilliseconds(500); + modm::delay(500ms); } } diff --git a/examples/nucleo_f303k8/blink/main.cpp b/examples/nucleo_f303k8/blink/main.cpp index 467df82f17..f7a7bcef2e 100644 --- a/examples/nucleo_f303k8/blink/main.cpp +++ b/examples/nucleo_f303k8/blink/main.cpp @@ -31,7 +31,7 @@ main() while (true) { LedD13::toggle(); - modm::delayMilliseconds(Button::read() ? 100 : 500); + modm::delay(Button::read() ? 100ms : 500ms); MODM_LOG_INFO << "loop: " << counter++ << modm::endl; } diff --git a/examples/nucleo_f401re/blink/main.cpp b/examples/nucleo_f401re/blink/main.cpp index 9ce0515806..a350d65468 100644 --- a/examples/nucleo_f401re/blink/main.cpp +++ b/examples/nucleo_f401re/blink/main.cpp @@ -31,7 +31,7 @@ main() while (true) { LedD13::toggle(); - modm::delayMilliseconds(Button::read() ? 100 : 500); + modm::delay(Button::read() ? 100ms : 500ms); MODM_LOG_INFO << "loop: " << counter++ << modm::endl; } diff --git a/examples/nucleo_f411re/blink/main.cpp b/examples/nucleo_f411re/blink/main.cpp index 467df82f17..f7a7bcef2e 100644 --- a/examples/nucleo_f411re/blink/main.cpp +++ b/examples/nucleo_f411re/blink/main.cpp @@ -31,7 +31,7 @@ main() while (true) { LedD13::toggle(); - modm::delayMilliseconds(Button::read() ? 100 : 500); + modm::delay(Button::read() ? 100ms : 500ms); MODM_LOG_INFO << "loop: " << counter++ << modm::endl; } diff --git a/examples/nucleo_f411re/radio/nrf24-phy-test/main.cpp b/examples/nucleo_f411re/radio/nrf24-phy-test/main.cpp index 7d52f27204..7abb719f72 100644 --- a/examples/nucleo_f411re/radio/nrf24-phy-test/main.cpp +++ b/examples/nucleo_f411re/radio/nrf24-phy-test/main.cpp @@ -53,7 +53,7 @@ int main() MODM_LOG_INFO << "Testing PHY2" << modm::endl; test(); - modm::delayMilliseconds(1000); + modm::delay(1s); } return 0; diff --git a/examples/nucleo_f411re/radio/nrf24-scanner/main.cpp b/examples/nucleo_f411re/radio/nrf24-scanner/main.cpp index 1a7c452b2d..83f67b779d 100644 --- a/examples/nucleo_f411re/radio/nrf24-scanner/main.cpp +++ b/examples/nucleo_f411re/radio/nrf24-scanner/main.cpp @@ -79,9 +79,9 @@ int main() Nrf1Phy::writeRegister(Nrf1Phy::NrfRegister::RF_CH, i + channel_start); Nrf1Ce::set(); - modm::delayMicroseconds(rx_settle); + modm::delay(std::chrono::microseconds(rx_settle)); Nrf1Ce::reset(); - modm::delayMicroseconds(2); + modm::delay(2us); channel_info[i] += 5*Nrf1Phy::readRegister(Nrf1Phy::NrfRegister::RPD); if(channel_info[i] > max) diff --git a/examples/nucleo_f429zi/blink/main.cpp b/examples/nucleo_f429zi/blink/main.cpp index 5bee7b62ff..205bc44743 100644 --- a/examples/nucleo_f429zi/blink/main.cpp +++ b/examples/nucleo_f429zi/blink/main.cpp @@ -31,7 +31,7 @@ main() while (true) { Leds::write(1 << (counter % (Leds::width+1) )); - modm::delayMilliseconds(Button::read() ? 100 : 500); + modm::delay(Button::read() ? 100ms : 500ms); MODM_LOG_INFO << "loop: " << counter++ << modm::endl; } diff --git a/examples/nucleo_f429zi/cmsis_dsp/runner.cpp b/examples/nucleo_f429zi/cmsis_dsp/runner.cpp index 5b3cfe91e4..c1f5798e23 100644 --- a/examples/nucleo_f429zi/cmsis_dsp/runner.cpp +++ b/examples/nucleo_f429zi/cmsis_dsp/runner.cpp @@ -29,7 +29,7 @@ int main() } else { Board::LedRed::toggle(); } - modm::delayMilliseconds(1000); + modm::delay(1s); } return 0; diff --git a/examples/nucleo_f446re/blink/main.cpp b/examples/nucleo_f446re/blink/main.cpp index 5bee7b62ff..205bc44743 100644 --- a/examples/nucleo_f446re/blink/main.cpp +++ b/examples/nucleo_f446re/blink/main.cpp @@ -31,7 +31,7 @@ main() while (true) { Leds::write(1 << (counter % (Leds::width+1) )); - modm::delayMilliseconds(Button::read() ? 100 : 500); + modm::delay(Button::read() ? 100ms : 500ms); MODM_LOG_INFO << "loop: " << counter++ << modm::endl; } diff --git a/examples/nucleo_g071rb/adc/main.cpp b/examples/nucleo_g071rb/adc/main.cpp index 4747e5c97a..9cca71dc89 100644 --- a/examples/nucleo_g071rb/adc/main.cpp +++ b/examples/nucleo_g071rb/adc/main.cpp @@ -43,7 +43,7 @@ main() while (true) { LedD13::toggle(); - modm::delayMilliseconds(100); + modm::delay(100ms); MODM_LOG_INFO << "mV=" << (Vref * Adc1::getValue() / 4095ul) << modm::endl; } diff --git a/examples/nucleo_g071rb/blink/main.cpp b/examples/nucleo_g071rb/blink/main.cpp index 130a1b0d50..7b18c00195 100644 --- a/examples/nucleo_g071rb/blink/main.cpp +++ b/examples/nucleo_g071rb/blink/main.cpp @@ -31,7 +31,7 @@ main() while (true) { LedD13::toggle(); - modm::delayMilliseconds(Button::read() ? 500 : 1000); + modm::delay(Button::read() ? 500ms : 1s); MODM_LOG_INFO << "loop: " << counter++ << modm::endl; } diff --git a/examples/nucleo_g071rb/custom_allocator/main.cpp b/examples/nucleo_g071rb/custom_allocator/main.cpp index ca11a63465..ffadfb6cf1 100644 --- a/examples/nucleo_g071rb/custom_allocator/main.cpp +++ b/examples/nucleo_g071rb/custom_allocator/main.cpp @@ -52,7 +52,7 @@ int main() while (true) { LedD13::toggle(); - modm::delayMilliseconds(200); + modm::delay(200ms); // leak memory until heap is exhausted ptr = malloc(1024); diff --git a/examples/nucleo_g474re/blink/main.cpp b/examples/nucleo_g474re/blink/main.cpp index 4ef69dffc8..942c463502 100644 --- a/examples/nucleo_g474re/blink/main.cpp +++ b/examples/nucleo_g474re/blink/main.cpp @@ -30,7 +30,7 @@ main() while (true) { LedD13::toggle(); - modm::delayMilliseconds(Button::read() ? 100 : 500); + modm::delay(Button::read() ? 100ms : 500ms); MODM_LOG_INFO << "loop: " << counter++ << modm::endl; } diff --git a/examples/nucleo_l152re/blink/main.cpp b/examples/nucleo_l152re/blink/main.cpp index 467df82f17..f7a7bcef2e 100644 --- a/examples/nucleo_l152re/blink/main.cpp +++ b/examples/nucleo_l152re/blink/main.cpp @@ -31,7 +31,7 @@ main() while (true) { LedD13::toggle(); - modm::delayMilliseconds(Button::read() ? 100 : 500); + modm::delay(Button::read() ? 100ms : 500ms); MODM_LOG_INFO << "loop: " << counter++ << modm::endl; } diff --git a/examples/nucleo_l432kc/blink/main.cpp b/examples/nucleo_l432kc/blink/main.cpp index 6d5864ee5e..c5853f01af 100644 --- a/examples/nucleo_l432kc/blink/main.cpp +++ b/examples/nucleo_l432kc/blink/main.cpp @@ -31,7 +31,7 @@ main() while (true) { Leds::write(1 << (counter % Leds::width)); - modm::delayMilliseconds(Button::read() ? 100 : 500); + modm::delay(Button::read() ? 100ms : 500ms); MODM_LOG_INFO << "loop: " << counter++ << modm::endl; } diff --git a/examples/nucleo_l432kc/comp/main.cpp b/examples/nucleo_l432kc/comp/main.cpp index d51eb1760b..fd1c4d5275 100644 --- a/examples/nucleo_l432kc/comp/main.cpp +++ b/examples/nucleo_l432kc/comp/main.cpp @@ -40,7 +40,7 @@ main() while (true) { - modm::delayMilliseconds(250); + modm::delay(250ms); MODM_LOG_INFO << "Comparator: " << Comparator::getOutput() << modm::endl; Board::LedD13::set(Comparator::getOutput()); } diff --git a/examples/nucleo_l432kc/pwm/main.cpp b/examples/nucleo_l432kc/pwm/main.cpp index a6c6e3308e..7af7b7cfd7 100644 --- a/examples/nucleo_l432kc/pwm/main.cpp +++ b/examples/nucleo_l432kc/pwm/main.cpp @@ -52,7 +52,7 @@ main() while (true) { LedD13::toggle(); - modm::delayMilliseconds(500); + modm::delay(500ms); MODM_LOG_INFO << "loop: " << counter++ << modm::endl; MODM_LOG_INFO << "Timer1 counter: " << Timer1::getValue() << modm::endl; } diff --git a/examples/nucleo_l432kc/pwm_advanced/main.cpp b/examples/nucleo_l432kc/pwm_advanced/main.cpp index 7f9cf06882..62bb1df78d 100644 --- a/examples/nucleo_l432kc/pwm_advanced/main.cpp +++ b/examples/nucleo_l432kc/pwm_advanced/main.cpp @@ -109,7 +109,7 @@ main() if(++state > 3) { state = 0; } - modm::delayMilliseconds(250); + modm::delay(250ms); TriggerOut::reset(); } diff --git a/examples/nucleo_l476rg/adc/main.cpp b/examples/nucleo_l476rg/adc/main.cpp index d215230353..8e045f47a9 100644 --- a/examples/nucleo_l476rg/adc/main.cpp +++ b/examples/nucleo_l476rg/adc/main.cpp @@ -40,7 +40,7 @@ main() while (true) { LedGreen::toggle(); - modm::delayMilliseconds(Button::read() ? 250 : 500); + modm::delay(Button::read() ? 250ms : 500ms); Adc1::startConversion(); // wait for conversion to finish diff --git a/examples/nucleo_l476rg/blink/main.cpp b/examples/nucleo_l476rg/blink/main.cpp index 6f916f0f47..47913e7234 100644 --- a/examples/nucleo_l476rg/blink/main.cpp +++ b/examples/nucleo_l476rg/blink/main.cpp @@ -32,7 +32,7 @@ main() while (true) { LedGreen::toggle(); - modm::delayMilliseconds(Button::read() ? 250 : 500); + modm::delay(Button::read() ? 250ms : 500ms); } return 0; diff --git a/examples/nucleo_l476rg/i2c_test/main.cpp b/examples/nucleo_l476rg/i2c_test/main.cpp index fe0c16e473..916217be29 100644 --- a/examples/nucleo_l476rg/i2c_test/main.cpp +++ b/examples/nucleo_l476rg/i2c_test/main.cpp @@ -139,30 +139,30 @@ main() LedGreen::set(); RF_CALL_BLOCKING(i2c.ping()); - modm::delayMicroseconds(25); + modm::delay(25us); RF_CALL_BLOCKING(i2c.write(0)); - modm::delayMicroseconds(25); + modm::delay(25us); RF_CALL_BLOCKING(i2c.write(1)); - modm::delayMicroseconds(25); + modm::delay(25us); RF_CALL_BLOCKING(i2c.write(2)); - modm::delayMicroseconds(25); + modm::delay(25us); RF_CALL_BLOCKING(i2c.writeRead(0, 5)); - modm::delayMicroseconds(25); + modm::delay(25us); RF_CALL_BLOCKING(i2c.writeRead(1, 5)); - modm::delayMicroseconds(25); + modm::delay(25us); RF_CALL_BLOCKING(i2c.writeRead(2, 5)); - modm::delayMicroseconds(25); + modm::delay(25us); // Blink if run without hanging. while(true) { LedGreen::toggle(); - modm::delayMilliseconds(500); + modm::delay(500ms); }; return 0; diff --git a/examples/olimexino_stm32/blink/main.cpp b/examples/olimexino_stm32/blink/main.cpp index 2894a29642..3a891ec401 100644 --- a/examples/olimexino_stm32/blink/main.cpp +++ b/examples/olimexino_stm32/blink/main.cpp @@ -19,7 +19,7 @@ int main() while (true) { Board::LedD3::toggle(); - modm::delayMilliseconds(200); + modm::delay(200ms); } return 0; } diff --git a/examples/stm32f030f4p6_demo_board/blink/main.cpp b/examples/stm32f030f4p6_demo_board/blink/main.cpp index 2ed57a160f..cce170aadc 100644 --- a/examples/stm32f030f4p6_demo_board/blink/main.cpp +++ b/examples/stm32f030f4p6_demo_board/blink/main.cpp @@ -27,10 +27,10 @@ main() while (true) { LedOrange::set(); - modm::delayMilliseconds(900); + modm::delay(900ms); LedOrange::reset(); - modm::delayMilliseconds(100); + modm::delay(100ms); } return 0; diff --git a/examples/stm32f072_discovery/blink/main.cpp b/examples/stm32f072_discovery/blink/main.cpp index b72d991ed9..6759121eb2 100644 --- a/examples/stm32f072_discovery/blink/main.cpp +++ b/examples/stm32f072_discovery/blink/main.cpp @@ -27,6 +27,6 @@ main() LedUp::toggle(); LedLeft::toggle(); LedDown::toggle(); - modm::delayMilliseconds(1000); + modm::delay(1000ms); } } diff --git a/examples/stm32f072_discovery/hard_fault/main.cpp b/examples/stm32f072_discovery/hard_fault/main.cpp index 58eb44af15..40916af434 100644 --- a/examples/stm32f072_discovery/hard_fault/main.cpp +++ b/examples/stm32f072_discovery/hard_fault/main.cpp @@ -82,7 +82,7 @@ main() while (true) { - modm::delayMilliseconds(1000); + modm::delay(1000ms); Board::LedUp::toggle(); } diff --git a/examples/stm32f072_discovery/uart/main.cpp b/examples/stm32f072_discovery/uart/main.cpp index ebcfd0c627..4e93cbac14 100644 --- a/examples/stm32f072_discovery/uart/main.cpp +++ b/examples/stm32f072_discovery/uart/main.cpp @@ -42,7 +42,7 @@ main() if (c > 'Z') { c = 'A'; } - modm::delayMilliseconds(500); + modm::delay(500ms); } return 0; diff --git a/examples/stm32f072_discovery/unaligned_access/main.cpp b/examples/stm32f072_discovery/unaligned_access/main.cpp index f92675ffa6..ffc3d20679 100644 --- a/examples/stm32f072_discovery/unaligned_access/main.cpp +++ b/examples/stm32f072_discovery/unaligned_access/main.cpp @@ -25,7 +25,7 @@ void error() while (true) { LedUp::toggle(); - modm::delayMilliseconds(100); + modm::delay(100ms); } } @@ -79,7 +79,7 @@ main() LedRight::toggle(); LedLeft::toggle(); - modm::delayMilliseconds(Button::read() ? 250 : 500); + modm::delay(Button::read() ? 250ms : 500ms); } return 0; diff --git a/examples/stm32f0_discovery/blink/main.cpp b/examples/stm32f0_discovery/blink/main.cpp index e567bd6557..227ebd3cf6 100644 --- a/examples/stm32f0_discovery/blink/main.cpp +++ b/examples/stm32f0_discovery/blink/main.cpp @@ -23,6 +23,6 @@ main() while (true) { LedGreen::toggle(); LedBlue::toggle(); - modm::delayMilliseconds(Board::Button::read() ? 500 : 1000); + modm::delay(Board::Button::read() ? 0.5s : 1s); } } diff --git a/examples/stm32f103c8t6_black_pill/blink/main.cpp b/examples/stm32f103c8t6_black_pill/blink/main.cpp index 82e620721a..ddedac3bb7 100644 --- a/examples/stm32f103c8t6_black_pill/blink/main.cpp +++ b/examples/stm32f103c8t6_black_pill/blink/main.cpp @@ -29,10 +29,10 @@ main() while (true) { LedGreen::set(); - modm::delayMilliseconds(900); + modm::delay(900ms); LedGreen::reset(); - modm::delayMilliseconds(100); + modm::delay(100ms); } return 0; diff --git a/examples/stm32f103c8t6_blue_pill/blink/main.cpp b/examples/stm32f103c8t6_blue_pill/blink/main.cpp index 82e620721a..ddedac3bb7 100644 --- a/examples/stm32f103c8t6_blue_pill/blink/main.cpp +++ b/examples/stm32f103c8t6_blue_pill/blink/main.cpp @@ -29,10 +29,10 @@ main() while (true) { LedGreen::set(); - modm::delayMilliseconds(900); + modm::delay(900ms); LedGreen::reset(); - modm::delayMilliseconds(100); + modm::delay(100ms); } return 0; diff --git a/examples/stm32f103c8t6_blue_pill/tlc594x/main.cpp b/examples/stm32f103c8t6_blue_pill/tlc594x/main.cpp index 26d48896d1..986453afaa 100644 --- a/examples/stm32f103c8t6_blue_pill/tlc594x/main.cpp +++ b/examples/stm32f103c8t6_blue_pill/tlc594x/main.cpp @@ -41,7 +41,7 @@ main() tlc594x.setChannel(i, 0xfff); RF_CALL_BLOCKING(tlc594x.writeChannels()); - modm::delayMilliseconds(500); + modm::delay(500ms); } } diff --git a/examples/stm32f1_discovery/blink/main.cpp b/examples/stm32f1_discovery/blink/main.cpp index 55d6e1cb5a..736e444999 100644 --- a/examples/stm32f1_discovery/blink/main.cpp +++ b/examples/stm32f1_discovery/blink/main.cpp @@ -23,10 +23,10 @@ main() while (true) { LedGreen::toggle(); - modm::delayMilliseconds(Button::read() ? 100 : 300); + modm::delay(Button::read() ? 100ms : 300ms); LedBlue::toggle(); - modm::delayMilliseconds(Button::read() ? 100 : 300); + modm::delay(Button::read() ? 100ms : 300ms); } return 0; diff --git a/examples/stm32f3_discovery/adc/continous/main.cpp b/examples/stm32f3_discovery/adc/continous/main.cpp index a255be2a68..5cbd5d2726 100644 --- a/examples/stm32f3_discovery/adc/continous/main.cpp +++ b/examples/stm32f3_discovery/adc/continous/main.cpp @@ -95,7 +95,7 @@ main() while (true) { - modm::delayMilliseconds(200); + modm::delay(200ms); printAdc(); } diff --git a/examples/stm32f3_discovery/adc/interrupt/main.cpp b/examples/stm32f3_discovery/adc/interrupt/main.cpp index 654ebd4738..021f9ec602 100644 --- a/examples/stm32f3_discovery/adc/interrupt/main.cpp +++ b/examples/stm32f3_discovery/adc/interrupt/main.cpp @@ -61,7 +61,7 @@ main() Adc4::startConversion(); while(!Adc4::isConversionFinished); printAdc(); - modm::delayMilliseconds(500); + modm::delay(500ms); } return 0; diff --git a/examples/stm32f3_discovery/adc/simple/main.cpp b/examples/stm32f3_discovery/adc/simple/main.cpp index 70294ab565..52f279f33c 100644 --- a/examples/stm32f3_discovery/adc/simple/main.cpp +++ b/examples/stm32f3_discovery/adc/simple/main.cpp @@ -50,7 +50,7 @@ main() MODM_LOG_INFO << "adcValue=" << adcValue; float voltage = adcValue * 3.3 / 0xfff; MODM_LOG_INFO << " voltage=" << voltage << modm::endl; - modm::delayMilliseconds(500); + modm::delay(500ms); } return 0; diff --git a/examples/stm32f3_discovery/blink/main.cpp b/examples/stm32f3_discovery/blink/main.cpp index dcf1c85b7d..12ac9b1080 100644 --- a/examples/stm32f3_discovery/blink/main.cpp +++ b/examples/stm32f3_discovery/blink/main.cpp @@ -25,21 +25,21 @@ main() while (true) { Board::LedNorth::toggle(); - modm::delayMilliseconds(100); + modm::delay(100ms); Board::LedNorthEast::toggle(); - modm::delayMilliseconds(100); + modm::delay(100ms); Board::LedEast::toggle(); - modm::delayMilliseconds(100); + modm::delay(100ms); Board::LedSouthEast::toggle(); - modm::delayMilliseconds(100); + modm::delay(100ms); Board::LedSouth::toggle(); - modm::delayMilliseconds(100); + modm::delay(100ms); Board::LedSouthWest::toggle(); - modm::delayMilliseconds(100); + modm::delay(100ms); Board::LedWest::toggle(); - modm::delayMilliseconds(100); + modm::delay(100ms); Board::LedNorthWest::toggle(); - modm::delayMilliseconds(100); + modm::delay(100ms); } return 0; diff --git a/examples/stm32f3_discovery/comp/main.cpp b/examples/stm32f3_discovery/comp/main.cpp index 401d8d9411..5695c45d91 100644 --- a/examples/stm32f3_discovery/comp/main.cpp +++ b/examples/stm32f3_discovery/comp/main.cpp @@ -59,7 +59,7 @@ main() while (true) { - modm::delayMilliseconds(250); + modm::delay(250ms); MODM_LOG_INFO << "Comparator: " << Comparator::getOutput() << modm::endl; Board::LedNorth::set(Comparator::getOutput()); } diff --git a/examples/stm32f3_discovery/timer/basic/main.cpp b/examples/stm32f3_discovery/timer/basic/main.cpp index c37fe53681..eb59e0b173 100644 --- a/examples/stm32f3_discovery/timer/basic/main.cpp +++ b/examples/stm32f3_discovery/timer/basic/main.cpp @@ -39,7 +39,7 @@ main() uint8_t i = 0; while (true){ Timer1::setCompareValue(1, ++i); - modm::delayMilliseconds(10); + modm::delay(10ms); } return 0; diff --git a/examples/stm32f401ccu_mini_f401/blink/main.cpp b/examples/stm32f401ccu_mini_f401/blink/main.cpp index 34fdb445b7..e45c8e0f41 100644 --- a/examples/stm32f401ccu_mini_f401/blink/main.cpp +++ b/examples/stm32f401ccu_mini_f401/blink/main.cpp @@ -30,7 +30,7 @@ main() while (true) { LedGreen::toggle(); - modm::delayMilliseconds(Button::read() ? 100 : 500); + modm::delay(Button::read() ? 100ms : 500ms); } return 0; diff --git a/examples/stm32f411ceu_mini_f411/blink/main.cpp b/examples/stm32f411ceu_mini_f411/blink/main.cpp index 34fdb445b7..e45c8e0f41 100644 --- a/examples/stm32f411ceu_mini_f411/blink/main.cpp +++ b/examples/stm32f411ceu_mini_f411/blink/main.cpp @@ -30,7 +30,7 @@ main() while (true) { LedGreen::toggle(); - modm::delayMilliseconds(Button::read() ? 100 : 500); + modm::delay(Button::read() ? 100ms : 500ms); } return 0; diff --git a/examples/stm32f429_discovery/blink/main.cpp b/examples/stm32f429_discovery/blink/main.cpp index 961a36d23d..c7a2e67843 100644 --- a/examples/stm32f429_discovery/blink/main.cpp +++ b/examples/stm32f429_discovery/blink/main.cpp @@ -28,12 +28,12 @@ main() LedRed::toggle(); LedGreen::toggle(); - modm::delayMilliseconds(Button::read() ? 125 : 500); + modm::delay(Button::read() ? 125ms : 500ms); usb::VBus::toggle(); usb::Overcurrent::toggle(); - modm::delayMilliseconds(Button::read() ? 125 : 500); + modm::delay(Button::read() ? 125ms : 500ms); } return 0; diff --git a/examples/stm32f469_discovery/display/main.cpp b/examples/stm32f469_discovery/display/main.cpp index 377ef73087..d96ec1f57a 100644 --- a/examples/stm32f469_discovery/display/main.cpp +++ b/examples/stm32f469_discovery/display/main.cpp @@ -35,7 +35,7 @@ main() while (true) { - modm::delayMilliseconds(50); + modm::delay(50ms); if (Button::read()) { display.clear(); diff --git a/examples/stm32f469_discovery/exceptions_rtti/main.cpp b/examples/stm32f469_discovery/exceptions_rtti/main.cpp index 9d6802f12b..4365900d13 100644 --- a/examples/stm32f469_discovery/exceptions_rtti/main.cpp +++ b/examples/stm32f469_discovery/exceptions_rtti/main.cpp @@ -27,7 +27,7 @@ main() while (true) { LedBlue::toggle(); - modm::delayMilliseconds(500); + modm::delay(500ms); try { throw counter++; diff --git a/examples/stm32f469_discovery/game_of_life/main.cpp b/examples/stm32f469_discovery/game_of_life/main.cpp index 9872493be2..9ade44c72a 100644 --- a/examples/stm32f469_discovery/game_of_life/main.cpp +++ b/examples/stm32f469_discovery/game_of_life/main.cpp @@ -11,6 +11,7 @@ #include #include #include +#include using namespace Board; using namespace modm::glcd; @@ -293,7 +294,7 @@ void game_of_life() init(framebuffers); evolve(framebuffers[0], framebuffers[1]); while(Button::read()) - modm::delayMilliseconds(10); + modm::delay(10ms); reseed.restart(); } // read touch sensor during frame rate delay diff --git a/examples/stm32f469_discovery/hard_fault/main.cpp b/examples/stm32f469_discovery/hard_fault/main.cpp index 61380a29a5..e3e6b38641 100644 --- a/examples/stm32f469_discovery/hard_fault/main.cpp +++ b/examples/stm32f469_discovery/hard_fault/main.cpp @@ -37,7 +37,7 @@ void modm_hardfault_entry() // Put hardware in safe mode here Board::Leds::set(); // But do not wait forever - modm::delayMilliseconds(100); + modm::delay(100ms); // Do not depend on interrupts in this function (buffered UART etc!) } @@ -82,7 +82,7 @@ main() function2(23, 43); - modm::delayMilliseconds(250); + modm::delay(250ms); } return 0; diff --git a/examples/stm32f469_discovery/ports/main.cpp b/examples/stm32f469_discovery/ports/main.cpp index d23f74a591..c0acdde3c8 100644 --- a/examples/stm32f469_discovery/ports/main.cpp +++ b/examples/stm32f469_discovery/ports/main.cpp @@ -81,10 +81,10 @@ main() PinGroup4::setInput(); MODM_LOG_INFO << modm::bin << PinGroup4::read() << modm::endl; MODM_LOG_INFO << modm::endl; - PinGroup::setOutput(modm::Gpio::High); modm::delayMilliseconds(1000); + PinGroup::setOutput(modm::Gpio::High); modm::delay(1s); const auto fn_report = []() { - MODM_LOG_INFO << modm::bin << PinGroup::read() << modm::endl; modm::delayMilliseconds(200); + MODM_LOG_INFO << modm::bin << PinGroup::read() << modm::endl; modm::delay(200ms); }; while (true) diff --git a/examples/stm32f469_discovery/threadsafe_statics/main.cpp b/examples/stm32f469_discovery/threadsafe_statics/main.cpp index 3e0b4dd2a2..17edda4a5b 100644 --- a/examples/stm32f469_discovery/threadsafe_statics/main.cpp +++ b/examples/stm32f469_discovery/threadsafe_statics/main.cpp @@ -38,7 +38,7 @@ main() while (true) { Board::LedGreen::toggle(); - modm::delayMilliseconds(Board::Button::read() ? 125 : 500); + modm::delay(Board::Button::read() ? 125ms : 500ms); MODM_LOG_INFO << "loop: " << counter++ << modm::endl; constructDummy(); diff --git a/examples/stm32f469_discovery/tlsf-allocator/main.cpp b/examples/stm32f469_discovery/tlsf-allocator/main.cpp index 83361bac48..9f06ba1f31 100644 --- a/examples/stm32f469_discovery/tlsf-allocator/main.cpp +++ b/examples/stm32f469_discovery/tlsf-allocator/main.cpp @@ -57,7 +57,7 @@ int main() while (true) { Board::Leds::toggle(); - modm::delayMilliseconds(500); + modm::delay(500ms); } return 0; } diff --git a/examples/stm32f4_discovery/adc/interrupt/main.cpp b/examples/stm32f4_discovery/adc/interrupt/main.cpp index 10c9dc680f..b63d72db7c 100644 --- a/examples/stm32f4_discovery/adc/interrupt/main.cpp +++ b/examples/stm32f4_discovery/adc/interrupt/main.cpp @@ -61,7 +61,7 @@ main() { Adc2::startConversion(); - modm::delayMilliseconds(500); + modm::delay(500ms); } return 0; diff --git a/examples/stm32f4_discovery/adc/simple/main.cpp b/examples/stm32f4_discovery/adc/simple/main.cpp index f31f6e05a5..42c7d92c0a 100644 --- a/examples/stm32f4_discovery/adc/simple/main.cpp +++ b/examples/stm32f4_discovery/adc/simple/main.cpp @@ -49,7 +49,7 @@ main() MODM_LOG_INFO << "adcValue=" << adcValue; float voltage = adcValue * 3.3 / 0xfff; MODM_LOG_INFO << " voltage=" << voltage << modm::endl; - modm::delayMilliseconds(500); + modm::delay(500ms); } return 0; diff --git a/examples/stm32f4_discovery/app_uart_sniffer/main.cpp b/examples/stm32f4_discovery/app_uart_sniffer/main.cpp index 62298d80db..036959a5bb 100644 --- a/examples/stm32f4_discovery/app_uart_sniffer/main.cpp +++ b/examples/stm32f4_discovery/app_uart_sniffer/main.cpp @@ -116,7 +116,7 @@ main() Board::LedGreen::toggle(); } - modm::delayMicroseconds(100); + modm::delay(100us); } return 0; diff --git a/examples/stm32f4_discovery/blink/main.cpp b/examples/stm32f4_discovery/blink/main.cpp index f4050ac281..c25042e47e 100644 --- a/examples/stm32f4_discovery/blink/main.cpp +++ b/examples/stm32f4_discovery/blink/main.cpp @@ -32,7 +32,7 @@ main() LedGreen::toggle(); LedOrange::toggle(); LedRed::toggle(); - modm::delayMilliseconds(Button::read() ? 250 : 500); + modm::delay(Button::read() ? 250ms : 500ms); } return 0; diff --git a/examples/stm32f4_discovery/exti/main.cpp b/examples/stm32f4_discovery/exti/main.cpp index 988ff29c96..bbe899dfaf 100644 --- a/examples/stm32f4_discovery/exti/main.cpp +++ b/examples/stm32f4_discovery/exti/main.cpp @@ -44,7 +44,7 @@ MODM_ISR(EXTI0) { Button::acknowledgeExternalInterruptFlag(); LedBlue::set(); - modm::delayMicroseconds(1000); + modm::delay(1ms); LedBlue::reset(); } @@ -53,7 +53,7 @@ MODM_ISR(EXTI15_10) { Irq::acknowledgeExternalInterruptFlag(); LedOrange::set(); - modm::delayMicroseconds(1000); + modm::delay(1ms); LedOrange::reset(); } @@ -87,7 +87,7 @@ main() { LedRed::toggle(); LedGreen::toggle(); - modm::delayMilliseconds(500); + modm::delay(500ms); } return 0; diff --git a/examples/stm32f4_discovery/fsmc/main.cpp b/examples/stm32f4_discovery/fsmc/main.cpp index 7d3e3bb354..ed129b31ec 100644 --- a/examples/stm32f4_discovery/fsmc/main.cpp +++ b/examples/stm32f4_discovery/fsmc/main.cpp @@ -85,7 +85,7 @@ main() ++ii; Board::LedOrange::toggle(); Board::LedGreen::toggle(); - modm::delayMilliseconds(data[ii]); + modm::delay_ms(data[ii]); } return 0; diff --git a/examples/stm32f4_discovery/open407v-d/gui/main.cpp b/examples/stm32f4_discovery/open407v-d/gui/main.cpp index ad641c65fa..7ade2fade2 100644 --- a/examples/stm32f4_discovery/open407v-d/gui/main.cpp +++ b/examples/stm32f4_discovery/open407v-d/gui/main.cpp @@ -211,7 +211,7 @@ calibrateTouchscreen(modm::GraphicDisplay& display, modm::glcd::Point *fixed_sam display << "Touch crosshair to calibrate"; drawCross(display, calibrationPoint[i]); - modm::delayMilliseconds(500); + modm::delay(500ms); while (!ads7843.read(&sample[i])) { // wait until a valid sample can be taken @@ -267,7 +267,7 @@ touchActive() bool m1, m2; m1 = !IntTouchscreen::read(); - modm::delayMicroseconds(130); + modm::delay(130us); m2 = !IntTouchscreen::read(); return (m1 || m2); diff --git a/examples/stm32f4_discovery/open407v-d/touchscreen/main.cpp b/examples/stm32f4_discovery/open407v-d/touchscreen/main.cpp index 0e6788fe35..5a804b30fc 100644 --- a/examples/stm32f4_discovery/open407v-d/touchscreen/main.cpp +++ b/examples/stm32f4_discovery/open407v-d/touchscreen/main.cpp @@ -167,7 +167,7 @@ calibrateTouchscreen(modm::GraphicDisplay& display) display << "Touch crosshair to calibrate"; drawCross(display, calibrationPoint[i]); - modm::delayMilliseconds(500); + modm::delay(500ms); while (!ads7843.read(&sample[i])) { // wait until a valid sample can be taken diff --git a/examples/stm32f4_discovery/sab2/main.cpp b/examples/stm32f4_discovery/sab2/main.cpp index ec5a8dd45b..e20da6e3a1 100644 --- a/examples/stm32f4_discovery/sab2/main.cpp +++ b/examples/stm32f4_discovery/sab2/main.cpp @@ -58,7 +58,7 @@ main() } Board::LedGreen::toggle(); - modm::delayMilliseconds(100); + modm::delay(100ms); } return 0; diff --git a/examples/stm32f4_discovery/timer_test/main.cpp b/examples/stm32f4_discovery/timer_test/main.cpp index ffec05a7ff..3190888651 100644 --- a/examples/stm32f4_discovery/timer_test/main.cpp +++ b/examples/stm32f4_discovery/timer_test/main.cpp @@ -96,9 +96,9 @@ main() while (true) { LedBlue::set(); - modm::delayMilliseconds(20); + modm::delay(20ms); LedBlue::reset(); - modm::delayMilliseconds(150); + modm::delay(150ms); if (restart) { restart = false; diff --git a/examples/stm32f4_discovery/uart/main.cpp b/examples/stm32f4_discovery/uart/main.cpp index f42be20a63..8a980bcfad 100644 --- a/examples/stm32f4_discovery/uart/main.cpp +++ b/examples/stm32f4_discovery/uart/main.cpp @@ -42,7 +42,7 @@ main() if (c > 'Z') { c = 'A'; } - modm::delayMilliseconds(500); + modm::delay(500ms); } return 0; diff --git a/examples/stm32f746g_discovery/blink/main.cpp b/examples/stm32f746g_discovery/blink/main.cpp index 08fc7c651e..8fabb14c2d 100644 --- a/examples/stm32f746g_discovery/blink/main.cpp +++ b/examples/stm32f746g_discovery/blink/main.cpp @@ -32,7 +32,7 @@ main() while (true) { - modm::delayMilliseconds(Button::read() ? 250 : 1000); + modm::delay(Button::read() ? 250ms : 1s); LedD13::toggle(); MODM_LOG_INFO << "loop: " << counter++ << modm::endl; diff --git a/examples/stm32f769i_discovery/blink/main.cpp b/examples/stm32f769i_discovery/blink/main.cpp index 5f16f75ce7..ef7887409d 100644 --- a/examples/stm32f769i_discovery/blink/main.cpp +++ b/examples/stm32f769i_discovery/blink/main.cpp @@ -36,7 +36,7 @@ main() while (true) { - modm::delayMilliseconds(Button::read() ? 250 : 1000); + modm::delay(Button::read() ? 250ms : 1s); LedJ13::toggle(); LedJ5::toggle(); LedA12::toggle(); diff --git a/examples/stm32l1_discovery/blink/main.cpp b/examples/stm32l1_discovery/blink/main.cpp index 56380d3279..7d02b7e109 100644 --- a/examples/stm32l1_discovery/blink/main.cpp +++ b/examples/stm32l1_discovery/blink/main.cpp @@ -23,7 +23,7 @@ main() while (true) { Leds::write(1ul << (counter++ % Leds::width)); - modm::delayMilliseconds(Button::read() ? 500 : 1000); + modm::delay(Button::read() ? 500ms : 1s); } return 0; diff --git a/examples/stm32l476_discovery/blink/main.cpp b/examples/stm32l476_discovery/blink/main.cpp index 85d8894597..796f0b1378 100644 --- a/examples/stm32l476_discovery/blink/main.cpp +++ b/examples/stm32l476_discovery/blink/main.cpp @@ -24,7 +24,7 @@ main() { LedGreen::toggle(); LedRed::toggle(); - modm::delayMilliseconds(Button::read() ? 250 : 500); + modm::delay(Button::read() ? 250ms : 500ms); } return 0; diff --git a/examples/zmq/1_stm32/main.cpp b/examples/zmq/1_stm32/main.cpp index 35eba8503f..ec5fde0089 100644 --- a/examples/zmq/1_stm32/main.cpp +++ b/examples/zmq/1_stm32/main.cpp @@ -112,7 +112,7 @@ main() LedOrange::toggle(); } - modm::delayMicroseconds(100); + modm::delay(100us); } return 0; diff --git a/examples/zmq/2_zmq_gateway/main.cpp b/examples/zmq/2_zmq_gateway/main.cpp index 4c6eda905d..0dd9610bad 100644 --- a/examples/zmq/2_zmq_gateway/main.cpp +++ b/examples/zmq/2_zmq_gateway/main.cpp @@ -22,6 +22,7 @@ #include #include using namespace modm::literals; +using namespace std::chrono_literals; /** * Listens to a CAN bus connected by a CAN2USB and publishes modm messages with zeromq. @@ -105,7 +106,7 @@ main() zmqConnector.dropPacket(); } - modm::delayMilliseconds(10); + modm::delay(10ms); } canUsb.close(); diff --git a/examples/zmq/3_zmq_app/main.cpp b/examples/zmq/3_zmq_app/main.cpp index 371431d3e3..edc6a91e0d 100644 --- a/examples/zmq/3_zmq_app/main.cpp +++ b/examples/zmq/3_zmq_app/main.cpp @@ -19,6 +19,7 @@ #include #include +using namespace std::chrono_literals; /** * Simple subscriber with zeromq. @@ -52,6 +53,6 @@ main() dispatcher.update(); component::gui.update(); - modm::delayMilliseconds(25); + modm::delay(25ms); } } diff --git a/examples/zmq/4_zmq_backtoback/main.cpp b/examples/zmq/4_zmq_backtoback/main.cpp index a906db2b94..7790b45c08 100644 --- a/examples/zmq/4_zmq_backtoback/main.cpp +++ b/examples/zmq/4_zmq_backtoback/main.cpp @@ -15,6 +15,7 @@ #include #include +using namespace std::chrono_literals; modm::PeriodicTimer pt(2000); @@ -70,6 +71,6 @@ main() zmqConnectorServer.sendPacket(header, payload); } - modm::delayMilliseconds(100); + modm::delay(100ms); } } diff --git a/src/modm/architecture/interface/gpio.md b/src/modm/architecture/interface/gpio.md index b0f7bd68ef..50693521eb 100644 --- a/src/modm/architecture/interface/gpio.md +++ b/src/modm/architecture/interface/gpio.md @@ -27,7 +27,7 @@ Led::set(); while (true) { Led::toggle(); - modm::delayMilliseconds(500); + modm::delay(500ms); } ``` diff --git a/src/modm/architecture/interface/i2c.hpp b/src/modm/architecture/interface/i2c.hpp index 8e0cd3000f..6af7490210 100644 --- a/src/modm/architecture/interface/i2c.hpp +++ b/src/modm/architecture/interface/i2c.hpp @@ -116,14 +116,14 @@ struct I2c static void resetDevices() { - static_assert(baudrate <= 500'000, "I2c::resetDevices() can only do max. 500kHz!"); - constexpr uint32_t delay = 500'000 / baudrate; + static_assert(baudrate <= 500'000ul, "I2c::resetDevices() can only do max. 500kHz!"); + constexpr auto delay = 500'000ul / baudrate; for (uint_fast8_t ii = 0; ii < 9; ++ii) { Scl::reset(); - modm::delayMicroseconds(delay); + modm::delay_us(delay); Scl::set(); - modm::delayMicroseconds(delay); + modm::delay_us(delay); } } diff --git a/src/modm/board/board.cpp.in b/src/modm/board/board.cpp.in index e457d71b40..f7150b4c82 100644 --- a/src/modm/board/board.cpp.in +++ b/src/modm/board/board.cpp.in @@ -10,6 +10,7 @@ // ---------------------------------------------------------------------------- #include "board.hpp" +#include %% if with_assert #include %% endif @@ -47,9 +48,9 @@ modm_abandon(const modm::AssertionInfo &info) for(int times=10; times>=0; times--) { Board::Leds::write(1); - modm::delayMilliseconds(20); + modm::delay_ms(20); Board::Leds::write(0); - modm::delayMilliseconds(180); + modm::delay_ms(180); } %% if with_logger // Do not flush here otherwise you may deadlock due to waiting on the UART diff --git a/src/modm/board/board.hpp b/src/modm/board/board.hpp index 70c3037512..69892af84b 100644 --- a/src/modm/board/board.hpp +++ b/src/modm/board/board.hpp @@ -13,6 +13,7 @@ #ifndef MODM_BOARD_DO_NOT_USE_LITERALS using namespace modm::literals; +using namespace std::chrono_literals; #endif namespace Board { diff --git a/src/modm/board/disco_f469ni/board_dsi.cpp b/src/modm/board/disco_f469ni/board_dsi.cpp index 07c9035c63..cd00bddb6e 100644 --- a/src/modm/board/disco_f469ni/board_dsi.cpp +++ b/src/modm/board/disco_f469ni/board_dsi.cpp @@ -31,13 +31,13 @@ board_initialize_display(uint8_t ColorCoding) DSI->WRPCR = DSI_WRPCR_REGEN; // Wait until stable for (int t = 1'024; not (DSI->WISR & DSI_WISR_RRS) and t; t--) { - modm::delayMilliseconds(1); + modm::delay_ms(1); } // Set up PLL and enable it DSI->WRPCR |= (0 << 16) | (2 << 11) | (125 << 2) | DSI_WRPCR_PLLEN; // Wait until stable for (int t = 1'024; not (DSI->WISR & DSI_WISR_PLLLS) and t; t--) { - modm::delayMilliseconds(1); + modm::delay_ms(1); } // D-PHY clock and digital enable DSI->PCTLR = DSI_PCTLR_CKE | DSI_PCTLR_DEN; @@ -131,7 +131,7 @@ board_initialize_display(uint8_t ColorCoding) // Enable PLLSAI RCC->CR |= RCC_CR_PLLSAION; for (int t = 1'024; not (RCC->CR & RCC_CR_PLLSAIRDY) and t; t--) { - modm::delayMilliseconds(1); + modm::delay_ms(1); } } diff --git a/src/modm/board/disco_f469ni/board_init.cpp b/src/modm/board/disco_f469ni/board_init.cpp index 3c4318ba9f..362d0facf2 100644 --- a/src/modm/board/disco_f469ni/board_init.cpp +++ b/src/modm/board/disco_f469ni/board_init.cpp @@ -19,9 +19,9 @@ modm_board_init(void) { // Reset LCD Board::DisplayReset::setOutput(modm::Gpio::Low); - modm::delayMilliseconds(20); + modm::delay_ms(20); Board::DisplayReset::set(); - modm::delayMilliseconds(10); + modm::delay_ms(10); // initialize system clock and external SDRAM before accessing external memories Board::SystemClock::enable(); diff --git a/src/modm/board/disco_f469ni/board_otm8009a.cpp b/src/modm/board/disco_f469ni/board_otm8009a.cpp index 57831d7f18..dac6343d76 100644 --- a/src/modm/board/disco_f469ni/board_otm8009a.cpp +++ b/src/modm/board/disco_f469ni/board_otm8009a.cpp @@ -15,7 +15,7 @@ static void dsi_write_command(uint32_t count, uint8_t const * const p) { /* Wait for Command FIFO Empty */ for (int t = 1'024; not (DSI->GPSR & DSI_GPSR_CMDFE) and t; t--) { - modm::delayMilliseconds(1); + modm::delay_ms(1); } if(count <= 1) @@ -31,7 +31,7 @@ static void dsi_write_command(uint32_t count, uint8_t const * const p) uint16_t counter = 3; for (int t = 1'024; not (DSI->GPSR & DSI_GPSR_CMDFE) and t; t--) { - modm::delayMilliseconds(1); + modm::delay_ms(1); } while(counter < count) @@ -43,7 +43,7 @@ static void dsi_write_command(uint32_t count, uint8_t const * const p) counter += 4; for (int t = 1'024; not (DSI->GPSR & DSI_GPSR_CMDFE) and t; t--) { - modm::delayMilliseconds(1); + modm::delay_ms(1); } } @@ -245,11 +245,11 @@ void otm8009a_init(uint8_t ColorCoding) /* -> Source output level during porch and non-display area to GND */ dsi_write_command(0, ShortRegData2); dsi_write_command(0, ShortRegData3); - modm::delayMilliseconds(10); + modm::delay_ms(10); /* Not documented */ dsi_write_command(0, ShortRegData4); dsi_write_command(0, ShortRegData5); - modm::delayMilliseconds(10); + modm::delay_ms(10); ///////////////////////////////////////////////////////////////////// /* PWR_CTRL4 - 0xC4B0h - 178th parameter - Default 0xA8 */ @@ -414,7 +414,7 @@ void otm8009a_init(uint8_t ColorCoding) dsi_write_command(0, ShortRegData36); /* Wait for sleep out exit */ - modm::delayMilliseconds(120); + modm::delay_ms(120); if (ColorCoding == 0) { dsi_write_command(0, ShortRegData38); diff --git a/src/modm/board/disco_f469ni/board_sdram.cpp b/src/modm/board/disco_f469ni/board_sdram.cpp index db4f9cec46..a05a23bf3a 100644 --- a/src/modm/board/disco_f469ni/board_sdram.cpp +++ b/src/modm/board/disco_f469ni/board_sdram.cpp @@ -69,7 +69,7 @@ sdram_send_command(uint8_t mode, uint8_t auto_refresh = 1, uint16_t mode_registe int t = 1024; for (; (FMC_Bank5_6->SDSR & FMC_SDSR_BUSY) and t; t--) { - modm::delayMilliseconds(1); + modm::delay_ms(1); } return t; @@ -129,7 +129,7 @@ board_initialize_sdram() // FMC_SDRAM_CMD_CLK_ENABLE sdram_send_command(1); - modm::delayMilliseconds(1); + modm::delay_ms(1); // FMC_SDRAM_CMD_PALL sdram_send_command(2); // FMC_SDRAM_CMD_AUTOREFRESH_MODE diff --git a/src/modm/board/disco_l152rc/board.hpp b/src/modm/board/disco_l152rc/board.hpp index 985bc811f4..a4a8850033 100644 --- a/src/modm/board/disco_l152rc/board.hpp +++ b/src/modm/board/disco_l152rc/board.hpp @@ -79,7 +79,7 @@ struct SystemClock Rcc::setFlashLatency<4.1_MHz>(); Rcc::updateCoreFrequency<4.1_MHz>(); Rcc::enableMultiSpeedInternalClock(Rcc::MsiFrequency::MHz4); - modm::delayMicroseconds(5); + modm::delay_us(5); Rcc::enableInternalClock(); // 16MHz // set flash latency @@ -87,7 +87,7 @@ struct SystemClock // switch system clock to HSE output Rcc::enableSystemClock(Rcc::SystemClockSource::Hsi); Rcc::updateCoreFrequency<16_MHz>(); - modm::delayMicroseconds(5); + modm::delay_us(5); // internal clock 16MHz * 4 / 2 = 32MHz => bad for USB const Rcc::PllFactors pllFactors{ diff --git a/src/modm/board/nucleo_l152re/board.hpp b/src/modm/board/nucleo_l152re/board.hpp index efe5d2b178..e5a230972e 100644 --- a/src/modm/board/nucleo_l152re/board.hpp +++ b/src/modm/board/nucleo_l152re/board.hpp @@ -94,7 +94,7 @@ struct SystemClock Rcc::enablePll(Rcc::PllSource::ExternalClock, pllFactors); // set flash latency Rcc::setFlashLatency(); - modm::delayMicroseconds(5); + modm::delay_us(5); // switch system clock to PLL output Rcc::enableSystemClock(Rcc::SystemClockSource::Pll); // update frequencies for busy-wait delay functions diff --git a/src/modm/driver/adc/ad7280a_impl.hpp b/src/modm/driver/adc/ad7280a_impl.hpp index 8a9cc843fa..b5ddc0f834 100644 --- a/src/modm/driver/adc/ad7280a_impl.hpp +++ b/src/modm/driver/adc/ad7280a_impl.hpp @@ -229,7 +229,7 @@ modm::Ad7280a::performSelftest() // Allow sufficient time for the self-test conversions to be // completed plus tWAIT. - modm::delayMilliseconds(50); // TODO + modm::delay_ms(50); // TODO // The register address corresponding to the self-test // conversion should be written to the read register of all @@ -290,7 +290,7 @@ modm::Ad7280a::readChannel(uint8_t device, AD7280A_CTRL_HB_CONV_START_CS); // Wait for the conversion to finish - modm::delayMilliseconds(5); + modm::delay_ms(5); // Read one channel write(device, ad7280a::READ, false, channel); @@ -323,7 +323,7 @@ modm::Ad7280a::readAllChannels(uint16_t *values) AD7280A_CTRL_HB_CONV_START_CS); // Allow sufficient time for all conversions to be completed plus tWAIT. - modm::delayMilliseconds(5); + modm::delay_ms(5); // Apply a CS low pulse that frames 32 SCLKs to read back // the desired voltage. This frame should simultaneously @@ -401,7 +401,7 @@ modm::Ad7280a::write(uint8_t device, ad7280a::Register reg, Cs::set(); // TODO remove this - modm::delayMicroseconds(1); + modm::delay_us(1); return true; } diff --git a/src/modm/driver/adc/ad7928_impl.hpp b/src/modm/driver/adc/ad7928_impl.hpp index e00b53b876..d4fe3651d2 100644 --- a/src/modm/driver/adc/ad7928_impl.hpp +++ b/src/modm/driver/adc/ad7928_impl.hpp @@ -37,7 +37,7 @@ Ad7928::initialize() RF_BEGIN(); Cs::setOutput(modm::Gpio::High); - delayMicroseconds(1); + modm::delay_us(1); // reset device RF_CALL(transfer(Register_t(0xFF))); @@ -201,7 +201,7 @@ Ad7928::wakeup() RF_CALL(transfer(config)); // Wait for the device to power up - delayMicroseconds(1); + modm::delay_us(1); currentPowerMode = PowerMode::Normal; diff --git a/src/modm/driver/adc/hx711_impl.hpp b/src/modm/driver/adc/hx711_impl.hpp index 45e12305bb..cf837ac6cd 100644 --- a/src/modm/driver/adc/hx711_impl.hpp +++ b/src/modm/driver/adc/hx711_impl.hpp @@ -24,25 +24,25 @@ Hx711::singleConversion() RF_WAIT_UNTIL(Data::read() == modm::Gpio::Low); - modm::delayMicroseconds(1); + modm::delay_us(1); data = 0; for (uint8_t ii = 0; ii < 24; ++ii) { Sck::set(); - modm::delayMicroseconds(1); + modm::delay_us(1); data = (data << 1) | Data::read(); - modm::delayMicroseconds(1); + modm::delay_us(1); Sck::reset(); - modm::delayMicroseconds(1); + modm::delay_us(1); } // Additional pulses for mode of next conversion for (uint8_t ii = 0; ii < static_cast(Cfg::mode); ++ii) { Sck::set(); - modm::delayMicroseconds(1); + modm::delay_us(1); Sck::reset(); - modm::delayMicroseconds(1); + modm::delay_us(1); } // Fill up MSBs for negative numbers diff --git a/src/modm/driver/bus/bitbang_memory_interface_impl.hpp b/src/modm/driver/bus/bitbang_memory_interface_impl.hpp index aafc112de2..cfa3cc859e 100644 --- a/src/modm/driver/bus/bitbang_memory_interface_impl.hpp +++ b/src/modm/driver/bus/bitbang_memory_interface_impl.hpp @@ -47,17 +47,17 @@ void modm::BitbangMemoryInterface::writeRegister(uint8_t reg) WR::reset(); PORT::write(0); - modm::delayMicroseconds(1); + modm::delay_us(1); WR::set(); // Low-to-High strobe - modm::delayMicroseconds(1); + modm::delay_us(1); WR::reset(); PORT::write(reg); - modm::delayMicroseconds(1); + modm::delay_us(1); WR::set(); // Low-to-High strobe - modm::delayMicroseconds(1); + modm::delay_us(1); CS::set(); @@ -73,17 +73,17 @@ void modm::BitbangMemoryInterface::writeData(const uint16_t da WR::reset(); PORT::write(data >> 8); - modm::delayMicroseconds(1); + modm::delay_us(1); WR::set(); // Low-to-High strobe - modm::delayMicroseconds(1); + modm::delay_us(1); WR::reset(); PORT::write(data); - modm::delayMicroseconds(1); + modm::delay_us(1); WR::set(); // Low-to-High strobe - modm::delayMicroseconds(1); + modm::delay_us(1); CS::set(); } @@ -99,15 +99,15 @@ void modm::BitbangMemoryInterface::writeDataMult(const uint16_ { WR::reset(); PORT::write(data >> 8); - modm::delayMicroseconds(1); + modm::delay_us(1); WR::set(); // Low-to-High strobe WR::reset(); PORT::write(data); - modm::delayMicroseconds(1); + modm::delay_us(1); WR::set(); // Low-to-High strobe - modm::delayMicroseconds(1); + modm::delay_us(1); } @@ -134,9 +134,9 @@ void modm::BitbangMemoryInterface::writeRam(uint8_t * addr, co WR::reset(); PORT::write( *(addr++) ); - modm::delayMicroseconds(1); + modm::delay_us(1); WR::set(); // Low-to-high strobe - modm::delayMicroseconds(1); + modm::delay_us(1); } CS::set(); diff --git a/src/modm/driver/bus/tft_memory_bus.hpp b/src/modm/driver/bus/tft_memory_bus.hpp index 2992a290b3..7536bd0e1d 100644 --- a/src/modm/driver/bus/tft_memory_bus.hpp +++ b/src/modm/driver/bus/tft_memory_bus.hpp @@ -153,13 +153,13 @@ class MemoryBus PORT::write(data); // t_AS - modm::delayMicroseconds(1); + modm::delay_us(1); WR::reset(); - modm::delayMicroseconds(1); + modm::delay_us(1); WR::set(); - modm::delayMicroseconds(1); + modm::delay_us(1); PORT::setInput(); CS::set(); @@ -172,11 +172,11 @@ class MemoryBus CS::reset(); WR::set(); - modm::delayMicroseconds(1); + modm::delay_us(1); RD::reset(); - modm::delayMicroseconds(1); + modm::delay_us(1); ret = PORT::read(); RD::set(); diff --git a/src/modm/driver/can/mcp2515_impl.hpp b/src/modm/driver/can/mcp2515_impl.hpp index ff41dd77b4..9b705897b5 100644 --- a/src/modm/driver/can/mcp2515_impl.hpp +++ b/src/modm/driver/can/mcp2515_impl.hpp @@ -71,11 +71,11 @@ modm::Mcp2515::initializeWithPrescaler( // configuration mode chipSelect.reset(); spi.transferBlocking(RESET); - modm::delayMilliseconds(1); + modm::delay_ms(1); chipSelect.set(); // wait a bit to give the MCP2515 some time to restart - modm::delayMilliseconds(30); + modm::delay_ms(30); chipSelect.reset(); spi.transferBlocking(WRITE); @@ -295,7 +295,7 @@ modm::Mcp2515::sendMessage(const can::Message& message) } chipSelect.set(); - modm::delayMicroseconds(1); + modm::delay_us(1); // send message via RTS command chipSelect.reset(); diff --git a/src/modm/driver/dac/mcp4922_impl.hpp b/src/modm/driver/dac/mcp4922_impl.hpp index e50fa4e71a..cf6ec032d1 100644 --- a/src/modm/driver/dac/mcp4922_impl.hpp +++ b/src/modm/driver/dac/mcp4922_impl.hpp @@ -58,9 +58,9 @@ template void modm::Mcp4922::update() { - modm::delayMicroseconds(1); // 40 nanoseconds + modm::delay_us(1); // 40 nanoseconds Ldac::reset(); - modm::delayMicroseconds(1); // 100 nanoseconds + modm::delay_us(1); // 100 nanoseconds Ldac::set(); } diff --git a/src/modm/driver/display/hd44780_base_impl.hpp b/src/modm/driver/display/hd44780_base_impl.hpp index dc9ea428f3..23958448bf 100644 --- a/src/modm/driver/display/hd44780_base_impl.hpp +++ b/src/modm/driver/display/hd44780_base_impl.hpp @@ -29,15 +29,16 @@ modm::Hd44780Base::initialize(LineMode lineMode) Bus::writeHighNibble(Set8BitBus); - modm::delayMilliseconds(5); + modm::delay_ms(5); Bus::writeHighNibble(Set8BitBus); - modm::delayMicroseconds(100); + modm::delay_us(100); Bus::writeHighNibble(Set8BitBus); - if (DATA::width == 4) { + if constexpr (DATA::width == 4) + { while(isBusy()) ; RW::set(RW_Write); @@ -163,7 +164,7 @@ modm::Hd44780Base::isBusy() if (read() & BusyFlagMask) { - modm::delayMicroseconds(2); + modm::delay_us(2); return true; } return false; @@ -192,16 +193,16 @@ modm::Hd44780Base::Bus::write(uint8_t data) DATA::write(data >> 4); E::set(); - modm::delayMicroseconds(1); + modm::delay_us(1); E::reset(); - modm::delayNanoseconds(10); + modm::delay_ns(10); DATA::write(data); E::set(); - modm::delayMicroseconds(1); + modm::delay_us(1); E::reset(); - modm::delayNanoseconds(10); + modm::delay_ns(10); } template @@ -221,18 +222,18 @@ modm::Hd44780Base::Bus::read() DATA::setInput(); E::set(); - modm::delayMicroseconds(1); + modm::delay_us(1); data = DATA::read(); E::reset(); - modm::delayNanoseconds(10); + modm::delay_ns(10); data <<= 4; E::set(); - modm::delayMicroseconds(1); + modm::delay_us(1); data |= DATA::read(); E::reset(); - modm::delayNanoseconds(10); + modm::delay_ns(10); return data; } @@ -247,9 +248,9 @@ modm::Hd44780Base::Bus::write(uint8_t data) DATA::write(data); E::set(); - modm::delayMicroseconds(1); + modm::delay_us(1); E::reset(); - modm::delayNanoseconds(500); + modm::delay_ns(500); } template @@ -269,10 +270,10 @@ modm::Hd44780Base::Bus::read() DATA::setInput(); E::set(); - modm::delayMicroseconds(1); + modm::delay_us(1); data = DATA::read(); E::reset(); - modm::delayNanoseconds(500); + modm::delay_ns(500); return data; } diff --git a/src/modm/driver/display/ks0108.hpp b/src/modm/driver/display/ks0108.hpp index 4a263075f1..c43f74440d 100644 --- a/src/modm/driver/display/ks0108.hpp +++ b/src/modm/driver/display/ks0108.hpp @@ -57,9 +57,10 @@ namespace modm protected: // Timing constants form the datasheet - static constexpr float DATA_SET_UP_TIME = 0.14f; - static constexpr float MIN_E_HIGH_TIME = 0.45f; - static constexpr float MIN_E_LOW_TIME = 0.45f; + static constexpr std::chrono::nanoseconds ADDRESS_SET_UP_TIME{140}; + static constexpr std::chrono::nanoseconds DATA_SET_UP_TIME{200}; + static constexpr std::chrono::nanoseconds MIN_E_HIGH_TIME{450}; + static constexpr std::chrono::nanoseconds MIN_E_LOW_TIME{450}; protected: /// Write one byte (Sets RW and E) diff --git a/src/modm/driver/display/ks0108_impl.hpp b/src/modm/driver/display/ks0108_impl.hpp index 6fd99b044e..ce3932a69f 100644 --- a/src/modm/driver/display/ks0108_impl.hpp +++ b/src/modm/driver/display/ks0108_impl.hpp @@ -124,13 +124,13 @@ modm::Ks0108::writeByte(uint8_t data) port.write(data); rw.reset(); - delayMicroseconds(DATA_SET_UP_TIME); + modm::delay(DATA_SET_UP_TIME); e.set(); - delayMicroseconds(MIN_E_HIGH_TIME); + modm::delay(MIN_E_HIGH_TIME); e.reset(); - delayMicroseconds(MIN_E_LOW_TIME); + modm::delay(MIN_E_LOW_TIME); } // ---------------------------------------------------------------------------- @@ -142,15 +142,15 @@ modm::Ks0108::readByte() port.setInput(); rw.set(); - delayMicroseconds(DATA_SET_UP_TIME); + modm::delay(DATA_SET_UP_TIME); e.set(); - delayMicroseconds(MIN_E_HIGH_TIME); + modm::delay(MIN_E_HIGH_TIME); uint8_t data = port.read(); e.reset(); - delayMicroseconds(MIN_E_LOW_TIME); + modm::delay(MIN_E_LOW_TIME); return data; } diff --git a/src/modm/driver/display/nokia6610_impl.hpp b/src/modm/driver/display/nokia6610_impl.hpp index 6ce76574f5..d0d886e169 100644 --- a/src/modm/driver/display/nokia6610_impl.hpp +++ b/src/modm/driver/display/nokia6610_impl.hpp @@ -31,9 +31,9 @@ modm::Nokia6610::initialize() // Reset pin Reset::setOutput(); Reset::reset(); - modm::delayMilliseconds(1); + modm::delay_ms(1); Reset::set(); - modm::delayMilliseconds(10); + modm::delay_ms(10); lcdSettings(); @@ -99,7 +99,8 @@ modm::Nokia6610::setContrast(uint8_t contrast) { template void -modm::Nokia6610::lcdSettings() { +modm::Nokia6610::lcdSettings() +{ CS::reset(); if( GE12){ @@ -107,9 +108,9 @@ modm::Nokia6610::lcdSettings() { else{ // Hardware reset Reset::reset(); - modm::delayMilliseconds(50); + modm::delay_ms(50); Reset::set(); - modm::delayMilliseconds(50); + modm::delay_ms(50); // Display vontrol writeSpiCommand(nokia::NOKIA_GE8_DISCTL); @@ -128,7 +129,7 @@ modm::Nokia6610::lcdSettings() { CS::set(); // wait aproximetly 100ms - modm::delayMilliseconds(100); + modm::delay_ms(100); CS::reset(); // Sleep out @@ -170,7 +171,8 @@ modm::Nokia6610::lcdSettings() { template void -modm::Nokia6610::update() { +modm::Nokia6610::update() +{ CS::reset(); if (GE12) @@ -219,7 +221,7 @@ modm::Nokia6610::update() { else { // wait approximately 100ms - modm::delayMilliseconds(100); + modm::delay_ms(100); // Display On writeSpiCommand(nokia::NOKIA_GE8_DISON); diff --git a/src/modm/driver/display/siemens_m55_impl.hpp b/src/modm/driver/display/siemens_m55_impl.hpp index 4fb584b61a..cf870e2378 100644 --- a/src/modm/driver/display/siemens_m55_impl.hpp +++ b/src/modm/driver/display/siemens_m55_impl.hpp @@ -59,11 +59,12 @@ modm::SiemensM55::initialize() template void -modm::SiemensM55::lcdSettings() { +modm::SiemensM55::lcdSettings() +{ // Hardware reset is low from initialize - modm::delayMilliseconds(10); + modm::delay_ms(10); Reset::set(); - modm::delayMilliseconds(10); + modm::delay_ms(10); RS::set(); // command mode CS::reset(); // select display @@ -72,10 +73,10 @@ modm::SiemensM55::lcdSettings() { { SPI::write(initData_lm15[ii]); // send initialization data } - modm::delayMilliseconds(1); + modm::delay_ms(1); CS::set(); // deactivate LCD CS - modm::delayMilliseconds(1); + modm::delay_ms(1); CS::reset(); // activate LCD CS SPI::write(0xF0); @@ -98,7 +99,7 @@ modm::SiemensM55::lcdSettings() { CS::set(); // deactivate LCD CS RS::reset(); // set LCD to data mode - modm::delayMilliseconds(10); + modm::delay_ms(10); static uint8_t contrast = 22; diff --git a/src/modm/driver/display/siemens_s65_impl.hpp b/src/modm/driver/display/siemens_s65_impl.hpp index 8ddd3c20a7..85320fa58a 100644 --- a/src/modm/driver/display/siemens_s65_impl.hpp +++ b/src/modm/driver/display/siemens_s65_impl.hpp @@ -97,14 +97,15 @@ modm::SiemensS65Common::writeData(uint16_t data) template void -modm::SiemensS65Common::lcdSettings(bool landscape) { +modm::SiemensS65Common::lcdSettings(bool landscape) +{ // Hardware reset is low from initialize - modm::delayMilliseconds(50); + modm::delay_ms(50); Reset::set(); - modm::delayMilliseconds(50); + modm::delay_ms(50); writeCmd(0x07, 0x0000); //display off - modm::delayMilliseconds(10); + modm::delay_ms(10); //power on sequence writeCmd(0x02, 0x0400); //lcd drive control @@ -117,11 +118,11 @@ modm::SiemensS65Common::lcdSettings(bool landscape) { writeCmd(0x03, 0x0000); //power control 1: BT //step 2 writeCmd(0x03, 0x0000); //power control 1: DC writeCmd(0x03, 0x000C); //power control 1: AP - modm::delayMilliseconds(40); + modm::delay_ms(40); writeCmd(0x0E, 0x2D1F); //power control 5: VCOMG //step 3 - modm::delayMilliseconds(40); + modm::delay_ms(40); writeCmd(0x0D, 0x0616); //power control 4: PON //step 4 - modm::delayMilliseconds(100); + modm::delay_ms(100); //display options if (landscape) { @@ -141,7 +142,7 @@ modm::SiemensS65Common::lcdSettings(bool landscape) { writeCmd(0x07, 0x0025); //display control: GON writeCmd(0x07, 0x0027); //display control: D1 writeCmd(0x07, 0x0037); //display control: DTE - modm::delayMilliseconds(10); + modm::delay_ms(10); lcdCls(0x03e0); } diff --git a/src/modm/driver/display/siemens_s75_impl.hpp b/src/modm/driver/display/siemens_s75_impl.hpp index e46043b1f4..0ae2484f47 100644 --- a/src/modm/driver/display/siemens_s75_impl.hpp +++ b/src/modm/driver/display/siemens_s75_impl.hpp @@ -135,12 +135,12 @@ void modm::SiemensS75Common::lcdSettings() { // Hardware reset is low from initialize - modm::delayMilliseconds(50); + modm::delay_ms(50); RESET::set(); - modm::delayMilliseconds(50); + modm::delay_ms(50); interface.writeRegister(0x00, 0x0001); // R00: Start oscillation - modm::delayMilliseconds(10); + modm::delay_ms(10); //power on sequence interface.writeRegister(0x10, 0x1f92); // R10: Power Control 1 @@ -152,7 +152,7 @@ modm::SiemensS75Common::lcdSettings() interface.writeRegister(0x02, 0x0000); // R02: LCD drive AC control interface.writeRegister(0x12, 0x040f); // R12: Power Control 2 - modm::delayMilliseconds(100); + modm::delay_ms(100); // R03: Entry mode switch(ORIENTATION) @@ -190,7 +190,7 @@ modm::SiemensS75Common::lcdSettings() interface.writeRegister(0x44, 0x8300); // Horizontal RAM Address interface.writeRegister(0x45, 0xaf00); // Vertical RAM Address - modm::delayMilliseconds(10); + modm::delay_ms(10); // colourful test lcdCls(0x0000); // black diff --git a/src/modm/driver/display/st7036_impl.hpp b/src/modm/driver/display/st7036_impl.hpp index 7f733cb7ea..7d06e2c1c9 100644 --- a/src/modm/driver/display/st7036_impl.hpp +++ b/src/modm/driver/display/st7036_impl.hpp @@ -90,9 +90,9 @@ modm::St7036::writeCommand(uint8_t inCommand) // check if the command is 'clear display' oder 'return home', these // commands take a bit longer until they are finished. if ((inCommand & 0xfc) == 0) { - modm::delayMicroseconds(1200); + modm::delay_us(1200); } else { - modm::delayMicroseconds(27); + modm::delay_us(27); } } diff --git a/src/modm/driver/display/st7565_impl.hpp b/src/modm/driver/display/st7565_impl.hpp index 159ae15503..06d21ca1c2 100644 --- a/src/modm/driver/display/st7565_impl.hpp +++ b/src/modm/driver/display/st7565_impl.hpp @@ -78,7 +78,7 @@ modm::St7565::initialize( // reset the controller reset.setOutput(); reset.reset(); - modm::delayMilliseconds(50); + modm::delay_ms(50); reset.set(); cs.reset(); diff --git a/src/modm/driver/fpga/xilinx_spartan3_impl.hpp b/src/modm/driver/fpga/xilinx_spartan3_impl.hpp index c2db93babf..3c9f921589 100644 --- a/src/modm/driver/fpga/xilinx_spartan3_impl.hpp +++ b/src/modm/driver/fpga/xilinx_spartan3_impl.hpp @@ -58,7 +58,6 @@ template < typename Cclk, bool modm::XilinxSpartan3::configure(const FpgaType fpgaType) { - configurePins(); MODM_LOG_DEBUG << MODM_FILE_INFO; @@ -72,7 +71,7 @@ modm::XilinxSpartan3::configure(const while (InitB::read() == modm::Gpio::High || Done::read() == modm::Gpio::High) { - modm::delayMicroseconds(1); + modm::delay_us(1); if (counter++ > 1000) { // Timeout (1ms) reached, FPGA is not responding abort configuration MODM_LOG_ERROR << MODM_FILE_INFO; @@ -83,14 +82,14 @@ modm::XilinxSpartan3::configure(const } // Led1::reset(); - modm::delayMicroseconds(1); + modm::delay_us(1); ProgB::set(); // Wait until INIT_B goes high uint32_t counter = 0; while (InitB::read() == modm::Gpio::Low) { - modm::delayMicroseconds(1); + modm::delay_us(1); if (counter++ > 1000) { // Timeout (1ms) reached, FPGA is not responding abort configuration MODM_LOG_ERROR << MODM_FILE_INFO; @@ -101,7 +100,7 @@ modm::XilinxSpartan3::configure(const // Led2::reset(); // wait 0.5..4us before starting the configuration - modm::delayMicroseconds(4); + modm::delay_us(4); uint8_t buffer[256]; diff --git a/src/modm/driver/fpga/xilinx_spartan6_impl.hpp b/src/modm/driver/fpga/xilinx_spartan6_impl.hpp index d1b77523c1..9d5f8f5862 100644 --- a/src/modm/driver/fpga/xilinx_spartan6_impl.hpp +++ b/src/modm/driver/fpga/xilinx_spartan6_impl.hpp @@ -55,7 +55,7 @@ modm::XilinxSpartan6Parallel 1000) { // Timeout (1ms) reached, FPGA is not responding abort configuration MODM_LOG_ERROR << MODM_FILE_INFO; @@ -74,7 +74,7 @@ modm::XilinxSpartan6Parallel 1000) { // Timeout (1ms) reached, FPGA is not responding abort configuration MODM_LOG_ERROR << MODM_FILE_INFO; diff --git a/src/modm/driver/gpio/mcp23s08_impl.hpp b/src/modm/driver/gpio/mcp23s08_impl.hpp index e8952682d4..2a526ad339 100644 --- a/src/modm/driver/gpio/mcp23s08_impl.hpp +++ b/src/modm/driver/gpio/mcp23s08_impl.hpp @@ -36,7 +36,7 @@ modm::Mcp23s08::initialize() cs.setOutput(); interrupt.setInput(); - modm::delayMicroseconds(1); + modm::delay_us(1); // disable address pins (as they are by default) and enable the // open-drain output from the interrupt line @@ -46,7 +46,7 @@ modm::Mcp23s08::initialize() spi.write(1 << 2); cs.set(); - modm::delayMicroseconds(1); + modm::delay_us(1); } template @@ -59,7 +59,7 @@ modm::Mcp23s08::configure(uint8_t inputMask, uint8_t pullupMask) spi.write(inputMask); cs.set(); - modm::delayMicroseconds(1); + modm::delay_us(1); cs.reset(); spi.write(deviceAddress | WRITE); @@ -67,7 +67,7 @@ modm::Mcp23s08::configure(uint8_t inputMask, uint8_t pullupMask) spi.write(pullupMask); cs.set(); - modm::delayMicroseconds(1); + modm::delay_us(1); } //void @@ -85,7 +85,7 @@ modm::Mcp23s08::read() uint8_t value = spi.write(0x00); cs.set(); - modm::delayMicroseconds(1); + modm::delay_us(1); return value; } @@ -100,5 +100,5 @@ modm::Mcp23s08::write(uint8_t output) spi.write(output); cs.set(); - modm::delayMicroseconds(1); + modm::delay_us(1); } diff --git a/src/modm/driver/motion/adns9800_impl.hpp b/src/modm/driver/motion/adns9800_impl.hpp index 9c5b0edca6..1456202df0 100644 --- a/src/modm/driver/motion/adns9800_impl.hpp +++ b/src/modm/driver/motion/adns9800_impl.hpp @@ -43,12 +43,12 @@ void modm::Adns9800< Spi, Cs>::getDeltaXY(int16_t &delta_x, int16_t &delta_y) { Cs::reset(); - modm::delayMicroseconds(100); // tSRAD + modm::delay_us(100); // tSRAD Spi::transferBlocking(static_cast(Register::Motion_Burst)); // Delay tSRAD - modm::delayMicroseconds(100); + modm::delay_us(100); static constexpr uint8_t buf_size = 6; uint8_t tx_buf[buf_size]; @@ -56,7 +56,7 @@ modm::Adns9800< Spi, Cs>::getDeltaXY(int16_t &delta_x, int16_t &delta_y) Spi::transferBlocking(tx_buf, rx_buf, buf_size); - modm::delayNanoseconds(120); // tSCLK-NCS for read operation is 120ns + modm::delay_ns(120); // tSCLK-NCS for read operation is 120ns Cs::set(); uint8_t delta_x_l = rx_buf[2]; @@ -78,14 +78,14 @@ modm::Adns9800< Spi, Cs>::readReg(Register const reg) // send adress of the register, with MSBit = 0 to indicate it's a read Spi::transferBlocking(address & 0x7f); - modm::delayMicroseconds(100); // tSRAD + modm::delay_us(100); // tSRAD // read data uint8_t data = Spi::transferBlocking(0); - modm::delayNanoseconds(120); // tSCLK-NCS for read operation is 120ns + modm::delay_ns(120); // tSCLK-NCS for read operation is 120ns Cs::set(); - modm::delayMicroseconds(19); // tSRW/tSRR (=20us) minus tSCLK-NCS + modm::delay_us(19); // tSRW/tSRR (=20us) minus tSCLK-NCS return data; } @@ -104,9 +104,9 @@ modm::Adns9800< Spi, Cs>::writeReg(Register const reg, uint8_t const data) //send data Spi::transferBlocking(data); - modm::delayMicroseconds(20); // tSCLK-NCS for write operation + modm::delay_us(20); // tSCLK-NCS for write operation Cs::set(); - modm::delayMicroseconds(100); // tSWW/tSWR (=120us) minus tSCLK-NCS. Could be shortened, but is looks like a safe lower bound + modm::delay_us(100); // tSWW/tSWR (=120us) minus tSCLK-NCS. Could be shortened, but is looks like a safe lower bound } template < typename Spi, typename Cs > @@ -120,7 +120,7 @@ modm::Adns9800< Spi, Cs >::uploadFirmware() writeReg(Register::SROM_Enable, 0x1d); // wait for more than one frame period - modm::delayMilliseconds(10); // assume that the frame rate is as low as 100fps... even if it should never be that low + modm::delay_ms(10); // assume that the frame rate is as low as 100fps... even if it should never be that low // write 0x18 to SROM_enable to start SROM download writeReg(Register::SROM_Enable, 0x18); @@ -131,13 +131,13 @@ modm::Adns9800< Spi, Cs >::uploadFirmware() // write burst destination address uint8_t address = static_cast(Register::SROM_Load_Burst) | 0x80; Spi::transferBlocking(address); - modm::delayMicroseconds(15); + modm::delay_us(15); // send all bytes of the firmware for(int ii = 0; ii < firmware_length; ++ii) { Spi::transferBlocking(firmware_data[ii]); - modm::delayMicroseconds(15); + modm::delay_us(15); } Cs::set(); @@ -155,7 +155,7 @@ modm::Adns9800< Spi, Cs >::initialise() Cs::set(); writeReg(Register::Power_Up_Reset, 0x5a); // force reset - modm::delayMilliseconds(50); // wait for it to reboot + modm::delay_ms(50); // wait for it to reboot // Read Product ID uint8_t id = readReg(Register::Product_ID); @@ -191,7 +191,7 @@ modm::Adns9800< Spi, Cs >::initialise() readReg(Register::Delta_Y_H); uploadFirmware(); - modm::delayMilliseconds(10); + modm::delay_ms(10); // enable laser(bit 0 = 0b), in normal mode (bits 3,2,1 = 000b) // reading the actual value of the register is important because the real @@ -214,7 +214,7 @@ modm::Adns9800< Spi, Cs >::initialise() writeReg(Register::Frame_Period_Max_Bound_Lower, 0x20); writeReg(Register::Frame_Period_Max_Bound_Upper, 0x1b); - modm::delayMilliseconds(1); + modm::delay_ms(1); return success; } diff --git a/src/modm/driver/other/ad840x_impl.hpp b/src/modm/driver/other/ad840x_impl.hpp index 65334deacb..ab7bc06cfe 100644 --- a/src/modm/driver/other/ad840x_impl.hpp +++ b/src/modm/driver/other/ad840x_impl.hpp @@ -33,7 +33,7 @@ inline void modm::AD840x::reset() { Rs::reset(); - modm::delayMicroseconds(1); // wait at least 50ns + modm::delay_us(1); // wait at least 50ns Rs::set(); } diff --git a/src/modm/driver/pressure/scp1000_impl.hpp b/src/modm/driver/pressure/scp1000_impl.hpp index 08e1fc27ca..857f09f665 100644 --- a/src/modm/driver/pressure/scp1000_impl.hpp +++ b/src/modm/driver/pressure/scp1000_impl.hpp @@ -101,7 +101,7 @@ modm::Scp1000::setOperation(scp1000::Operation opMode) uint8_t retries = 16; // wait for the sensor to complete setting the operation while (--retries && (readStatus(true) & scp1000::OPERATION_STATUS_RUNNING)) { - modm::delayMilliseconds(1); + modm::delay_ms(1); } // The sensor took too long to complete the operation @@ -129,12 +129,12 @@ modm::Scp1000::reset(uint8_t timeout=50) writeRegister(scp1000::REGISTER_RSTR, scp1000::RESET); // wait a bit to give the Scp1000 some time to restart - modm::delayMilliseconds(151); + modm::delay_ms(151); uint8_t retries = timeout; // wait for the sensor to complete start up, this should take 160ms while (--retries && (readStatus() & scp1000::STATUS_STARTUP_RUNNING_bm)) { - modm::delayMilliseconds(1); + modm::delay_ms(1); } if (retries > 0) { diff --git a/src/modm/driver/pwm/max6966_impl.hpp b/src/modm/driver/pwm/max6966_impl.hpp index b1ec5f45a4..a14694fbb7 100644 --- a/src/modm/driver/pwm/max6966_impl.hpp +++ b/src/modm/driver/pwm/max6966_impl.hpp @@ -164,7 +164,7 @@ modm::MAX6966::readFromDriver(uint8_t driver, max6966::Registe Cs::set(); // TODO: Add delay here? -// modm::delayMilliseconds(1); +// modm::delay_ms(1); // send dummy data and get the right register uint8_t data=0; diff --git a/src/modm/driver/pwm/tlc594x_impl.hpp b/src/modm/driver/pwm/tlc594x_impl.hpp index fa93177dd0..ea20a410f5 100644 --- a/src/modm/driver/pwm/tlc594x_impl.hpp +++ b/src/modm/driver/pwm/tlc594x_impl.hpp @@ -42,7 +42,7 @@ modm::TLC594X::latch() Xlat::set(); // datasheet says 20ns but that is unreliable // => wait for at least 1000ns - modm::delayMicroseconds(1); + modm::delay_us(1); Xlat::reset(); if (enabled) Xblank::reset(); } diff --git a/src/modm/driver/radio/nrf24/nrf24_config_impl.hpp b/src/modm/driver/radio/nrf24/nrf24_config_impl.hpp index 10f1a45324..aa3e5fd850 100644 --- a/src/modm/driver/radio/nrf24/nrf24_config_impl.hpp +++ b/src/modm/driver/radio/nrf24/nrf24_config_impl.hpp @@ -33,7 +33,7 @@ modm::Nrf24Config::setMode(Mode mode) case Mode::Rx: // MODM_LOG_DEBUG << "[nrf24] Set mode Rx" << modm::endl; // Nrf24Phy::resetCe(); -// modm::delayMicroseconds(30); +// modm::delay_us(30); Nrf24Phy::flushRxFifo(); Nrf24Phy::setBits(NrfRegister::CONFIG, Config::PRIM_RX); diff --git a/src/modm/driver/radio/nrf24/nrf24_phy_impl.hpp b/src/modm/driver/radio/nrf24/nrf24_phy_impl.hpp index 67ba979d57..e75123e5eb 100644 --- a/src/modm/driver/radio/nrf24/nrf24_phy_impl.hpp +++ b/src/modm/driver/radio/nrf24/nrf24_phy_impl.hpp @@ -320,7 +320,7 @@ modm::Nrf24Phy::pulseCe() Ce::toggle(); // delay might not be precise enough - modm::delayMicroseconds(15); + modm::delay_us(15); Ce::toggle(); } diff --git a/src/modm/driver/rtc/ds1302.hpp b/src/modm/driver/rtc/ds1302.hpp index 93fcfdc45b..3b9e7753c1 100644 --- a/src/modm/driver/rtc/ds1302.hpp +++ b/src/modm/driver/rtc/ds1302.hpp @@ -13,6 +13,8 @@ #ifndef MODM_DS1302_HPP #define MODM_DS1302_HPP +#include + namespace modm { @@ -150,10 +152,10 @@ class Ds1302 protected: /// Required CE to CLK Setup Time can be as long as 4 usec and 2 Volts. - static constexpr uint8_t delay_ce = 4; // microseconds + static constexpr std::chrono::microseconds DELAY_CE{4}; /// Required CLK Low/High Time can be as long as 1 usec and 2 Volts. - static constexpr uint8_t delay_clk = 1; // microsecond + static constexpr std::chrono::microseconds DELAY_CLK{1}; }; } diff --git a/src/modm/driver/rtc/ds1302_impl.hpp b/src/modm/driver/rtc/ds1302_impl.hpp index ae166fa2cc..1b4449b4cd 100644 --- a/src/modm/driver/rtc/ds1302_impl.hpp +++ b/src/modm/driver/rtc/ds1302_impl.hpp @@ -14,8 +14,6 @@ #error "Do not include ds1302_impl.hpp. Only include ds1302.hpp" #endif -#include - template < class PinSet > void modm::Ds1302< PinSet >::initialize() @@ -29,20 +27,20 @@ template< class PinSet > void modm::Ds1302< PinSet >::writeByte(uint8_t byte) { - modm::delayMicroseconds(delay_ce); + modm::delay(DELAY_CE); Io::setOutput(); for (uint8_t ii = 8; ii > 0; --ii) { - modm::delayMicroseconds(delay_clk); + modm::delay(DELAY_CLK); Sclk::reset(); Io::set(byte & 0x01); - modm::delayMicroseconds(delay_clk); + modm::delay(DELAY_CLK); Sclk::set(); byte >>= 1; } - modm::delayMicroseconds(delay_clk); + modm::delay(DELAY_CLK); } template< class PinSet > @@ -55,10 +53,10 @@ modm::Ds1302< PinSet >::write(const uint8_t addr, const uint8_t data) // Cleanup Sclk::reset(); - modm::delayMicroseconds(delay_clk); + modm::delay(DELAY_CLK); Io::setInput(); Ce::reset(); - modm::delayMicroseconds(delay_ce); + modm::delay(DELAY_CE); } template< class PinSet > @@ -71,16 +69,16 @@ modm::Ds1302< PinSet >::read(const uint8_t addr) uint8_t ret = 0; Io::setInput(); - modm::delayMicroseconds(delay_clk); + modm::delay(DELAY_CLK); for (uint8_t ii = 8; ii > 0; --ii) { bool rr = Io::read(); ret >>= 1; ret |= (rr << 7); Sclk::set(); - modm::delayMicroseconds(delay_clk); + modm::delay(DELAY_CLK); Sclk::reset(); - modm::delayMicroseconds(delay_clk); + modm::delay(DELAY_CLK); } Ce::reset(); @@ -101,7 +99,7 @@ modm::Ds1302< PinSet >::readRtc(ds1302::Data &storage) Sclk::reset(); // Wait for stable output - modm::delayMicroseconds(delay_ce); + modm::delay(DELAY_CE); for (uint8_t jj = 0; jj < MODM_ARRAY_SIZE(storage.data); ++jj) { @@ -112,11 +110,11 @@ modm::Ds1302< PinSet >::readRtc(ds1302::Data &storage) ret >>= 1; ret |= (rr << 7); Sclk::set(); - modm::delayMicroseconds(delay_clk); + modm::delay(DELAY_CLK); // Falling edge of SCLK will trigger DS1302 output Sclk::reset(); - modm::delayMicroseconds(delay_clk); + modm::delay(DELAY_CLK); } storage.data[jj] = ret; } diff --git a/src/modm/driver/storage/spi_ram_impl.hpp b/src/modm/driver/storage/spi_ram_impl.hpp index c358eaa133..5a0ad48357 100644 --- a/src/modm/driver/storage/spi_ram_impl.hpp +++ b/src/modm/driver/storage/spi_ram_impl.hpp @@ -39,14 +39,14 @@ modm::SpiRam::initialize() hold.set(); hold.setOutput(); - modm::delayMicroseconds(1); + modm::delay_us(1); cs.reset(); spi.write(WRITE_STATUS_REGISTER); spi.write(SEQUENTIAL_MODE); cs.set(); - modm::delayMicroseconds(1); + modm::delay_us(1); // Check if the status register has the right content. This also used // as a general check that the device is available. diff --git a/src/modm/driver/touch/ads7843_impl.hpp b/src/modm/driver/touch/ads7843_impl.hpp index e6a3870ae8..a8f1ef47fa 100644 --- a/src/modm/driver/touch/ads7843_impl.hpp +++ b/src/modm/driver/touch/ads7843_impl.hpp @@ -94,13 +94,13 @@ uint16_t modm::Ads7843::readData(uint8_t command) { Cs::reset(); - modm::delayMicroseconds(1); // modm::delay_ns(100); + modm::delay_us(1); // modm::delay_ns(100); Spi::transferBlocking(command); - modm::delayMicroseconds(1); + modm::delay_us(1); uint16_t temp = Spi::transferBlocking(0x00); temp <<= 8; - modm::delayMicroseconds(1); + modm::delay_us(1); temp |= Spi::transferBlocking(0x00); temp >>= 3; diff --git a/src/modm/platform/adc/stm32f0/adc_impl.hpp.in b/src/modm/platform/adc/stm32f0/adc_impl.hpp.in index 60c9d3ad49..4167bc29a4 100644 --- a/src/modm/platform/adc/stm32f0/adc_impl.hpp.in +++ b/src/modm/platform/adc/stm32f0/adc_impl.hpp.in @@ -132,7 +132,7 @@ modm::platform::Adc{{ id }}::setChannel(const Channel channel, const SampleTimeG { %% if target.family in ["g0"] ADC1->CR |= ADC_CR_ADVREGEN; - modm::delayMicroseconds(30); + modm::delay_us(30); %% endif ADC1_COMMON->CCR |= ADC_CCR_VREFEN; } @@ -145,7 +145,7 @@ modm::platform::Adc{{ id }}::setChannel(const Channel channel, const SampleTimeG not (ADC1_COMMON->CCR & ADC_CCR_TSEN)) { ADC1_COMMON->CCR |= ADC_CCR_TSEN; - modm::delayMicroseconds(135); + modm::delay_us(135); } %% if target.family in ["g0"] diff --git a/src/modm/platform/adc/stm32f3/adc_impl.hpp.in b/src/modm/platform/adc/stm32f3/adc_impl.hpp.in index ad6331348a..2873b40d93 100644 --- a/src/modm/platform/adc/stm32f3/adc_impl.hpp.in +++ b/src/modm/platform/adc/stm32f3/adc_impl.hpp.in @@ -63,7 +63,7 @@ modm::platform::Adc{{ id }}::initialize(const ClockMode clk, // enable regulator ADC{{ id }}->CR &= ~ADC_CR_ADVREGEN; ADC{{ id }}->CR |= static_cast(VoltageRegulatorState::Enabled); - modm::delayMicroseconds(10); // FIXME: this is ugly -> find better solution + modm::delay_us(10); // FIXME: this is ugly -> find better solution // Clear ready flag ADC{{ id }}->ISR |= ADC_ISR_ADRDY; diff --git a/src/modm/platform/can/stm32/can.cpp.in b/src/modm/platform/can/stm32/can.cpp.in index 36f999fd12..b1a8451c7a 100644 --- a/src/modm/platform/can/stm32/can.cpp.in +++ b/src/modm/platform/can/stm32/can.cpp.in @@ -96,7 +96,7 @@ modm::platform::Can{{ id }}::initializeWithPrescaler( {{ reg }}->MCR |= CAN_MCR_INRQ; int deadlockPreventer = 10'000; // max ~10ms while ((({{ reg }}->MSR & CAN_MSR_INAK) == 0) and (deadlockPreventer-- > 0)) { - modm::delayMicroseconds(1); + modm::delay_us(1); // Wait until the initialization mode is entered. // The CAN hardware waits until the current CAN activity (transmission // or reception) is completed before entering the initialization mode. diff --git a/src/modm/platform/i2c/bitbang/bitbang_i2c_master.hpp.in b/src/modm/platform/i2c/bitbang/bitbang_i2c_master.hpp.in index 36215ceb53..8260a70c37 100644 --- a/src/modm/platform/i2c/bitbang/bitbang_i2c_master.hpp.in +++ b/src/modm/platform/i2c/bitbang/bitbang_i2c_master.hpp.in @@ -118,13 +118,13 @@ private: /// busy waits a **half** clock cycle static modm_always_inline void delay2() - { modm::delayNanoseconds(delayTime*2); } + { modm::delay_ns(delayTime*2); } // timings /// busy waits **quarter** clock cycle static modm_always_inline void delay4() - { modm::delayNanoseconds(delayTime); } + { modm::delay_ns(delayTime); } enum { diff --git a/src/modm/platform/one_wire/bitbang/bitbang_master.hpp.in b/src/modm/platform/one_wire/bitbang/bitbang_master.hpp.in index 501652c57d..218693cb71 100644 --- a/src/modm/platform/one_wire/bitbang/bitbang_master.hpp.in +++ b/src/modm/platform/one_wire/bitbang/bitbang_master.hpp.in @@ -167,16 +167,16 @@ protected: performSearch(); // standard delay times in microseconds - static constexpr unsigned int A = 6; - static constexpr unsigned int B = 64; - static constexpr unsigned int C = 60; - static constexpr unsigned int D = 10; - static constexpr unsigned int E = 9; - static constexpr unsigned int F = 55; - static constexpr unsigned int G = 0; - static constexpr unsigned int H = 480; - static constexpr unsigned int I = 70; - static constexpr unsigned int J = 410; + static constexpr std::chrono::microseconds A{6}; + static constexpr std::chrono::microseconds B{64}; + static constexpr std::chrono::microseconds C{60}; + static constexpr std::chrono::microseconds D{10}; + static constexpr std::chrono::microseconds E{9}; + static constexpr std::chrono::microseconds F{55}; + static constexpr std::chrono::microseconds G{0}; + static constexpr std::chrono::microseconds H{480}; + static constexpr std::chrono::microseconds I{70}; + static constexpr std::chrono::microseconds J{410}; // state of the search static uint8_t lastDiscrepancy; diff --git a/src/modm/platform/one_wire/bitbang/bitbang_master_impl.hpp.in b/src/modm/platform/one_wire/bitbang/bitbang_master_impl.hpp.in index 8906fed3d6..6b472041b9 100644 --- a/src/modm/platform/one_wire/bitbang/bitbang_master_impl.hpp.in +++ b/src/modm/platform/one_wire/bitbang/bitbang_master_impl.hpp.in @@ -31,16 +31,16 @@ template bool modm::platform::BitBangOneWireMaster::touchReset() { - delayMicroseconds(G); + modm::delay(G); PIN::reset(); // drives the bus low - delayMicroseconds(H); + modm::delay(H); PIN::set(); // releases the bus - delayMicroseconds(I); + modm::delay(I); // sample for presence pulse from slave bool result = !PIN::read(); - delayMicroseconds(J); // complete the reset sequence recovery + modm::delay(J); // complete the reset sequence recovery return result; } @@ -52,16 +52,16 @@ modm::platform::BitBangOneWireMaster::writeBit(bool bit) if (bit) { PIN::reset(); // Drives bus low - delayMicroseconds(A); + modm::delay(A); PIN::set(); // Releases the bus - delayMicroseconds(B); // Complete the time slot and 10us recovery + modm::delay(B); // Complete the time slot and 10us recovery } else { PIN::reset(); - delayMicroseconds(C); + modm::delay(C); PIN::set(); - delayMicroseconds(D); + modm::delay(D); } } @@ -70,14 +70,14 @@ bool modm::platform::BitBangOneWireMaster::readBit() { PIN::reset(); // drives the bus low - delayMicroseconds(A); + modm::delay(A); PIN::set(); // releases the bus - delayMicroseconds(E); + modm::delay(E); // Sample the bit value from the slave bool result = PIN::read(); - delayMicroseconds(F); // complete the reset sequence recovery + modm::delay(F); // complete the reset sequence recovery return result; } diff --git a/src/modm/platform/spi/bitbang/bitbang_spi_master_impl.hpp b/src/modm/platform/spi/bitbang/bitbang_spi_master_impl.hpp index 0967622cad..b33ee5be7e 100644 --- a/src/modm/platform/spi/bitbang/bitbang_spi_master_impl.hpp +++ b/src/modm/platform/spi/bitbang/bitbang_spi_master_impl.hpp @@ -217,5 +217,5 @@ template void modm_always_inline modm::platform::BitBangSpiMaster::delay() { - modm::delayNanoseconds(delayTime); + modm::delay_ns(delayTime); } diff --git a/test/all/avr.cpp b/test/all/avr.cpp index 7c2004a6bd..19dfb28e1e 100644 --- a/test/all/avr.cpp +++ b/test/all/avr.cpp @@ -10,6 +10,7 @@ #include #include +using namespace std::chrono_literals; int main(void) { @@ -19,7 +20,7 @@ int main(void) while (true) { LedRed::toggle(); - modm::delayMilliseconds(500); + modm::delay(500ms); } return 0; diff --git a/test/all/stm32.cpp b/test/all/stm32.cpp index 41e86d6521..298529e6bb 100644 --- a/test/all/stm32.cpp +++ b/test/all/stm32.cpp @@ -11,13 +11,14 @@ #include #include +using namespace std::chrono_literals; int main(void) { while (true) { - modm::delayMilliseconds(500); + modm::delay(500ms); } return 0;