Skip to content

Commit

Permalink
πŸ§‘β€πŸ’» Remove LOOP macros (#25917)
Browse files Browse the repository at this point in the history
  • Loading branch information
thinkyhead committed Jun 2, 2023
1 parent 2691167 commit 86c8116
Show file tree
Hide file tree
Showing 122 changed files with 362 additions and 367 deletions.
4 changes: 2 additions & 2 deletions Marlin/src/HAL/AVR/HAL_SPI.cpp
Expand Up @@ -198,7 +198,7 @@ void spiBegin() {
// output pin high - like sending 0xFF
WRITE(SD_MOSI_PIN, HIGH);

LOOP_L_N(i, 8) {
for (uint8_t i = 0; i < 8; ++i) {
WRITE(SD_SCK_PIN, HIGH);

nop; // adjust so SCK is nice
Expand All @@ -225,7 +225,7 @@ void spiBegin() {
void spiSend(uint8_t data) {
// no interrupts during byte send - about 8Β΅s
cli();
LOOP_L_N(i, 8) {
for (uint8_t i = 0; i < 8; ++i) {
WRITE(SD_SCK_PIN, LOW);
WRITE(SD_MOSI_PIN, data & 0x80);
data <<= 1;
Expand Down
4 changes: 2 additions & 2 deletions Marlin/src/HAL/AVR/fast_pwm.cpp
Expand Up @@ -132,7 +132,7 @@ void MarlinHAL::set_pwm_frequency(const pin_t pin, const uint16_t f_desired) {

DEBUG_ECHOLNPGM("f=", f);
DEBUG_ECHOLNPGM("(prescaler loop)");
LOOP_L_N(i, COUNT(prescaler)) { // Loop through all prescaler values
for (uint8_t i = 0; i < COUNT(prescaler); ++i) { // Loop through all prescaler values
const uint32_t p = prescaler[i]; // Extend to 32 bits for calculations
DEBUG_ECHOLNPGM("prescaler[", i, "]=", p);
uint16_t res_fast_temp, res_pc_temp;
Expand Down Expand Up @@ -232,7 +232,7 @@ void MarlinHAL::init_pwm_timers() {
#endif
};

LOOP_L_N(i, COUNT(pwm_pin))
for (uint8_t i = 0; i < COUNT(pwm_pin); ++i)
set_pwm_frequency(pwm_pin[i], 1000);
}

Expand Down
4 changes: 2 additions & 2 deletions Marlin/src/HAL/AVR/pinsDebug.h
Expand Up @@ -77,12 +77,12 @@

void PRINT_ARRAY_NAME(uint8_t x) {
PGM_P const name_mem_pointer = (PGM_P)pgm_read_ptr(&pin_array[x].name);
LOOP_L_N(y, MAX_NAME_LENGTH) {
for (uint8_t y = 0; y < MAX_NAME_LENGTH; ++y) {
char temp_char = pgm_read_byte(name_mem_pointer + y);
if (temp_char != 0)
SERIAL_CHAR(temp_char);
else {
LOOP_L_N(i, MAX_NAME_LENGTH - y) SERIAL_CHAR(' ');
for (uint8_t i = 0; i < MAX_NAME_LENGTH - y; ++i) SERIAL_CHAR(' ');
break;
}
}
Expand Down
4 changes: 2 additions & 2 deletions Marlin/src/HAL/AVR/u8g_com_HAL_AVR_sw_spi.cpp
Expand Up @@ -88,7 +88,7 @@ void u8g_spiSend_sw_AVR_mode_0(uint8_t val) {
volatile uint8_t *outData = u8g_outData,
*outClock = u8g_outClock;
U8G_ATOMIC_START();
LOOP_L_N(i, 8) {
for (uint8_t i = 0; i < 8; ++i) {
if (val & 0x80)
*outData |= bitData;
else
Expand All @@ -108,7 +108,7 @@ void u8g_spiSend_sw_AVR_mode_3(uint8_t val) {
volatile uint8_t *outData = u8g_outData,
*outClock = u8g_outClock;
U8G_ATOMIC_START();
LOOP_L_N(i, 8) {
for (uint8_t i = 0; i < 8; ++i) {
*outClock &= bitNotClock;
if (val & 0x80)
*outData |= bitData;
Expand Down
4 changes: 2 additions & 2 deletions Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_sw_spi_shared.cpp
Expand Up @@ -81,7 +81,7 @@ Pio *SCK_pPio, *MOSI_pPio;
uint32_t SCK_dwMask, MOSI_dwMask;

void u8g_spiSend_sw_DUE_mode_0(uint8_t val) { // 3MHz
LOOP_L_N(i, 8) {
for (uint8_t i = 0; i < 8; ++i) {
if (val & 0x80)
MOSI_pPio->PIO_SODR = MOSI_dwMask;
else
Expand All @@ -95,7 +95,7 @@ void u8g_spiSend_sw_DUE_mode_0(uint8_t val) { // 3MHz
}

void u8g_spiSend_sw_DUE_mode_3(uint8_t val) { // 3.5MHz
LOOP_L_N(i, 8) {
for (uint8_t i = 0; i < 8; ++i) {
SCK_pPio->PIO_CODR = SCK_dwMask;
DELAY_NS(50);
if (val & 0x80)
Expand Down
2 changes: 1 addition & 1 deletion Marlin/src/HAL/DUE/fastio/G2_PWM.h
Expand Up @@ -63,7 +63,7 @@ extern PWM_map ISR_table[NUM_PWMS];
extern uint32_t motor_current_setting[3];

#define IR_BIT(p) (WITHIN(p, 0, 3) ? (p) : (p) + 4)
#define COPY_ACTIVE_TABLE() do{ LOOP_L_N(i, 6) work_table[i] = active_table[i]; }while(0)
#define COPY_ACTIVE_TABLE() do{ for (uint8_t i = 0; i < 6; ++i) work_table[i] = active_table[i]; }while(0)

#define PWM_MR0 19999 // base repetition rate minus one count - 20mS
#define PWM_PR 24 // prescaler value - prescaler divide by 24 + 1 - 1 MHz output
Expand Down
2 changes: 1 addition & 1 deletion Marlin/src/HAL/ESP32/i2s.cpp
Expand Up @@ -356,7 +356,7 @@ void i2s_push_sample() {
// Every 4Β΅s (when space in DMA buffer) toggle each expander PWM output using
// the current duty cycle/frequency so they sync with any steps (once
// through the DMA/FIFO buffers). PWM signal inversion handled by other functions
LOOP_L_N(p, MAX_EXPANDER_BITS) {
for (uint8_t p = 0; p < MAX_EXPANDER_BITS; ++p) {
if (hal.pwm_pin_data[p].pwm_duty_ticks > 0) { // pin has active pwm?
if (hal.pwm_pin_data[p].pwm_tick_count == 0) {
if (TEST32(i2s_port_data, p)) { // hi->lo
Expand Down
2 changes: 1 addition & 1 deletion Marlin/src/HAL/LPC1768/main.cpp
Expand Up @@ -68,7 +68,7 @@ void MarlinHAL::init() {
#endif

// Flash status LED 3 times to indicate Marlin has started booting
LOOP_L_N(i, 6) {
for (uint8_t i = 0; i < 6; ++i) {
TOGGLE(LED_PIN);
delay(100);
}
Expand Down
2 changes: 1 addition & 1 deletion Marlin/src/HAL/LPC1768/tft/tft_spi.cpp
Expand Up @@ -74,7 +74,7 @@ uint32_t TFT_SPI::ReadID(uint16_t Reg) {
WRITE(TFT_CS_PIN, LOW);
WriteReg(Reg);

LOOP_L_N(i, 4) {
for (uint8_t i = 0; i < 4; ++i) {
SPIx.read((uint8_t*)&d, 1);
data = (data << 8) | d;
}
Expand Down
16 changes: 8 additions & 8 deletions Marlin/src/HAL/LPC1768/u8g/u8g_com_HAL_LPC1768_sw_spi.cpp
Expand Up @@ -75,7 +75,7 @@

uint8_t swSpiTransfer_mode_0(uint8_t b, const uint8_t spi_speed, const pin_t sck_pin, const pin_t miso_pin, const pin_t mosi_pin ) {

LOOP_L_N(i, 8) {
for (uint8_t i = 0; i < 8; ++i) {
if (spi_speed == 0) {
LPC176x::gpio_set(mosi_pin, !!(b & 0x80));
LPC176x::gpio_set(sck_pin, HIGH);
Expand All @@ -85,16 +85,16 @@ uint8_t swSpiTransfer_mode_0(uint8_t b, const uint8_t spi_speed, const pin_t sck
}
else {
const uint8_t state = (b & 0x80) ? HIGH : LOW;
LOOP_L_N(j, spi_speed)
for (uint8_t j = 0; j < spi_speed; ++j)
LPC176x::gpio_set(mosi_pin, state);

LOOP_L_N(j, spi_speed + (miso_pin >= 0 ? 0 : 1))
for (uint8_t j = 0; j < spi_speed + (miso_pin >= 0 ? 0 : 1); ++j)
LPC176x::gpio_set(sck_pin, HIGH);

b <<= 1;
if (miso_pin >= 0 && LPC176x::gpio_get(miso_pin)) b |= 1;

LOOP_L_N(j, spi_speed)
for (uint8_t j = 0; j < spi_speed; ++j)
LPC176x::gpio_set(sck_pin, LOW);
}
}
Expand All @@ -104,7 +104,7 @@ uint8_t swSpiTransfer_mode_0(uint8_t b, const uint8_t spi_speed, const pin_t sck

uint8_t swSpiTransfer_mode_3(uint8_t b, const uint8_t spi_speed, const pin_t sck_pin, const pin_t miso_pin, const pin_t mosi_pin ) {

LOOP_L_N(i, 8) {
for (uint8_t i = 0; i < 8; ++i) {
const uint8_t state = (b & 0x80) ? HIGH : LOW;
if (spi_speed == 0) {
LPC176x::gpio_set(sck_pin, LOW);
Expand All @@ -113,13 +113,13 @@ uint8_t swSpiTransfer_mode_3(uint8_t b, const uint8_t spi_speed, const pin_t sck
LPC176x::gpio_set(sck_pin, HIGH);
}
else {
LOOP_L_N(j, spi_speed + (miso_pin >= 0 ? 0 : 1))
for (uint8_t j = 0; j < spi_speed + (miso_pin >= 0 ? 0 : 1); ++j)
LPC176x::gpio_set(sck_pin, LOW);

LOOP_L_N(j, spi_speed)
for (uint8_t j = 0; j < spi_speed; ++j)
LPC176x::gpio_set(mosi_pin, state);

LOOP_L_N(j, spi_speed)
for (uint8_t j = 0; j < spi_speed; ++j)
LPC176x::gpio_set(sck_pin, HIGH);
}
b <<= 1;
Expand Down
16 changes: 8 additions & 8 deletions Marlin/src/HAL/NATIVE_SIM/u8g/u8g_com_sw_spi.cpp
Expand Up @@ -70,7 +70,7 @@
#endif

uint8_t swSpiTransfer_mode_0(uint8_t b, const uint8_t spi_speed, const pin_t sck_pin, const pin_t miso_pin, const pin_t mosi_pin ) {
LOOP_L_N(i, 8) {
for (uint8_t i = 0; i < 8; ++i) {
if (spi_speed == 0) {
WRITE_PIN(mosi_pin, !!(b & 0x80));
WRITE_PIN(sck_pin, HIGH);
Expand All @@ -80,16 +80,16 @@ uint8_t swSpiTransfer_mode_0(uint8_t b, const uint8_t spi_speed, const pin_t sck
}
else {
const uint8_t state = (b & 0x80) ? HIGH : LOW;
LOOP_L_N(j, spi_speed)
for (uint8_t j = 0; j < spi_speed; ++j)
WRITE_PIN(mosi_pin, state);

LOOP_L_N(j, spi_speed + (miso_pin >= 0 ? 0 : 1))
for (uint8_t j = 0; j < spi_speed + (miso_pin >= 0 ? 0 : 1); ++j)
WRITE_PIN(sck_pin, HIGH);

b <<= 1;
if (miso_pin >= 0 && READ_PIN(miso_pin)) b |= 1;

LOOP_L_N(j, spi_speed)
for (uint8_t j = 0; j < spi_speed; ++j)
WRITE_PIN(sck_pin, LOW);
}
}
Expand All @@ -99,7 +99,7 @@ uint8_t swSpiTransfer_mode_0(uint8_t b, const uint8_t spi_speed, const pin_t sck

uint8_t swSpiTransfer_mode_3(uint8_t b, const uint8_t spi_speed, const pin_t sck_pin, const pin_t miso_pin, const pin_t mosi_pin ) {

LOOP_L_N(i, 8) {
for (uint8_t i = 0; i < 8; ++i) {
const uint8_t state = (b & 0x80) ? HIGH : LOW;
if (spi_speed == 0) {
WRITE_PIN(sck_pin, LOW);
Expand All @@ -108,13 +108,13 @@ uint8_t swSpiTransfer_mode_3(uint8_t b, const uint8_t spi_speed, const pin_t sck
WRITE_PIN(sck_pin, HIGH);
}
else {
LOOP_L_N(j, spi_speed + (miso_pin >= 0 ? 0 : 1))
for (uint8_t j = 0; j < spi_speed + (miso_pin >= 0 ? 0 : 1); ++j)
WRITE_PIN(sck_pin, LOW);

LOOP_L_N(j, spi_speed)
for (uint8_t j = 0; j < spi_speed; ++j)
WRITE_PIN(mosi_pin, state);

LOOP_L_N(j, spi_speed)
for (uint8_t j = 0; j < spi_speed; ++j)
WRITE_PIN(sck_pin, HIGH);
}
b <<= 1;
Expand Down
6 changes: 3 additions & 3 deletions Marlin/src/HAL/SAMD51/HAL.cpp
Expand Up @@ -650,10 +650,10 @@ void MarlinHAL::adc_init() {
#if ADC_IS_REQUIRED
memset(adc_results, 0xFF, sizeof(adc_results)); // Fill result with invalid values

LOOP_L_N(pi, COUNT(adc_pins))
for (uint8_t pi = 0; pi < COUNT(adc_pins); ++pi)
pinPeripheral(adc_pins[pi], PIO_ANALOG);

LOOP_S_LE_N(ai, FIRST_ADC, LAST_ADC) {
for (uint8_t ai = FIRST_ADC; ai <= LAST_ADC; ++ai) {
Adc* adc = ((Adc*[])ADC_INSTS)[ai];

// ADC clock setup
Expand Down Expand Up @@ -685,7 +685,7 @@ void MarlinHAL::adc_init() {

void MarlinHAL::adc_start(const pin_t pin) {
#if ADC_IS_REQUIRED
LOOP_L_N(pi, COUNT(adc_pins))
for (uint8_t pi = 0; pi < COUNT(adc_pins); ++pi)
if (pin == adc_pins[pi]) { adc_result = adc_results[pi]; return; }
#endif

Expand Down
2 changes: 1 addition & 1 deletion Marlin/src/HAL/STM32/fastio.cpp
Expand Up @@ -29,7 +29,7 @@
GPIO_TypeDef* FastIOPortMap[LastPort + 1] = { 0 };

void FastIO_init() {
LOOP_L_N(i, NUM_DIGITAL_PINS)
for (uint8_t i = 0; i < NUM_DIGITAL_PINS; ++i)
FastIOPortMap[STM_PORT(digitalPin[i])] = get_GPIO_Port(STM_PORT(digitalPin[i]));
}

Expand Down
12 changes: 6 additions & 6 deletions Marlin/src/HAL/STM32/tft/gt911.cpp
Expand Up @@ -90,7 +90,7 @@ bool SW_IIC::read_ack() {
}

void SW_IIC::send_byte(uint8_t txd) {
LOOP_L_N(i, 8) {
for (uint8_t i = 0; i < 8; ++i) {
write_sda(txd & 0x80); // write data bit
txd <<= 1;
iic_delay(1);
Expand All @@ -107,7 +107,7 @@ uint8_t SW_IIC::read_byte(bool ack) {
uint8_t data = 0;

set_sda_in();
LOOP_L_N(i, 8) {
for (uint8_t i = 0; i < 8; ++i) {
write_scl(HIGH); // SCL = 1
iic_delay(1);
data <<= 1;
Expand All @@ -128,12 +128,12 @@ SW_IIC GT911::sw_iic = SW_IIC(GT911_SW_I2C_SDA_PIN, GT911_SW_I2C_SCL_PIN);
void GT911::write_reg(uint16_t reg, uint8_t reg_len, uint8_t* w_data, uint8_t w_len) {
sw_iic.start();
sw_iic.send_byte(gt911_slave_address); // Set IIC Slave address
LOOP_L_N(i, reg_len) { // Set reg address
for (uint8_t i = 0; i < reg_len; ++i) { // Set reg address
uint8_t r = (reg >> (8 * (reg_len - 1 - i))) & 0xFF;
sw_iic.send_byte(r);
}

LOOP_L_N(i, w_len) { // Write data to reg
for (uint8_t i = 0; i < w_len; ++i) { // Write data to reg
sw_iic.send_byte(w_data[i]);
}
sw_iic.stop();
Expand All @@ -142,15 +142,15 @@ void GT911::write_reg(uint16_t reg, uint8_t reg_len, uint8_t* w_data, uint8_t w_
void GT911::read_reg(uint16_t reg, uint8_t reg_len, uint8_t* r_data, uint8_t r_len) {
sw_iic.start();
sw_iic.send_byte(gt911_slave_address); // Set IIC Slave address
LOOP_L_N(i, reg_len) { // Set reg address
for (uint8_t i = 0; i < reg_len; ++i) { // Set reg address
uint8_t r = (reg >> (8 * (reg_len - 1 - i))) & 0xFF;
sw_iic.send_byte(r);
}

sw_iic.start();
sw_iic.send_byte(gt911_slave_address + 1); // Set read mode

LOOP_L_N(i, r_len)
for (uint8_t i = 0; i < r_len; ++i)
r_data[i] = sw_iic.read_byte(1); // Read data from reg

sw_iic.stop();
Expand Down
4 changes: 2 additions & 2 deletions Marlin/src/HAL/STM32/timers.cpp
Expand Up @@ -316,8 +316,8 @@ static constexpr struct { TimerPurpose p; int t; } timers_in_use[] = {
};

static constexpr bool verify_no_timer_conflicts() {
LOOP_L_N(i, COUNT(timers_in_use))
LOOP_S_L_N(j, i + 1, COUNT(timers_in_use))
for (uint8_t i = 0; i < COUNT(timers_in_use); ++i)
for (uint8_t j = i + 1; j < COUNT(timers_in_use); ++j)
if (timers_in_use[i].t == timers_in_use[j].t) return false;
return true;
}
Expand Down
16 changes: 8 additions & 8 deletions Marlin/src/HAL/STM32F1/dogm/u8g_com_stm32duino_swspi.cpp
Expand Up @@ -37,7 +37,7 @@
static uint8_t SPI_speed = LCD_SPI_SPEED;

static inline uint8_t swSpiTransfer_mode_0(uint8_t b, const uint8_t spi_speed, const pin_t miso_pin=-1) {
LOOP_L_N(i, 8) {
for (uint8_t i = 0; i < 8; ++i) {
if (spi_speed == 0) {
WRITE(DOGLCD_MOSI, !!(b & 0x80));
WRITE(DOGLCD_SCK, HIGH);
Expand All @@ -47,24 +47,24 @@ static inline uint8_t swSpiTransfer_mode_0(uint8_t b, const uint8_t spi_speed, c
}
else {
const uint8_t state = (b & 0x80) ? HIGH : LOW;
LOOP_L_N(j, spi_speed)
for (uint8_t j = 0; j < spi_speed; ++j)
WRITE(DOGLCD_MOSI, state);

LOOP_L_N(j, spi_speed + (miso_pin >= 0 ? 0 : 1))
for (uint8_t j = 0; j < spi_speed + (miso_pin >= 0 ? 0 : 1); ++j)
WRITE(DOGLCD_SCK, HIGH);

b <<= 1;
if (miso_pin >= 0 && READ(miso_pin)) b |= 1;

LOOP_L_N(j, spi_speed)
for (uint8_t j = 0; j < spi_speed; ++j)
WRITE(DOGLCD_SCK, LOW);
}
}
return b;
}

static inline uint8_t swSpiTransfer_mode_3(uint8_t b, const uint8_t spi_speed, const pin_t miso_pin=-1) {
LOOP_L_N(i, 8) {
for (uint8_t i = 0; i < 8; ++i) {
const uint8_t state = (b & 0x80) ? HIGH : LOW;
if (spi_speed == 0) {
WRITE(DOGLCD_SCK, LOW);
Expand All @@ -73,13 +73,13 @@ static inline uint8_t swSpiTransfer_mode_3(uint8_t b, const uint8_t spi_speed, c
WRITE(DOGLCD_SCK, HIGH);
}
else {
LOOP_L_N(j, spi_speed + (miso_pin >= 0 ? 0 : 1))
for (uint8_t j = 0; j < spi_speed + (miso_pin >= 0 ? 0 : 1); ++j)
WRITE(DOGLCD_SCK, LOW);

LOOP_L_N(j, spi_speed)
for (uint8_t j = 0; j < spi_speed; ++j)
WRITE(DOGLCD_MOSI, state);

LOOP_L_N(j, spi_speed)
for (uint8_t j = 0; j < spi_speed; ++j)
WRITE(DOGLCD_SCK, HIGH);
}
b <<= 1;
Expand Down
2 changes: 1 addition & 1 deletion Marlin/src/HAL/STM32F1/tft/tft_spi.cpp
Expand Up @@ -101,7 +101,7 @@ uint32_t TFT_SPI::ReadID(uint16_t Reg) {
DataTransferBegin(DATASIZE_8BIT);
WriteReg(Reg);

LOOP_L_N(i, 4) {
for (uint8_t i = 0; i < 4; ++i) {
uint8_t d;
SPIx.read(&d, 1);
data = (data << 8) | d;
Expand Down
2 changes: 1 addition & 1 deletion Marlin/src/HAL/shared/servo.cpp
Expand Up @@ -67,7 +67,7 @@ uint8_t ServoCount = 0; // the total number of attached

static bool anyTimerChannelActive(const timer16_Sequence_t timer) {
// returns true if any servo is active on this timer
LOOP_L_N(channel, SERVOS_PER_TIMER) {
for (uint8_t channel = 0; channel < SERVOS_PER_TIMER; ++channel) {
if (SERVO(timer, channel).Pin.isActive)
return true;
}
Expand Down

0 comments on commit 86c8116

Please sign in to comment.