~ruther/qmk_firmware

2d1aed78a67b3d2b002cc739ef087963b05b76b8 — Ryan 1 year, 2 months ago 6810aaf
Update GPIO macro usages in core (#23093)

61 files changed, 334 insertions(+), 334 deletions(-)

M drivers/bluetooth/bluefruit_le.cpp
M drivers/eeprom/eeprom_i2c.c
M drivers/gpio/sn74x138.c
M drivers/gpio/sn74x154.c
M drivers/haptic/solenoid.c
M drivers/lcd/hd44780.c
M drivers/lcd/st7565.c
M drivers/led/apa102.c
M drivers/led/aw20216s.c
M drivers/led/issi/is31fl3218-mono.c
M drivers/led/issi/is31fl3218.c
M drivers/led/issi/is31fl3731-mono.c
M drivers/led/issi/is31fl3731.c
M drivers/led/issi/is31fl3733-mono.c
M drivers/led/issi/is31fl3733.c
M drivers/led/issi/is31fl3736-mono.c
M drivers/led/issi/is31fl3736.c
M drivers/led/issi/is31fl3737-mono.c
M drivers/led/issi/is31fl3737.c
M drivers/led/issi/is31fl3741-mono.c
M drivers/led/issi/is31fl3741.c
M drivers/led/issi/is31fl3742a-mono.c
M drivers/led/issi/is31fl3742a.c
M drivers/led/issi/is31fl3743a-mono.c
M drivers/led/issi/is31fl3743a.c
M drivers/led/issi/is31fl3745-mono.c
M drivers/led/issi/is31fl3745.c
M drivers/led/issi/is31fl3746a-mono.c
M drivers/led/issi/is31fl3746a.c
M drivers/led/snled27351-mono.c
M drivers/led/snled27351.c
M drivers/oled/oled_driver.c
M drivers/painter/comms/qp_comms_spi.c
M drivers/sensors/adns5050.c
M drivers/sensors/adns9800.c
M drivers/sensors/analog_joystick.c
M drivers/sensors/paw3204.c
M drivers/sensors/pmw3320.c
M drivers/usb2422.c
M keyboards/handwired/onekey/keymaps/chibios_waiting_test/keymap.c
M platforms/avr/drivers/audio_pwm_hardware.c
M platforms/avr/drivers/backlight_pwm.c
M platforms/avr/drivers/ps2/ps2_io.c
M platforms/avr/drivers/serial.c
M platforms/avr/drivers/spi_master.c
M platforms/chibios/drivers/serial.c
M platforms/chibios/drivers/spi_master.c
M platforms/chibios/drivers/ws2812_bitbang.c
M quantum/backlight/backlight_driver_common.c
M quantum/dip_switch.c
M quantum/encoder.c
M quantum/haptic.c
M quantum/haptic.h
M quantum/joystick.c
M quantum/led.c
M quantum/matrix.c
M quantum/pointing_device/pointing_device.c
M quantum/split_common/split_util.c
M tmk_core/protocol/arm_atsam/shift_register.c
M tmk_core/protocol/arm_atsam/spi_master.c
M tmk_core/protocol/usb_util.c
M drivers/bluetooth/bluefruit_le.cpp => drivers/bluetooth/bluefruit_le.cpp +9 -9
@@ 188,7 188,7 @@ static bool sdep_recv_pkt(struct sdep_msg *msg, uint16_t timeout) {
    bool     ready      = false;

    do {
        ready = readPin(BLUEFRUIT_LE_IRQ_PIN);
        ready = gpio_read_pin(BLUEFRUIT_LE_IRQ_PIN);
        if (ready) {
            break;
        }


@@ 231,7 231,7 @@ static void resp_buf_read_one(bool greedy) {
        return;
    }

    if (readPin(BLUEFRUIT_LE_IRQ_PIN)) {
    if (gpio_read_pin(BLUEFRUIT_LE_IRQ_PIN)) {
        struct sdep_msg msg;

    again:


@@ 242,7 242,7 @@ static void resp_buf_read_one(bool greedy) {
                dprintf("recv latency %dms\n", TIMER_DIFF_16(timer_read(), last_send));
            }

            if (greedy && resp_buf.peek(last_send) && readPin(BLUEFRUIT_LE_IRQ_PIN)) {
            if (greedy && resp_buf.peek(last_send) && gpio_read_pin(BLUEFRUIT_LE_IRQ_PIN)) {
                goto again;
            }
        }


@@ 293,16 293,16 @@ void bluefruit_le_init(void) {
    state.configured   = false;
    state.is_connected = false;

    setPinInput(BLUEFRUIT_LE_IRQ_PIN);
    gpio_set_pin_input(BLUEFRUIT_LE_IRQ_PIN);

    spi_init();

    // Perform a hardware reset
    setPinOutput(BLUEFRUIT_LE_RST_PIN);
    writePinHigh(BLUEFRUIT_LE_RST_PIN);
    writePinLow(BLUEFRUIT_LE_RST_PIN);
    gpio_set_pin_output(BLUEFRUIT_LE_RST_PIN);
    gpio_write_pin_high(BLUEFRUIT_LE_RST_PIN);
    gpio_write_pin_low(BLUEFRUIT_LE_RST_PIN);
    wait_ms(10);
    writePinHigh(BLUEFRUIT_LE_RST_PIN);
    gpio_write_pin_high(BLUEFRUIT_LE_RST_PIN);

    wait_ms(1000); // Give it a second to initialize



@@ 508,7 508,7 @@ void bluefruit_le_task(void) {
    resp_buf_read_one(true);
    send_buf_send_one(SdepShortTimeout);

    if (resp_buf.empty() && (state.event_flags & UsingEvents) && readPin(BLUEFRUIT_LE_IRQ_PIN)) {
    if (resp_buf.empty() && (state.event_flags & UsingEvents) && gpio_read_pin(BLUEFRUIT_LE_IRQ_PIN)) {
        // Must be an event update
        if (at_command_P(PSTR("AT+EVENTSTATUS"), resbuf, sizeof(resbuf))) {
            uint32_t mask = strtoul(resbuf, NULL, 16);

M drivers/eeprom/eeprom_i2c.c => drivers/eeprom/eeprom_i2c.c +6 -6
@@ 57,8 57,8 @@ void eeprom_driver_init(void) {
    i2c_init();
#if defined(EXTERNAL_EEPROM_WP_PIN)
    /* We are setting the WP pin to high in a way that requires at least two bit-flips to change back to 0 */
    writePin(EXTERNAL_EEPROM_WP_PIN, 1);
    setPinInputHigh(EXTERNAL_EEPROM_WP_PIN);
    gpio_write_pin(EXTERNAL_EEPROM_WP_PIN, 1);
    gpio_set_pin_input_high(EXTERNAL_EEPROM_WP_PIN);
#endif
}



@@ 100,8 100,8 @@ void eeprom_write_block(const void *buf, void *addr, size_t len) {
    uintptr_t target_addr = (uintptr_t)addr;

#if defined(EXTERNAL_EEPROM_WP_PIN)
    setPinOutput(EXTERNAL_EEPROM_WP_PIN);
    writePin(EXTERNAL_EEPROM_WP_PIN, 0);
    gpio_set_pin_output(EXTERNAL_EEPROM_WP_PIN);
    gpio_write_pin(EXTERNAL_EEPROM_WP_PIN, 0);
#endif

    while (len > 0) {


@@ 134,7 134,7 @@ void eeprom_write_block(const void *buf, void *addr, size_t len) {

#if defined(EXTERNAL_EEPROM_WP_PIN)
    /* We are setting the WP pin to high in a way that requires at least two bit-flips to change back to 0 */
    writePin(EXTERNAL_EEPROM_WP_PIN, 1);
    setPinInputHigh(EXTERNAL_EEPROM_WP_PIN);
    gpio_write_pin(EXTERNAL_EEPROM_WP_PIN, 1);
    gpio_set_pin_input_high(EXTERNAL_EEPROM_WP_PIN);
#endif
}

M drivers/gpio/sn74x138.c => drivers/gpio/sn74x138.c +12 -12
@@ 27,39 27,39 @@ static const pin_t address_pins[ADDRESS_PIN_COUNT] = SN74X138_ADDRESS_PINS;

void sn74x138_init(void) {
    for (int i = 0; i < ADDRESS_PIN_COUNT; i++) {
        setPinOutput(address_pins[i]);
        writePinLow(address_pins[i]);
        gpio_set_pin_output(address_pins[i]);
        gpio_write_pin_low(address_pins[i]);
    }

#if defined(SN74X138_E1_PIN)
    setPinOutput(SN74X138_E1_PIN);
    writePinHigh(SN74X138_E1_PIN);
    gpio_set_pin_output(SN74X138_E1_PIN);
    gpio_write_pin_high(SN74X138_E1_PIN);
#endif

#if defined(SN74X138_E2_PIN)
    setPinOutput(SN74X138_E2_PIN);
    writePinHigh(SN74X138_E2_PIN);
    gpio_set_pin_output(SN74X138_E2_PIN);
    gpio_write_pin_high(SN74X138_E2_PIN);
#endif
#if defined(SN74X138_E3_PIN)
    setPinOutput(SN74X138_E3_PIN);
    writePinLow(SN74X138_E3_PIN);
    gpio_set_pin_output(SN74X138_E3_PIN);
    gpio_write_pin_low(SN74X138_E3_PIN);
#endif
}

void sn74x138_set_enabled(bool enabled) {
#if defined(SN74X138_E1_PIN)
    writePin(SN74X138_E1_PIN, !enabled);
    gpio_write_pin(SN74X138_E1_PIN, !enabled);
#endif
#if defined(SN74X138_E2_PIN)
    writePin(SN74X138_E2_PIN, !enabled);
    gpio_write_pin(SN74X138_E2_PIN, !enabled);
#endif
#if defined(SN74X138_E3_PIN)
    writePin(SN74X138_E3_PIN, enabled);
    gpio_write_pin(SN74X138_E3_PIN, enabled);
#endif
}

void sn74x138_set_addr(uint8_t address) {
    for (int i = 0; i < ADDRESS_PIN_COUNT; i++) {
        writePin(address_pins[i], address & (1 << i));
        gpio_write_pin(address_pins[i], address & (1 << i));
    }
}

M drivers/gpio/sn74x154.c => drivers/gpio/sn74x154.c +9 -9
@@ 27,32 27,32 @@ static const pin_t address_pins[ADDRESS_PIN_COUNT] = SN74X154_ADDRESS_PINS;

void sn74x154_init(void) {
    for (int i = 0; i < ADDRESS_PIN_COUNT; i++) {
        setPinOutput(address_pins[i]);
        writePinLow(address_pins[i]);
        gpio_set_pin_output(address_pins[i]);
        gpio_write_pin_low(address_pins[i]);
    }

#if defined(SN74X154_E0_PIN)
    setPinOutput(SN74X154_E0_PIN);
    writePinHigh(SN74X154_E0_PIN);
    gpio_set_pin_output(SN74X154_E0_PIN);
    gpio_write_pin_high(SN74X154_E0_PIN);
#endif

#if defined(SN74X154_E1_PIN)
    setPinOutput(SN74X154_E1_PIN);
    writePinHigh(SN74X154_E1_PIN);
    gpio_set_pin_output(SN74X154_E1_PIN);
    gpio_write_pin_high(SN74X154_E1_PIN);
#endif
}

void sn74x154_set_enabled(bool enabled) {
#if defined(SN74X154_E0_PIN)
    writePin(SN74X154_E0_PIN, !enabled);
    gpio_write_pin(SN74X154_E0_PIN, !enabled);
#endif
#if defined(SN74X154_E1_PIN)
    writePin(SN74X154_E1_PIN, !enabled);
    gpio_write_pin(SN74X154_E1_PIN, !enabled);
#endif
}

void sn74x154_set_addr(uint8_t address) {
    for (int i = 0; i < ADDRESS_PIN_COUNT; i++) {
        writePin(address_pins[i], address & (1 << i));
        gpio_write_pin(address_pins[i], address & (1 << i));
    }
}

M drivers/haptic/solenoid.c => drivers/haptic/solenoid.c +7 -7
@@ 61,7 61,7 @@ void solenoid_set_dwell(uint8_t dwell) {
 * @param index select which solenoid to check/stop
 */
void solenoid_stop(uint8_t index) {
    writePin(solenoid_pads[index], !solenoid_active_state[index]);
    gpio_write_pin(solenoid_pads[index], !solenoid_active_state[index]);
    solenoid_on[index]      = false;
    solenoid_buzzing[index] = false;
}


@@ 78,7 78,7 @@ void solenoid_fire(uint8_t index) {
    solenoid_on[index]      = true;
    solenoid_buzzing[index] = true;
    solenoid_start[index]   = timer_read();
    writePin(solenoid_pads[index], solenoid_active_state[index]);
    gpio_write_pin(solenoid_pads[index], solenoid_active_state[index]);
}

/**


@@ 128,12 128,12 @@ void solenoid_check(void) {
            if ((elapsed[i] % (SOLENOID_BUZZ_ACTUATED + SOLENOID_BUZZ_NONACTUATED)) < SOLENOID_BUZZ_ACTUATED) {
                if (!solenoid_buzzing[i]) {
                    solenoid_buzzing[i] = true;
                    writePin(solenoid_pads[i], solenoid_active_state[i]);
                    gpio_write_pin(solenoid_pads[i], solenoid_active_state[i]);
                }
            } else {
                if (solenoid_buzzing[i]) {
                    solenoid_buzzing[i] = false;
                    writePin(solenoid_pads[i], !solenoid_active_state[i]);
                    gpio_write_pin(solenoid_pads[i], !solenoid_active_state[i]);
                }
            }
        }


@@ 156,8 156,8 @@ void solenoid_setup(void) {
#else
        solenoid_active_state[i] = high;
#endif
        writePin(solenoid_pads[i], !solenoid_active_state[i]);
        setPinOutput(solenoid_pads[i]);
        gpio_write_pin(solenoid_pads[i], !solenoid_active_state[i]);
        gpio_set_pin_output(solenoid_pads[i]);
        if ((!HAPTIC_OFF_IN_LOW_POWER) || (usb_device_state == USB_DEVICE_STATE_CONFIGURED)) {
            solenoid_fire(i);
        }


@@ 170,6 170,6 @@ void solenoid_setup(void) {
 */
void solenoid_shutdown(void) {
    for (uint8_t i = 0; i < NUMBER_OF_SOLENOIDS; i++) {
        writePin(solenoid_pads[i], !solenoid_active_state[i]);
        gpio_write_pin(solenoid_pads[i], !solenoid_active_state[i]);
    }
}

M drivers/lcd/hd44780.c => drivers/lcd/hd44780.c +24 -24
@@ 57,67 57,67 @@ static const pin_t data_pins[4] = HD44780_DATA_PINS;
#define HD44780_ENABLE_DELAY_US 1

static void hd44780_latch(void) {
    writePinHigh(HD44780_E_PIN);
    gpio_write_pin_high(HD44780_E_PIN);
    wait_us(HD44780_ENABLE_DELAY_US);
    writePinLow(HD44780_E_PIN);
    gpio_write_pin_low(HD44780_E_PIN);
}

void hd44780_write(uint8_t data, bool isData) {
    writePin(HD44780_RS_PIN, isData);
    writePinLow(HD44780_RW_PIN);
    gpio_write_pin(HD44780_RS_PIN, isData);
    gpio_write_pin_low(HD44780_RW_PIN);

    for (int i = 0; i < 4; i++) {
        setPinOutput(data_pins[i]);
        gpio_set_pin_output(data_pins[i]);
    }

    // Write high nibble
    for (int i = 0; i < 4; i++) {
        writePin(data_pins[i], (data >> 4) & (1 << i));
        gpio_write_pin(data_pins[i], (data >> 4) & (1 << i));
    }
    hd44780_latch();

    // Write low nibble
    for (int i = 0; i < 4; i++) {
        writePin(data_pins[i], data & (1 << i));
        gpio_write_pin(data_pins[i], data & (1 << i));
    }
    hd44780_latch();

    for (int i = 0; i < 4; i++) {
        writePinHigh(data_pins[i]);
        gpio_write_pin_high(data_pins[i]);
    }
}

uint8_t hd44780_read(bool isData) {
    uint8_t data = 0;

    writePin(HD44780_RS_PIN, isData);
    writePinHigh(HD44780_RW_PIN);
    gpio_write_pin(HD44780_RS_PIN, isData);
    gpio_write_pin_high(HD44780_RW_PIN);

    for (int i = 0; i < 4; i++) {
        setPinInput(data_pins[i]);
        gpio_set_pin_input(data_pins[i]);
    }

    writePinHigh(HD44780_E_PIN);
    gpio_write_pin_high(HD44780_E_PIN);
    wait_us(HD44780_ENABLE_DELAY_US);

    // Read high nibble
    for (int i = 0; i < 4; i++) {
        data |= (readPin(data_pins[i]) << i);
        data |= (gpio_read_pin(data_pins[i]) << i);
    }

    data <<= 4;

    writePinLow(HD44780_E_PIN);
    gpio_write_pin_low(HD44780_E_PIN);
    wait_us(HD44780_ENABLE_DELAY_US);
    writePinHigh(HD44780_E_PIN);
    gpio_write_pin_high(HD44780_E_PIN);
    wait_us(HD44780_ENABLE_DELAY_US);

    // Read low nibble
    for (int i = 0; i < 4; i++) {
        data |= (readPin(data_pins[i]) << i);
        data |= (gpio_read_pin(data_pins[i]) << i);
    }

    writePinLow(HD44780_E_PIN);
    gpio_write_pin_low(HD44780_E_PIN);

    return data;
}


@@ 171,20 171,20 @@ void hd44780_set_ddram_address(uint8_t address) {
}

void hd44780_init(bool cursor, bool blink) {
    setPinOutput(HD44780_RS_PIN);
    setPinOutput(HD44780_RW_PIN);
    setPinOutput(HD44780_E_PIN);
    gpio_set_pin_output(HD44780_RS_PIN);
    gpio_set_pin_output(HD44780_RW_PIN);
    gpio_set_pin_output(HD44780_E_PIN);

    for (int i = 0; i < 4; i++) {
        setPinOutput(data_pins[i]);
        gpio_set_pin_output(data_pins[i]);
    }

    wait_ms(HD44780_INIT_DELAY_MS);

    // Manually configure for 4-bit mode - can't use hd44780_command() yet
    // HD44780U datasheet, Fig. 24 (p46)
    writePinHigh(data_pins[0]); // Function set
    writePinHigh(data_pins[1]); // DL = 1
    gpio_write_pin_high(data_pins[0]); // Function set
    gpio_write_pin_high(data_pins[1]); // DL = 1
    hd44780_latch();
    wait_ms(5);
    // Send again


@@ 194,7 194,7 @@ void hd44780_init(bool cursor, bool blink) {
    hd44780_latch();
    wait_us(64);

    writePinLow(data_pins[0]); // DL = 0
    gpio_write_pin_low(data_pins[0]); // DL = 0
    hd44780_latch();
    wait_us(64);


M drivers/lcd/st7565.c => drivers/lcd/st7565.c +8 -8
@@ 92,10 92,10 @@ static void InvertCharacter(uint8_t *cursor) {
}

bool st7565_init(display_rotation_t rotation) {
    setPinOutput(ST7565_A0_PIN);
    writePinHigh(ST7565_A0_PIN);
    setPinOutput(ST7565_RST_PIN);
    writePinHigh(ST7565_RST_PIN);
    gpio_set_pin_output(ST7565_A0_PIN);
    gpio_write_pin_high(ST7565_A0_PIN);
    gpio_set_pin_output(ST7565_RST_PIN);
    gpio_write_pin_high(ST7565_RST_PIN);

    st7565_rotation = st7565_init_user(rotation);



@@ 488,18 488,18 @@ void st7565_task(void) {
__attribute__((weak)) void st7565_task_user(void) {}

void st7565_reset(void) {
    writePinLow(ST7565_RST_PIN);
    gpio_write_pin_low(ST7565_RST_PIN);
    wait_ms(20);
    writePinHigh(ST7565_RST_PIN);
    gpio_write_pin_high(ST7565_RST_PIN);
    wait_ms(20);
}

spi_status_t st7565_send_cmd(uint8_t cmd) {
    writePinLow(ST7565_A0_PIN);
    gpio_write_pin_low(ST7565_A0_PIN);
    return spi_write(cmd);
}

spi_status_t st7565_send_data(uint8_t *data, uint16_t length) {
    writePinHigh(ST7565_A0_PIN);
    gpio_write_pin_high(ST7565_A0_PIN);
    return spi_transmit(data, length);
}

M drivers/led/apa102.c => drivers/led/apa102.c +12 -12
@@ 43,14 43,14 @@
        }                                       \
    } while (0)

#define APA102_SEND_BIT(byte, bit)                  \
    do {                                            \
        writePin(APA102_DI_PIN, (byte >> bit) & 1); \
        io_wait;                                    \
        writePinHigh(APA102_CI_PIN);                \
        io_wait;                                    \
        writePinLow(APA102_CI_PIN);                 \
        io_wait;                                    \
#define APA102_SEND_BIT(byte, bit)                        \
    do {                                                  \
        gpio_write_pin(APA102_DI_PIN, (byte >> bit) & 1); \
        io_wait;                                          \
        gpio_write_pin_high(APA102_CI_PIN);               \
        io_wait;                                          \
        gpio_write_pin_low(APA102_CI_PIN);                \
        io_wait;                                          \
    } while (0)

uint8_t apa102_led_brightness = APA102_DEFAULT_BRIGHTNESS;


@@ 114,11 114,11 @@ static void apa102_send_frame(uint8_t red, uint8_t green, uint8_t blue, uint8_t 
}

void apa102_init(void) {
    setPinOutput(APA102_DI_PIN);
    setPinOutput(APA102_CI_PIN);
    gpio_set_pin_output(APA102_DI_PIN);
    gpio_set_pin_output(APA102_CI_PIN);

    writePinLow(APA102_DI_PIN);
    writePinLow(APA102_CI_PIN);
    gpio_write_pin_low(APA102_DI_PIN);
    gpio_write_pin_low(APA102_CI_PIN);
}

void apa102_setleds(rgb_led_t *start_led, uint16_t num_leds) {

M drivers/led/aw20216s.c => drivers/led/aw20216s.c +2 -2
@@ 114,8 114,8 @@ void aw20216s_init_drivers(void) {
    spi_init();

#if defined(AW20216S_EN_PIN)
    setPinOutput(AW20216S_EN_PIN);
    writePinHigh(AW20216S_EN_PIN);
    gpio_set_pin_output(AW20216S_EN_PIN);
    gpio_write_pin_high(AW20216S_EN_PIN);
#endif

    aw20216s_init(AW20216S_CS_PIN_1);

M drivers/led/issi/is31fl3218-mono.c => drivers/led/issi/is31fl3218-mono.c +2 -2
@@ 68,8 68,8 @@ void is31fl3218_init(void) {
    i2c_init();

#if defined(IS31FL3218_SDB_PIN)
    setPinOutput(IS31FL3218_SDB_PIN);
    writePinHigh(IS31FL3218_SDB_PIN);
    gpio_set_pin_output(IS31FL3218_SDB_PIN);
    gpio_write_pin_high(IS31FL3218_SDB_PIN);
#endif

    // In case we ever want to reinitialize (?)

M drivers/led/issi/is31fl3218.c => drivers/led/issi/is31fl3218.c +2 -2
@@ 68,8 68,8 @@ void is31fl3218_init(void) {
    i2c_init();

#if defined(IS31FL3218_SDB_PIN)
    setPinOutput(IS31FL3218_SDB_PIN);
    writePinHigh(IS31FL3218_SDB_PIN);
    gpio_set_pin_output(IS31FL3218_SDB_PIN);
    gpio_write_pin_high(IS31FL3218_SDB_PIN);
#endif

    // In case we ever want to reinitialize (?)

M drivers/led/issi/is31fl3731-mono.c => drivers/led/issi/is31fl3731-mono.c +2 -2
@@ 99,8 99,8 @@ void is31fl3731_init_drivers(void) {
    i2c_init();

#if defined(IS31FL3731_SDB_PIN)
    setPinOutput(IS31FL3731_SDB_PIN);
    writePinHigh(IS31FL3731_SDB_PIN);
    gpio_set_pin_output(IS31FL3731_SDB_PIN);
    gpio_write_pin_high(IS31FL3731_SDB_PIN);
#endif

    for (uint8_t i = 0; i < IS31FL3731_DRIVER_COUNT; i++) {

M drivers/led/issi/is31fl3731.c => drivers/led/issi/is31fl3731.c +2 -2
@@ 98,8 98,8 @@ void is31fl3731_init_drivers(void) {
    i2c_init();

#if defined(IS31FL3731_SDB_PIN)
    setPinOutput(IS31FL3731_SDB_PIN);
    writePinHigh(IS31FL3731_SDB_PIN);
    gpio_set_pin_output(IS31FL3731_SDB_PIN);
    gpio_write_pin_high(IS31FL3731_SDB_PIN);
#endif

    for (uint8_t i = 0; i < IS31FL3731_DRIVER_COUNT; i++) {

M drivers/led/issi/is31fl3733-mono.c => drivers/led/issi/is31fl3733-mono.c +2 -2
@@ 144,8 144,8 @@ void is31fl3733_init_drivers(void) {
    i2c_init();

#if defined(IS31FL3733_SDB_PIN)
    setPinOutput(IS31FL3733_SDB_PIN);
    writePinHigh(IS31FL3733_SDB_PIN);
    gpio_set_pin_output(IS31FL3733_SDB_PIN);
    gpio_write_pin_high(IS31FL3733_SDB_PIN);
#endif

    for (uint8_t i = 0; i < IS31FL3733_DRIVER_COUNT; i++) {

M drivers/led/issi/is31fl3733.c => drivers/led/issi/is31fl3733.c +2 -2
@@ 143,8 143,8 @@ void is31fl3733_init_drivers(void) {
    i2c_init();

#if defined(IS31FL3733_SDB_PIN)
    setPinOutput(IS31FL3733_SDB_PIN);
    writePinHigh(IS31FL3733_SDB_PIN);
    gpio_set_pin_output(IS31FL3733_SDB_PIN);
    gpio_write_pin_high(IS31FL3733_SDB_PIN);
#endif

    for (uint8_t i = 0; i < IS31FL3733_DRIVER_COUNT; i++) {

M drivers/led/issi/is31fl3736-mono.c => drivers/led/issi/is31fl3736-mono.c +2 -2
@@ 115,8 115,8 @@ void is31fl3736_init_drivers(void) {
    i2c_init();

#if defined(IS31FL3736_SDB_PIN)
    setPinOutput(IS31FL3736_SDB_PIN);
    writePinHigh(IS31FL3736_SDB_PIN);
    gpio_set_pin_output(IS31FL3736_SDB_PIN);
    gpio_write_pin_high(IS31FL3736_SDB_PIN);
#endif

    for (uint8_t i = 0; i < IS31FL3736_DRIVER_COUNT; i++) {

M drivers/led/issi/is31fl3736.c => drivers/led/issi/is31fl3736.c +2 -2
@@ 115,8 115,8 @@ void is31fl3736_init_drivers(void) {
    i2c_init();

#if defined(IS31FL3736_SDB_PIN)
    setPinOutput(IS31FL3736_SDB_PIN);
    writePinHigh(IS31FL3736_SDB_PIN);
    gpio_set_pin_output(IS31FL3736_SDB_PIN);
    gpio_write_pin_high(IS31FL3736_SDB_PIN);
#endif

    for (uint8_t i = 0; i < IS31FL3736_DRIVER_COUNT; i++) {

M drivers/led/issi/is31fl3737-mono.c => drivers/led/issi/is31fl3737-mono.c +2 -2
@@ 117,8 117,8 @@ void is31fl3737_init_drivers(void) {
    i2c_init();

#if defined(IS31FL3737_SDB_PIN)
    setPinOutput(IS31FL3737_SDB_PIN);
    writePinHigh(IS31FL3737_SDB_PIN);
    gpio_set_pin_output(IS31FL3737_SDB_PIN);
    gpio_write_pin_high(IS31FL3737_SDB_PIN);
#endif

    for (uint8_t i = 0; i < IS31FL3737_DRIVER_COUNT; i++) {

M drivers/led/issi/is31fl3737.c => drivers/led/issi/is31fl3737.c +2 -2
@@ 117,8 117,8 @@ void is31fl3737_init_drivers(void) {
    i2c_init();

#if defined(IS31FL3737_SDB_PIN)
    setPinOutput(IS31FL3737_SDB_PIN);
    writePinHigh(IS31FL3737_SDB_PIN);
    gpio_set_pin_output(IS31FL3737_SDB_PIN);
    gpio_write_pin_high(IS31FL3737_SDB_PIN);
#endif

    for (uint8_t i = 0; i < IS31FL3737_DRIVER_COUNT; i++) {

M drivers/led/issi/is31fl3741-mono.c => drivers/led/issi/is31fl3741-mono.c +2 -2
@@ 143,8 143,8 @@ void is31fl3741_init_drivers(void) {
    i2c_init();

#if defined(IS31FL3741_SDB_PIN)
    setPinOutput(IS31FL3741_SDB_PIN);
    writePinHigh(IS31FL3741_SDB_PIN);
    gpio_set_pin_output(IS31FL3741_SDB_PIN);
    gpio_write_pin_high(IS31FL3741_SDB_PIN);
#endif

    for (uint8_t i = 0; i < IS31FL3741_DRIVER_COUNT; i++) {

M drivers/led/issi/is31fl3741.c => drivers/led/issi/is31fl3741.c +2 -2
@@ 143,8 143,8 @@ void is31fl3741_init_drivers(void) {
    i2c_init();

#if defined(IS31FL3741_SDB_PIN)
    setPinOutput(IS31FL3741_SDB_PIN);
    writePinHigh(IS31FL3741_SDB_PIN);
    gpio_set_pin_output(IS31FL3741_SDB_PIN);
    gpio_write_pin_high(IS31FL3741_SDB_PIN);
#endif

    for (uint8_t i = 0; i < IS31FL3741_DRIVER_COUNT; i++) {

M drivers/led/issi/is31fl3742a-mono.c => drivers/led/issi/is31fl3742a-mono.c +2 -2
@@ 116,8 116,8 @@ void is31fl3742a_init_drivers(void) {
    i2c_init();

#if defined(IS31FL3742A_SDB_PIN)
    setPinOutput(IS31FL3742A_SDB_PIN);
    writePinHigh(IS31FL3742A_SDB_PIN);
    gpio_set_pin_output(IS31FL3742A_SDB_PIN);
    gpio_write_pin_high(IS31FL3742A_SDB_PIN);
#endif

    for (uint8_t i = 0; i < IS31FL3742A_DRIVER_COUNT; i++) {

M drivers/led/issi/is31fl3742a.c => drivers/led/issi/is31fl3742a.c +2 -2
@@ 116,8 116,8 @@ void is31fl3742a_init_drivers(void) {
    i2c_init();

#if defined(IS31FL3742A_SDB_PIN)
    setPinOutput(IS31FL3742A_SDB_PIN);
    writePinHigh(IS31FL3742A_SDB_PIN);
    gpio_set_pin_output(IS31FL3742A_SDB_PIN);
    gpio_write_pin_high(IS31FL3742A_SDB_PIN);
#endif

    for (uint8_t i = 0; i < IS31FL3742A_DRIVER_COUNT; i++) {

M drivers/led/issi/is31fl3743a-mono.c => drivers/led/issi/is31fl3743a-mono.c +2 -2
@@ 138,8 138,8 @@ void is31fl3743a_init_drivers(void) {
    i2c_init();

#if defined(IS31FL3743A_SDB_PIN)
    setPinOutput(IS31FL3743A_SDB_PIN);
    writePinHigh(IS31FL3743A_SDB_PIN);
    gpio_set_pin_output(IS31FL3743A_SDB_PIN);
    gpio_write_pin_high(IS31FL3743A_SDB_PIN);
#endif

    for (uint8_t i = 0; i < IS31FL3743A_DRIVER_COUNT; i++) {

M drivers/led/issi/is31fl3743a.c => drivers/led/issi/is31fl3743a.c +2 -2
@@ 138,8 138,8 @@ void is31fl3743a_init_drivers(void) {
    i2c_init();

#if defined(IS31FL3743A_SDB_PIN)
    setPinOutput(IS31FL3743A_SDB_PIN);
    writePinHigh(IS31FL3743A_SDB_PIN);
    gpio_set_pin_output(IS31FL3743A_SDB_PIN);
    gpio_write_pin_high(IS31FL3743A_SDB_PIN);
#endif

    for (uint8_t i = 0; i < IS31FL3743A_DRIVER_COUNT; i++) {

M drivers/led/issi/is31fl3745-mono.c => drivers/led/issi/is31fl3745-mono.c +2 -2
@@ 138,8 138,8 @@ void is31fl3745_init_drivers(void) {
    i2c_init();

#if defined(IS31FL3745_SDB_PIN)
    setPinOutput(IS31FL3745_SDB_PIN);
    writePinHigh(IS31FL3745_SDB_PIN);
    gpio_set_pin_output(IS31FL3745_SDB_PIN);
    gpio_write_pin_high(IS31FL3745_SDB_PIN);
#endif

    for (uint8_t i = 0; i < IS31FL3745_DRIVER_COUNT; i++) {

M drivers/led/issi/is31fl3745.c => drivers/led/issi/is31fl3745.c +2 -2
@@ 138,8 138,8 @@ void is31fl3745_init_drivers(void) {
    i2c_init();

#if defined(IS31FL3745_SDB_PIN)
    setPinOutput(IS31FL3745_SDB_PIN);
    writePinHigh(IS31FL3745_SDB_PIN);
    gpio_set_pin_output(IS31FL3745_SDB_PIN);
    gpio_write_pin_high(IS31FL3745_SDB_PIN);
#endif

    for (uint8_t i = 0; i < IS31FL3745_DRIVER_COUNT; i++) {

M drivers/led/issi/is31fl3746a-mono.c => drivers/led/issi/is31fl3746a-mono.c +2 -2
@@ 116,8 116,8 @@ void is31fl3746a_init_drivers(void) {
    i2c_init();

#if defined(IS31FL3746A_SDB_PIN)
    setPinOutput(IS31FL3746A_SDB_PIN);
    writePinHigh(IS31FL3746A_SDB_PIN);
    gpio_set_pin_output(IS31FL3746A_SDB_PIN);
    gpio_write_pin_high(IS31FL3746A_SDB_PIN);
#endif

    for (uint8_t i = 0; i < IS31FL3746A_DRIVER_COUNT; i++) {

M drivers/led/issi/is31fl3746a.c => drivers/led/issi/is31fl3746a.c +2 -2
@@ 116,8 116,8 @@ void is31fl3746a_init_drivers(void) {
    i2c_init();

#if defined(IS31FL3746A_SDB_PIN)
    setPinOutput(IS31FL3746A_SDB_PIN);
    writePinHigh(IS31FL3746A_SDB_PIN);
    gpio_set_pin_output(IS31FL3746A_SDB_PIN);
    gpio_write_pin_high(IS31FL3746A_SDB_PIN);
#endif

    for (uint8_t i = 0; i < IS31FL3746A_DRIVER_COUNT; i++) {

M drivers/led/snled27351-mono.c => drivers/led/snled27351-mono.c +2 -2
@@ 105,8 105,8 @@ void snled27351_init_drivers(void) {
    i2c_init();

#if defined(SNLED27351_SDB_PIN)
    setPinOutput(SNLED27351_SDB_PIN);
    writePinHigh(SNLED27351_SDB_PIN);
    gpio_set_pin_output(SNLED27351_SDB_PIN);
    gpio_write_pin_high(SNLED27351_SDB_PIN);
#endif

    for (uint8_t i = 0; i < SNLED27351_DRIVER_COUNT; i++) {

M drivers/led/snled27351.c => drivers/led/snled27351.c +2 -2
@@ 105,8 105,8 @@ void snled27351_init_drivers(void) {
    i2c_init();

#if defined(SNLED27351_SDB_PIN)
    setPinOutput(SNLED27351_SDB_PIN);
    writePinHigh(SNLED27351_SDB_PIN);
    gpio_set_pin_output(SNLED27351_SDB_PIN);
    gpio_write_pin_high(SNLED27351_SDB_PIN);
#endif

    for (uint8_t i = 0; i < SNLED27351_DRIVER_COUNT; i++) {

M drivers/oled/oled_driver.c => drivers/oled/oled_driver.c +10 -10
@@ 192,7 192,7 @@ __attribute__((weak)) bool oled_send_cmd(const uint8_t *data, uint16_t size) {
        return false;
    }
    // Command Mode
    writePinLow(OLED_DC_PIN);
    gpio_write_pin_low(OLED_DC_PIN);
    // Send the commands
    if (spi_transmit(&data[1], size - 1) != SPI_STATUS_SUCCESS) {
        spi_stop();


@@ 215,7 215,7 @@ __attribute__((weak)) bool oled_send_cmd_P(const uint8_t *data, uint16_t size) {
    }
    spi_status_t status = SPI_STATUS_SUCCESS;
    // Command Mode
    writePinLow(OLED_DC_PIN);
    gpio_write_pin_low(OLED_DC_PIN);
    // Send the commands
    for (uint16_t i = 1; i < size && status >= 0; i++) {
        status = spi_write(pgm_read_byte((const char *)&data[i]));


@@ 239,7 239,7 @@ __attribute__((weak)) bool oled_send_data(const uint8_t *data, uint16_t size) {
        return false;
    }
    // Data Mode
    writePinHigh(OLED_DC_PIN);
    gpio_write_pin_high(OLED_DC_PIN);
    // Send the commands
    if (spi_transmit(data, size) != SPI_STATUS_SUCCESS) {
        spi_stop();


@@ 256,17 256,17 @@ __attribute__((weak)) bool oled_send_data(const uint8_t *data, uint16_t size) {
__attribute__((weak)) void oled_driver_init(void) {
#if defined(OLED_TRANSPORT_SPI)
    spi_init();
    setPinOutput(OLED_CS_PIN);
    writePinHigh(OLED_CS_PIN);
    gpio_set_pin_output(OLED_CS_PIN);
    gpio_write_pin_high(OLED_CS_PIN);

    setPinOutput(OLED_DC_PIN);
    writePinLow(OLED_DC_PIN);
    gpio_set_pin_output(OLED_DC_PIN);
    gpio_write_pin_low(OLED_DC_PIN);
#    ifdef OLED_RST_PIN
    /* Reset device */
    setPinOutput(OLED_RST_PIN);
    writePinLow(OLED_RST_PIN);
    gpio_set_pin_output(OLED_RST_PIN);
    gpio_write_pin_low(OLED_RST_PIN);
    wait_ms(20);
    writePinHigh(OLED_RST_PIN);
    gpio_write_pin_high(OLED_RST_PIN);
    wait_ms(20);
#    endif
#elif defined(OLED_TRANSPORT_I2C)

M drivers/painter/comms/qp_comms_spi.c => drivers/painter/comms/qp_comms_spi.c +10 -10
@@ 17,8 17,8 @@ bool qp_comms_spi_init(painter_device_t device) {
    spi_init();

    // Set up CS as output high
    setPinOutput(comms_config->chip_select_pin);
    writePinHigh(comms_config->chip_select_pin);
    gpio_set_pin_output(comms_config->chip_select_pin);
    gpio_write_pin_high(comms_config->chip_select_pin);

    return true;
}


@@ 49,7 49,7 @@ void qp_comms_spi_stop(painter_device_t device) {
    painter_driver_t *     driver       = (painter_driver_t *)device;
    qp_comms_spi_config_t *comms_config = (qp_comms_spi_config_t *)driver->comms_config;
    spi_stop();
    writePinHigh(comms_config->chip_select_pin);
    gpio_write_pin_high(comms_config->chip_select_pin);
}

const painter_comms_vtable_t spi_comms_vtable = {


@@ 74,16 74,16 @@ bool qp_comms_spi_dc_reset_init(painter_device_t device) {

    // Set up D/C as output low, if specified
    if (comms_config->dc_pin != NO_PIN) {
        setPinOutput(comms_config->dc_pin);
        writePinLow(comms_config->dc_pin);
        gpio_set_pin_output(comms_config->dc_pin);
        gpio_write_pin_low(comms_config->dc_pin);
    }

    // Set up RST as output, if specified, performing a reset in the process
    if (comms_config->reset_pin != NO_PIN) {
        setPinOutput(comms_config->reset_pin);
        writePinLow(comms_config->reset_pin);
        gpio_set_pin_output(comms_config->reset_pin);
        gpio_write_pin_low(comms_config->reset_pin);
        wait_ms(20);
        writePinHigh(comms_config->reset_pin);
        gpio_write_pin_high(comms_config->reset_pin);
        wait_ms(20);
    }



@@ 93,14 93,14 @@ bool qp_comms_spi_dc_reset_init(painter_device_t device) {
uint32_t qp_comms_spi_dc_reset_send_data(painter_device_t device, const void *data, uint32_t byte_count) {
    painter_driver_t *              driver       = (painter_driver_t *)device;
    qp_comms_spi_dc_reset_config_t *comms_config = (qp_comms_spi_dc_reset_config_t *)driver->comms_config;
    writePinHigh(comms_config->dc_pin);
    gpio_write_pin_high(comms_config->dc_pin);
    return qp_comms_spi_send_data(device, data, byte_count);
}

void qp_comms_spi_dc_reset_send_command(painter_device_t device, uint8_t cmd) {
    painter_driver_t *              driver       = (painter_driver_t *)device;
    qp_comms_spi_dc_reset_config_t *comms_config = (qp_comms_spi_dc_reset_config_t *)driver->comms_config;
    writePinLow(comms_config->dc_pin);
    gpio_write_pin_low(comms_config->dc_pin);
    spi_write(cmd);
}


M drivers/sensors/adns5050.c => drivers/sensors/adns5050.c +16 -16
@@ 47,9 47,9 @@

void adns5050_init(void) {
    // Initialize the ADNS serial pins.
    setPinOutput(ADNS5050_SCLK_PIN);
    setPinOutput(ADNS5050_SDIO_PIN);
    setPinOutput(ADNS5050_CS_PIN);
    gpio_set_pin_output(ADNS5050_SCLK_PIN);
    gpio_set_pin_output(ADNS5050_SDIO_PIN);
    gpio_set_pin_output(ADNS5050_CS_PIN);

    // reboot the adns.
    // if the adns hasn't initialized yet, this is harmless.


@@ 69,30 69,30 @@ void adns5050_init(void) {
// Just as with the serial protocol, this is used by the slave to send a
// synchronization signal to the master.
void adns5050_sync(void) {
    writePinLow(ADNS5050_CS_PIN);
    gpio_write_pin_low(ADNS5050_CS_PIN);
    wait_us(1);
    writePinHigh(ADNS5050_CS_PIN);
    gpio_write_pin_high(ADNS5050_CS_PIN);
}

void adns5050_cs_select(void) {
    writePinLow(ADNS5050_CS_PIN);
    gpio_write_pin_low(ADNS5050_CS_PIN);
}

void adns5050_cs_deselect(void) {
    writePinHigh(ADNS5050_CS_PIN);
    gpio_write_pin_high(ADNS5050_CS_PIN);
}

uint8_t adns5050_serial_read(void) {
    setPinInput(ADNS5050_SDIO_PIN);
    gpio_set_pin_input(ADNS5050_SDIO_PIN);
    uint8_t byte = 0;

    for (uint8_t i = 0; i < 8; ++i) {
        writePinLow(ADNS5050_SCLK_PIN);
        gpio_write_pin_low(ADNS5050_SCLK_PIN);
        wait_us(1);

        byte = (byte << 1) | readPin(ADNS5050_SDIO_PIN);
        byte = (byte << 1) | gpio_read_pin(ADNS5050_SDIO_PIN);

        writePinHigh(ADNS5050_SCLK_PIN);
        gpio_write_pin_high(ADNS5050_SCLK_PIN);
        wait_us(1);
    }



@@ 100,19 100,19 @@ uint8_t adns5050_serial_read(void) {
}

void adns5050_serial_write(uint8_t data) {
    setPinOutput(ADNS5050_SDIO_PIN);
    gpio_set_pin_output(ADNS5050_SDIO_PIN);

    for (int8_t b = 7; b >= 0; b--) {
        writePinLow(ADNS5050_SCLK_PIN);
        gpio_write_pin_low(ADNS5050_SCLK_PIN);

        if (data & (1 << b))
            writePinHigh(ADNS5050_SDIO_PIN);
            gpio_write_pin_high(ADNS5050_SDIO_PIN);
        else
            writePinLow(ADNS5050_SDIO_PIN);
            gpio_write_pin_low(ADNS5050_SDIO_PIN);

        wait_us(2);

        writePinHigh(ADNS5050_SCLK_PIN);
        gpio_write_pin_high(ADNS5050_SCLK_PIN);
    }

    // tSWR. See page 15 of the ADNS spec sheet.

M drivers/sensors/adns9800.c => drivers/sensors/adns9800.c +1 -1
@@ 100,7 100,7 @@ uint8_t adns9800_read(uint8_t reg_addr) {
}

void adns9800_init(void) {
    setPinOutput(ADNS9800_CS_PIN);
    gpio_set_pin_output(ADNS9800_CS_PIN);

    spi_init();


M drivers/sensors/analog_joystick.c => drivers/sensors/analog_joystick.c +4 -4
@@ 122,17 122,17 @@ report_analog_joystick_t analog_joystick_read(void) {
        report.y   = axisToMouseComponent(ANALOG_JOYSTICK_Y_AXIS_PIN, yOrigin, maxCursorSpeed, 1);
    }
#ifdef ANALOG_JOYSTICK_CLICK_PIN
    report.button = !readPin(ANALOG_JOYSTICK_CLICK_PIN);
    report.button = !gpio_read_pin(ANALOG_JOYSTICK_CLICK_PIN);
#endif
    return report;
}

void analog_joystick_init(void) {
    setPinInputHigh(ANALOG_JOYSTICK_X_AXIS_PIN);
    setPinInputHigh(ANALOG_JOYSTICK_Y_AXIS_PIN);
    gpio_set_pin_input_high(ANALOG_JOYSTICK_X_AXIS_PIN);
    gpio_set_pin_input_high(ANALOG_JOYSTICK_Y_AXIS_PIN);

#ifdef ANALOG_JOYSTICK_CLICK_PIN
    setPinInputHigh(ANALOG_JOYSTICK_CLICK_PIN);
    gpio_set_pin_input_high(ANALOG_JOYSTICK_CLICK_PIN);
#endif
    // Account for drift
    xOrigin = analogReadPin(ANALOG_JOYSTICK_X_AXIS_PIN);

M drivers/sensors/paw3204.c => drivers/sensors/paw3204.c +12 -12
@@ 51,8 51,8 @@ uint8_t paw3204_read_reg(uint8_t reg_addr);
void    paw3204_write_reg(uint8_t reg_addr, uint8_t data);

void paw3204_init(void) {
    setPinOutput(PAW3204_SCLK_PIN);    // setclockpin to output
    setPinInputHigh(PAW3204_SDIO_PIN); // set datapin input high
    gpio_set_pin_output(PAW3204_SCLK_PIN);     // setclockpin to output
    gpio_set_pin_input_high(PAW3204_SDIO_PIN); // set datapin input high

    paw3204_write_reg(REG_SETUP, 0x86); // reset sensor and set 1600cpi
    wait_us(5);


@@ 64,16 64,16 @@ void paw3204_init(void) {
}

uint8_t paw3204_serial_read(void) {
    setPinInput(PAW3204_SDIO_PIN);
    gpio_set_pin_input(PAW3204_SDIO_PIN);
    uint8_t byte = 0;

    for (uint8_t i = 0; i < 8; ++i) {
        writePinLow(PAW3204_SCLK_PIN);
        gpio_write_pin_low(PAW3204_SCLK_PIN);
        wait_us(1);

        byte = (byte << 1) | readPin(PAW3204_SDIO_PIN);
        byte = (byte << 1) | gpio_read_pin(PAW3204_SDIO_PIN);

        writePinHigh(PAW3204_SCLK_PIN);
        gpio_write_pin_high(PAW3204_SCLK_PIN);
        wait_us(1);
    }



@@ 81,17 81,17 @@ uint8_t paw3204_serial_read(void) {
}

void paw3204_serial_write(uint8_t data) {
    writePinLow(PAW3204_SDIO_PIN);
    setPinOutput(PAW3204_SDIO_PIN);
    gpio_write_pin_low(PAW3204_SDIO_PIN);
    gpio_set_pin_output(PAW3204_SDIO_PIN);

    for (int8_t b = 7; b >= 0; b--) {
        writePinLow(PAW3204_SCLK_PIN);
        gpio_write_pin_low(PAW3204_SCLK_PIN);
        if (data & (1 << b)) {
            writePinHigh(PAW3204_SDIO_PIN);
            gpio_write_pin_high(PAW3204_SDIO_PIN);
        } else {
            writePinLow(PAW3204_SDIO_PIN);
            gpio_write_pin_low(PAW3204_SDIO_PIN);
        }
        writePinHigh(PAW3204_SCLK_PIN);
        gpio_write_pin_high(PAW3204_SCLK_PIN);
    }

    wait_us(4);

M drivers/sensors/pmw3320.c => drivers/sensors/pmw3320.c +16 -16
@@ 24,9 24,9 @@

void pmw3320_init(void) {
    // Initialize sensor serial pins.
    setPinOutput(PMW3320_SCLK_PIN);
    setPinOutput(PMW3320_SDIO_PIN);
    setPinOutput(PMW3320_CS_PIN);
    gpio_set_pin_output(PMW3320_SCLK_PIN);
    gpio_set_pin_output(PMW3320_SDIO_PIN);
    gpio_set_pin_output(PMW3320_CS_PIN);

    // reboot the sensor.
    pmw3320_write_reg(REG_Power_Up_Reset, 0x5a);


@@ 54,30 54,30 @@ void pmw3320_init(void) {
// Just as with the serial protocol, this is used by the slave to send a
// synchronization signal to the master.
void pmw3320_sync(void) {
    writePinLow(PMW3320_CS_PIN);
    gpio_write_pin_low(PMW3320_CS_PIN);
    wait_us(1);
    writePinHigh(PMW3320_CS_PIN);
    gpio_write_pin_high(PMW3320_CS_PIN);
}

void pmw3320_cs_select(void) {
    writePinLow(PMW3320_CS_PIN);
    gpio_write_pin_low(PMW3320_CS_PIN);
}

void pmw3320_cs_deselect(void) {
    writePinHigh(PMW3320_CS_PIN);
    gpio_write_pin_high(PMW3320_CS_PIN);
}

uint8_t pmw3320_serial_read(void) {
    setPinInput(PMW3320_SDIO_PIN);
    gpio_set_pin_input(PMW3320_SDIO_PIN);
    uint8_t byte = 0;

    for (uint8_t i = 0; i < 8; ++i) {
        writePinLow(PMW3320_SCLK_PIN);
        gpio_write_pin_low(PMW3320_SCLK_PIN);
        wait_us(1);

        byte = (byte << 1) | readPin(PMW3320_SDIO_PIN);
        byte = (byte << 1) | gpio_read_pin(PMW3320_SDIO_PIN);

        writePinHigh(PMW3320_SCLK_PIN);
        gpio_write_pin_high(PMW3320_SCLK_PIN);
        wait_us(1);
    }



@@ 85,19 85,19 @@ uint8_t pmw3320_serial_read(void) {
}

void pmw3320_serial_write(uint8_t data) {
    setPinOutput(PMW3320_SDIO_PIN);
    gpio_set_pin_output(PMW3320_SDIO_PIN);

    for (int8_t b = 7; b >= 0; b--) {
        writePinLow(PMW3320_SCLK_PIN);
        gpio_write_pin_low(PMW3320_SCLK_PIN);

        if (data & (1 << b))
            writePinHigh(PMW3320_SDIO_PIN);
            gpio_write_pin_high(PMW3320_SDIO_PIN);
        else
            writePinLow(PMW3320_SDIO_PIN);
            gpio_write_pin_low(PMW3320_SDIO_PIN);

        wait_us(2);

        writePinHigh(PMW3320_SCLK_PIN);
        gpio_write_pin_high(PMW3320_SCLK_PIN);
    }

    // This was taken from ADNS5050 driver.

M drivers/usb2422.c => drivers/usb2422.c +5 -5
@@ 346,10 346,10 @@ static void USB2422_write_block(void) {

void USB2422_init(void) {
#ifdef USB2422_RESET_PIN
    setPinOutput(USB2422_RESET_PIN);
    gpio_set_pin_output(USB2422_RESET_PIN);
#endif
#ifdef USB2422_ACTIVE_PIN
    setPinInput(USB2422_ACTIVE_PIN);
    gpio_set_pin_input(USB2422_ACTIVE_PIN);
#endif

    i2c_init(); // IC2 clk must be high at USB2422 reset release time to signal SMB configuration


@@ 387,15 387,15 @@ void USB2422_configure(void) {

void USB2422_reset(void) {
#ifdef USB2422_RESET_PIN
    writePinLow(USB2422_RESET_PIN);
    gpio_write_pin_low(USB2422_RESET_PIN);
    wait_us(2);
    writePinHigh(USB2422_RESET_PIN);
    gpio_write_pin_high(USB2422_RESET_PIN);
#endif
}

bool USB2422_active(void) {
#ifdef USB2422_ACTIVE_PIN
    return readPin(USB2422_ACTIVE_PIN);
    return gpio_read_pin(USB2422_ACTIVE_PIN);
#else
    return 1;
#endif

M keyboards/handwired/onekey/keymaps/chibios_waiting_test/keymap.c => keyboards/handwired/onekey/keymaps/chibios_waiting_test/keymap.c +6 -6
@@ 13,20 13,20 @@ static inline void chThdSleepMicroseconds(uint32_t us) {
#endif

void keyboard_post_init_user(void) {
    setPinOutput(QMK_WAITING_TEST_BUSY_PIN);
    setPinOutput(QMK_WAITING_TEST_YIELD_PIN);
    gpio_set_pin_output(QMK_WAITING_TEST_BUSY_PIN);
    gpio_set_pin_output(QMK_WAITING_TEST_YIELD_PIN);
}

static inline void wait_us_polling_with_strobe(uint32_t us) {
    writePinHigh(QMK_WAITING_TEST_BUSY_PIN);
    gpio_write_pin_high(QMK_WAITING_TEST_BUSY_PIN);
    wait_us(us);
    writePinLow(QMK_WAITING_TEST_BUSY_PIN);
    gpio_write_pin_low(QMK_WAITING_TEST_BUSY_PIN);
}

static inline void wait_us_yield_with_strobe(uint32_t us) {
    writePinHigh(QMK_WAITING_TEST_YIELD_PIN);
    gpio_write_pin_high(QMK_WAITING_TEST_YIELD_PIN);
    chThdSleepMicroseconds(us);
    writePinLow(QMK_WAITING_TEST_YIELD_PIN);
    gpio_write_pin_low(QMK_WAITING_TEST_YIELD_PIN);
}

static const uint32_t waiting_values[] = {0, 1, 5, 10, 25, 50, 100, 150, 200, 500, 1000};

M platforms/avr/drivers/audio_pwm_hardware.c => platforms/avr/drivers/audio_pwm_hardware.c +2 -2
@@ 216,12 216,12 @@ void channel_2_stop(void) {
void audio_driver_initialize(void) {
#ifdef AUDIO1_PIN_SET
    channel_1_stop();
    setPinOutput(AUDIO1_PIN);
    gpio_set_pin_output(AUDIO1_PIN);
#endif

#ifdef AUDIO2_PIN_SET
    channel_2_stop();
    setPinOutput(AUDIO2_PIN);
    gpio_set_pin_output(AUDIO2_PIN);
#endif

    // TCCR3A / TCCR3B: Timer/Counter #3 Control Registers TCCR3A/TCCR3B, TCCR1A/TCCR1B

M platforms/avr/drivers/backlight_pwm.c => platforms/avr/drivers/backlight_pwm.c +3 -3
@@ 291,11 291,11 @@ ISR(TIMERx_OVF_vect) {
#endif // BACKLIGHT_BREATHING

void backlight_init_ports(void) {
    setPinOutput(BACKLIGHT_PIN);
    gpio_set_pin_output(BACKLIGHT_PIN);
#if BACKLIGHT_ON_STATE == 1
    writePinLow(BACKLIGHT_PIN);
    gpio_write_pin_low(BACKLIGHT_PIN);
#else
    writePinHigh(BACKLIGHT_PIN);
    gpio_write_pin_high(BACKLIGHT_PIN);
#endif

    // I could write a wall of text here to explain... but TL;DW

M platforms/avr/drivers/ps2/ps2_io.c => platforms/avr/drivers/ps2/ps2_io.c +10 -10
@@ 19,18 19,18 @@ void clock_init(void) {}

void clock_lo(void) {
    // Transition from input with pull-up to output low via Hi-Z instead of output high
    writePinLow(PS2_CLOCK_PIN);
    setPinOutput(PS2_CLOCK_PIN);
    gpio_write_pin_low(PS2_CLOCK_PIN);
    gpio_set_pin_output(PS2_CLOCK_PIN);
}

void clock_hi(void) {
    setPinInputHigh(PS2_CLOCK_PIN);
    gpio_set_pin_input_high(PS2_CLOCK_PIN);
}

bool clock_in(void) {
    setPinInputHigh(PS2_CLOCK_PIN);
    gpio_set_pin_input_high(PS2_CLOCK_PIN);
    wait_us(1);
    return readPin(PS2_CLOCK_PIN);
    return gpio_read_pin(PS2_CLOCK_PIN);
}

/*


@@ 40,16 40,16 @@ void data_init(void) {}

void data_lo(void) {
    // Transition from input with pull-up to output low via Hi-Z instead of output high
    writePinLow(PS2_DATA_PIN);
    setPinOutput(PS2_DATA_PIN);
    gpio_write_pin_low(PS2_DATA_PIN);
    gpio_set_pin_output(PS2_DATA_PIN);
}

void data_hi(void) {
    setPinInputHigh(PS2_DATA_PIN);
    gpio_set_pin_input_high(PS2_DATA_PIN);
}

bool data_in(void) {
    setPinInputHigh(PS2_DATA_PIN);
    gpio_set_pin_input_high(PS2_DATA_PIN);
    wait_us(1);
    return readPin(PS2_DATA_PIN);
    return gpio_read_pin(PS2_DATA_PIN);
}

M platforms/avr/drivers/serial.c => platforms/avr/drivers/serial.c +5 -5
@@ 239,28 239,28 @@ inline static void serial_delay_half2(void) {

inline static void serial_output(void) ALWAYS_INLINE;
inline static void serial_output(void) {
    setPinOutput(SOFT_SERIAL_PIN);
    gpio_set_pin_output(SOFT_SERIAL_PIN);
}

// make the serial pin an input with pull-up resistor
inline static void serial_input_with_pullup(void) ALWAYS_INLINE;
inline static void serial_input_with_pullup(void) {
    setPinInputHigh(SOFT_SERIAL_PIN);
    gpio_set_pin_input_high(SOFT_SERIAL_PIN);
}

inline static uint8_t serial_read_pin(void) ALWAYS_INLINE;
inline static uint8_t serial_read_pin(void) {
    return !!readPin(SOFT_SERIAL_PIN);
    return !!gpio_read_pin(SOFT_SERIAL_PIN);
}

inline static void serial_low(void) ALWAYS_INLINE;
inline static void serial_low(void) {
    writePinLow(SOFT_SERIAL_PIN);
    gpio_write_pin_low(SOFT_SERIAL_PIN);
}

inline static void serial_high(void) ALWAYS_INLINE;
inline static void serial_high(void) {
    writePinHigh(SOFT_SERIAL_PIN);
    gpio_write_pin_high(SOFT_SERIAL_PIN);
}

void soft_serial_initiator_init(void) {

M platforms/avr/drivers/spi_master.c => platforms/avr/drivers/spi_master.c +8 -8
@@ 41,10 41,10 @@ static uint8_t currentSlaveConfig = 0;
static bool    currentSlave2X     = false;

void spi_init(void) {
    writePinHigh(SPI_SS_PIN);
    setPinOutput(SPI_SCK_PIN);
    setPinOutput(SPI_MOSI_PIN);
    setPinInput(SPI_MISO_PIN);
    gpio_write_pin_high(SPI_SS_PIN);
    gpio_set_pin_output(SPI_SCK_PIN);
    gpio_set_pin_output(SPI_MOSI_PIN);
    gpio_set_pin_input(SPI_MISO_PIN);

    SPCR = (_BV(SPE) | _BV(MSTR));
}


@@ 105,8 105,8 @@ bool spi_start(pin_t slavePin, bool lsbFirst, uint8_t mode, uint16_t divisor) {
        SPSR |= _BV(SPI2X);
    }
    currentSlavePin = slavePin;
    setPinOutput(currentSlavePin);
    writePinLow(currentSlavePin);
    gpio_set_pin_output(currentSlavePin);
    gpio_write_pin_low(currentSlavePin);

    return true;
}


@@ 169,8 169,8 @@ spi_status_t spi_receive(uint8_t *data, uint16_t length) {

void spi_stop(void) {
    if (currentSlavePin != NO_PIN) {
        setPinOutput(currentSlavePin);
        writePinHigh(currentSlavePin);
        gpio_set_pin_output(currentSlavePin);
        gpio_write_pin_high(currentSlavePin);
        currentSlavePin = NO_PIN;
        SPSR &= ~(_BV(SPI2X));
        SPCR &= ~(currentSlaveConfig);

M platforms/chibios/drivers/serial.c => platforms/chibios/drivers/serial.c +6 -6
@@ 62,25 62,25 @@ inline static void serial_delay_blip(void) {
    wait_us(1);
}
inline static void serial_output(void) {
    setPinOutput(SOFT_SERIAL_PIN);
    gpio_set_pin_output(SOFT_SERIAL_PIN);
}
inline static void serial_input(void) {
    setPinInputHigh(SOFT_SERIAL_PIN);
    gpio_set_pin_input_high(SOFT_SERIAL_PIN);
}
inline static bool serial_read_pin(void) {
    return !!readPin(SOFT_SERIAL_PIN);
    return !!gpio_read_pin(SOFT_SERIAL_PIN);
}
inline static void serial_low(void) {
    writePinLow(SOFT_SERIAL_PIN);
    gpio_write_pin_low(SOFT_SERIAL_PIN);
}
inline static void serial_high(void) {
    writePinHigh(SOFT_SERIAL_PIN);
    gpio_write_pin_high(SOFT_SERIAL_PIN);
}

void interrupt_handler(void *arg);

// Use thread + palWaitLineTimeout instead of palSetLineCallback
//  - Methods like setPinOutput and palEnableLineEvent/palDisableLineEvent
//  - Methods like gpio_set_pin_output and palEnableLineEvent/palDisableLineEvent
//    cause the interrupt to lock up, which would limit to only receiving data...
static THD_WORKING_AREA(waThread1, 128);
static THD_FUNCTION(Thread1, arg) {

M platforms/chibios/drivers/spi_master.c => platforms/chibios/drivers/spi_master.c +7 -7
@@ 32,12 32,12 @@ __attribute__((weak)) void spi_init(void) {
        is_initialised = true;

        // Try releasing special pins for a short time
        setPinInput(SPI_SCK_PIN);
        gpio_set_pin_input(SPI_SCK_PIN);
        if (SPI_MOSI_PIN != NO_PIN) {
            setPinInput(SPI_MOSI_PIN);
            gpio_set_pin_input(SPI_MOSI_PIN);
        }
        if (SPI_MISO_PIN != NO_PIN) {
            setPinInput(SPI_MISO_PIN);
            gpio_set_pin_input(SPI_MISO_PIN);
        }

        chThdSleepMilliseconds(10);


@@ 271,10 271,10 @@ bool spi_start(pin_t slavePin, bool lsbFirst, uint8_t mode, uint16_t divisor) {
#if SPI_SELECT_MODE == SPI_SELECT_MODE_PAD
    spiConfig.ssport = PAL_PORT(slavePin);
    spiConfig.sspad  = PAL_PAD(slavePin);
    setPinOutput(slavePin);
    gpio_set_pin_output(slavePin);
#elif SPI_SELECT_MODE == SPI_SELECT_MODE_NONE
    if (slavePin != NO_PIN) {
        setPinOutput(slavePin);
        gpio_set_pin_output(slavePin);
    }
#else
#    error "Unsupported SPI_SELECT_MODE"


@@ 284,7 284,7 @@ bool spi_start(pin_t slavePin, bool lsbFirst, uint8_t mode, uint16_t divisor) {
    spiSelect(&SPI_DRIVER);
#if SPI_SELECT_MODE == SPI_SELECT_MODE_NONE
    if (slavePin != NO_PIN) {
        writePinLow(slavePin);
        gpio_write_pin_low(slavePin);
    }
#endif



@@ 319,7 319,7 @@ void spi_stop(void) {
    if (spiStarted) {
#if SPI_SELECT_MODE == SPI_SELECT_MODE_NONE
        if (currentSlavePin != NO_PIN) {
            writePinHigh(currentSlavePin);
            gpio_write_pin_high(currentSlavePin);
        }
#endif
        spiUnselect(&SPI_DRIVER);

M platforms/chibios/drivers/ws2812_bitbang.c => platforms/chibios/drivers/ws2812_bitbang.c +4 -4
@@ 57,15 57,15 @@ void sendByte(uint8_t byte) {
        // using something like wait_ns(is_one ? T1L : T0L) here throws off timings
        if (is_one) {
            // 1
            writePinHigh(WS2812_DI_PIN);
            gpio_write_pin_high(WS2812_DI_PIN);
            wait_ns(WS2812_T1H);
            writePinLow(WS2812_DI_PIN);
            gpio_write_pin_low(WS2812_DI_PIN);
            wait_ns(WS2812_T1L);
        } else {
            // 0
            writePinHigh(WS2812_DI_PIN);
            gpio_write_pin_high(WS2812_DI_PIN);
            wait_ns(WS2812_T0H);
            writePinLow(WS2812_DI_PIN);
            gpio_write_pin_low(WS2812_DI_PIN);
            wait_ns(WS2812_T0L);
        }
    }

M quantum/backlight/backlight_driver_common.c => quantum/backlight/backlight_driver_common.c +5 -5
@@ 26,23 26,23 @@ static const pin_t backlight_pin = BACKLIGHT_PIN;

static inline void backlight_on(pin_t backlight_pin) {
#if BACKLIGHT_ON_STATE == 0
    writePinLow(backlight_pin);
    gpio_write_pin_low(backlight_pin);
#else
    writePinHigh(backlight_pin);
    gpio_write_pin_high(backlight_pin);
#endif
}

static inline void backlight_off(pin_t backlight_pin) {
#if BACKLIGHT_ON_STATE == 0
    writePinHigh(backlight_pin);
    gpio_write_pin_high(backlight_pin);
#else
    writePinLow(backlight_pin);
    gpio_write_pin_low(backlight_pin);
#endif
}

void backlight_pins_init(void) {
    // Setup backlight pin as output and output to off state.
    FOR_EACH_LED(setPinOutput(backlight_pin); backlight_off(backlight_pin);)
    FOR_EACH_LED(gpio_set_pin_output(backlight_pin); backlight_off(backlight_pin);)
}

void backlight_pins_on(void) {

M quantum/dip_switch.c => quantum/dip_switch.c +2 -2
@@ 94,7 94,7 @@ void dip_switch_init(void) {
    }
#    endif
    for (uint8_t i = 0; i < NUM_DIP_SWITCHES; i++) {
        setPinInputHigh(dip_switch_pad[i]);
        gpio_set_pin_input_high(dip_switch_pad[i]);
    }
    dip_switch_read(true);
#endif


@@ 123,7 123,7 @@ void dip_switch_read(bool forced) {

    for (uint8_t i = 0; i < NUM_DIP_SWITCHES; i++) {
#ifdef DIP_SWITCH_PINS
        dip_switch_state[i] = !readPin(dip_switch_pad[i]);
        dip_switch_state[i] = !gpio_read_pin(dip_switch_pad[i]);
#endif
#ifdef DIP_SWITCH_MATRIX_GRID
        dip_switch_state[i] = peek_matrix(dip_switch_pad[i].row, dip_switch_pad[i].col, read_raw);

M quantum/encoder.c => quantum/encoder.c +4 -4
@@ 162,12 162,12 @@ void encoder_init(void) {
#endif // defined(SPLIT_KEYBOARD) && defined(ENCODER_RESOLUTIONS)

    for (uint8_t i = 0; i < thisCount; i++) {
        setPinInputHigh(encoders_pad_a[i]);
        setPinInputHigh(encoders_pad_b[i]);
        gpio_set_pin_input_high(encoders_pad_a[i]);
        gpio_set_pin_input_high(encoders_pad_b[i]);
    }
    encoder_wait_pullup_charge();
    for (uint8_t i = 0; i < thisCount; i++) {
        encoder_state[i] = (readPin(encoders_pad_a[i]) << 0) | (readPin(encoders_pad_b[i]) << 1);
        encoder_state[i] = (gpio_read_pin(encoders_pad_a[i]) << 0) | (gpio_read_pin(encoders_pad_b[i]) << 1);
    }
}



@@ 247,7 247,7 @@ static bool encoder_update(uint8_t index, uint8_t state) {
bool encoder_read(void) {
    bool changed = false;
    for (uint8_t i = 0; i < thisCount; i++) {
        uint8_t new_status = (readPin(encoders_pad_a[i]) << 0) | (readPin(encoders_pad_b[i]) << 1);
        uint8_t new_status = (gpio_read_pin(encoders_pad_a[i]) << 0) | (gpio_read_pin(encoders_pad_b[i]) << 1);
        if ((encoder_state[i] & 0x3) != new_status) {
            encoder_state[i] <<= 2;
            encoder_state[i] |= new_status;

M quantum/haptic.c => quantum/haptic.c +4 -4
@@ 96,10 96,10 @@ void haptic_init(void) {
#endif
    eeconfig_debug_haptic();
#ifdef HAPTIC_ENABLE_PIN
    setPinOutput(HAPTIC_ENABLE_PIN);
    gpio_set_pin_output(HAPTIC_ENABLE_PIN);
#endif
#ifdef HAPTIC_ENABLE_STATUS_LED
    setPinOutput(HAPTIC_ENABLE_STATUS_LED);
    gpio_set_pin_output(HAPTIC_ENABLE_STATUS_LED);
#endif
}



@@ 356,9 356,9 @@ void haptic_shutdown(void) {
void haptic_notify_usb_device_state_change(void) {
    update_haptic_enable_gpios();
#if defined(HAPTIC_ENABLE_PIN)
    setPinOutput(HAPTIC_ENABLE_PIN);
    gpio_set_pin_output(HAPTIC_ENABLE_PIN);
#endif
#if defined(HAPTIC_ENABLE_STATUS_LED)
    setPinOutput(HAPTIC_ENABLE_STATUS_LED);
    gpio_set_pin_output(HAPTIC_ENABLE_STATUS_LED);
#endif
}

M quantum/haptic.h => quantum/haptic.h +8 -8
@@ 84,22 84,22 @@ void haptic_notify_usb_device_state_change(void);
#    ifndef HAPTIC_ENABLE_PIN
#        error HAPTIC_ENABLE_PIN not defined
#    endif
#    define HAPTIC_ENABLE_PIN_WRITE_ACTIVE() writePinLow(HAPTIC_ENABLE_PIN)
#    define HAPTIC_ENABLE_PIN_WRITE_INACTIVE() writePinHigh(HAPTIC_ENABLE_PIN)
#    define HAPTIC_ENABLE_PIN_WRITE_ACTIVE() gpio_write_pin_low(HAPTIC_ENABLE_PIN)
#    define HAPTIC_ENABLE_PIN_WRITE_INACTIVE() gpio_write_pin_high(HAPTIC_ENABLE_PIN)
#else
#    define HAPTIC_ENABLE_PIN_WRITE_ACTIVE() writePinHigh(HAPTIC_ENABLE_PIN)
#    define HAPTIC_ENABLE_PIN_WRITE_INACTIVE() writePinLow(HAPTIC_ENABLE_PIN)
#    define HAPTIC_ENABLE_PIN_WRITE_ACTIVE() gpio_write_pin_high(HAPTIC_ENABLE_PIN)
#    define HAPTIC_ENABLE_PIN_WRITE_INACTIVE() gpio_write_pin_low(HAPTIC_ENABLE_PIN)
#endif

#ifdef HAPTIC_ENABLE_STATUS_LED_ACTIVE_LOW
#    ifndef HAPTIC_ENABLE_STATUS_LED
#        error HAPTIC_ENABLE_STATUS_LED not defined
#    endif
#    define HAPTIC_ENABLE_STATUS_LED_WRITE_ACTIVE() writePinLow(HAPTIC_ENABLE_STATUS_LED)
#    define HAPTIC_ENABLE_STATUS_LED_WRITE_INACTIVE() writePinHigh(HAPTIC_ENABLE_STATUS_LED)
#    define HAPTIC_ENABLE_STATUS_LED_WRITE_ACTIVE() gpio_write_pin_low(HAPTIC_ENABLE_STATUS_LED)
#    define HAPTIC_ENABLE_STATUS_LED_WRITE_INACTIVE() gpio_write_pin_high(HAPTIC_ENABLE_STATUS_LED)
#else
#    define HAPTIC_ENABLE_STATUS_LED_WRITE_ACTIVE() writePinHigh(HAPTIC_ENABLE_STATUS_LED)
#    define HAPTIC_ENABLE_STATUS_LED_WRITE_INACTIVE() writePinLow(HAPTIC_ENABLE_STATUS_LED)
#    define HAPTIC_ENABLE_STATUS_LED_WRITE_ACTIVE() gpio_write_pin_high(HAPTIC_ENABLE_STATUS_LED)
#    define HAPTIC_ENABLE_STATUS_LED_WRITE_INACTIVE() gpio_write_pin_low(HAPTIC_ENABLE_STATUS_LED)
#endif

#ifndef HAPTIC_OFF_IN_LOW_POWER

M quantum/joystick.c => quantum/joystick.c +1 -1
@@ 43,7 43,7 @@ __attribute__((weak)) void joystick_axis_init(uint8_t axis) {
    if (axis >= JOYSTICK_AXIS_COUNT) return;

#if defined(JOYSTICK_ANALOG)
    setPinInput(joystick_axes[axis].input_pin);
    gpio_set_pin_input(joystick_axes[axis].input_pin);
#endif
}


M quantum/led.c => quantum/led.c +15 -15
@@ 98,19 98,19 @@ __attribute__((weak)) void led_update_ports(led_t led_state) {
#endif

#ifdef LED_NUM_LOCK_PIN
    writePin(LED_NUM_LOCK_PIN, led_state.num_lock);
    gpio_write_pin(LED_NUM_LOCK_PIN, led_state.num_lock);
#endif
#ifdef LED_CAPS_LOCK_PIN
    writePin(LED_CAPS_LOCK_PIN, led_state.caps_lock);
    gpio_write_pin(LED_CAPS_LOCK_PIN, led_state.caps_lock);
#endif
#ifdef LED_SCROLL_LOCK_PIN
    writePin(LED_SCROLL_LOCK_PIN, led_state.scroll_lock);
    gpio_write_pin(LED_SCROLL_LOCK_PIN, led_state.scroll_lock);
#endif
#ifdef LED_COMPOSE_PIN
    writePin(LED_COMPOSE_PIN, led_state.compose);
    gpio_write_pin(LED_COMPOSE_PIN, led_state.compose);
#endif
#ifdef LED_KANA_PIN
    writePin(LED_KANA_PIN, led_state.kana);
    gpio_write_pin(LED_KANA_PIN, led_state.kana);
#endif
}



@@ 118,24 118,24 @@ __attribute__((weak)) void led_update_ports(led_t led_state) {
 */
__attribute__((weak)) void led_init_ports(void) {
#ifdef LED_NUM_LOCK_PIN
    setPinOutput(LED_NUM_LOCK_PIN);
    writePin(LED_NUM_LOCK_PIN, !LED_PIN_ON_STATE);
    gpio_set_pin_output(LED_NUM_LOCK_PIN);
    gpio_write_pin(LED_NUM_LOCK_PIN, !LED_PIN_ON_STATE);
#endif
#ifdef LED_CAPS_LOCK_PIN
    setPinOutput(LED_CAPS_LOCK_PIN);
    writePin(LED_CAPS_LOCK_PIN, !LED_PIN_ON_STATE);
    gpio_set_pin_output(LED_CAPS_LOCK_PIN);
    gpio_write_pin(LED_CAPS_LOCK_PIN, !LED_PIN_ON_STATE);
#endif
#ifdef LED_SCROLL_LOCK_PIN
    setPinOutput(LED_SCROLL_LOCK_PIN);
    writePin(LED_SCROLL_LOCK_PIN, !LED_PIN_ON_STATE);
    gpio_set_pin_output(LED_SCROLL_LOCK_PIN);
    gpio_write_pin(LED_SCROLL_LOCK_PIN, !LED_PIN_ON_STATE);
#endif
#ifdef LED_COMPOSE_PIN
    setPinOutput(LED_COMPOSE_PIN);
    writePin(LED_COMPOSE_PIN, !LED_PIN_ON_STATE);
    gpio_set_pin_output(LED_COMPOSE_PIN);
    gpio_write_pin(LED_COMPOSE_PIN, !LED_PIN_ON_STATE);
#endif
#ifdef LED_KANA_PIN
    setPinOutput(LED_KANA_PIN);
    writePin(LED_KANA_PIN, !LED_PIN_ON_STATE);
    gpio_set_pin_output(LED_KANA_PIN);
    gpio_write_pin(LED_KANA_PIN, !LED_PIN_ON_STATE);
#endif
}


M quantum/matrix.c => quantum/matrix.c +7 -7
@@ 78,27 78,27 @@ __attribute__((weak)) void matrix_read_rows_on_col(matrix_row_t current_matrix[]

static inline void setPinOutput_writeLow(pin_t pin) {
    ATOMIC_BLOCK_FORCEON {
        setPinOutput(pin);
        writePinLow(pin);
        gpio_set_pin_output(pin);
        gpio_write_pin_low(pin);
    }
}

static inline void setPinOutput_writeHigh(pin_t pin) {
    ATOMIC_BLOCK_FORCEON {
        setPinOutput(pin);
        writePinHigh(pin);
        gpio_set_pin_output(pin);
        gpio_write_pin_high(pin);
    }
}

static inline void setPinInputHigh_atomic(pin_t pin) {
    ATOMIC_BLOCK_FORCEON {
        setPinInputHigh(pin);
        gpio_set_pin_input_high(pin);
    }
}

static inline uint8_t readMatrixPin(pin_t pin) {
    if (pin != NO_PIN) {
        return (readPin(pin) == MATRIX_INPUT_PRESSED_STATE) ? 0 : 1;
        return (gpio_read_pin(pin) == MATRIX_INPUT_PRESSED_STATE) ? 0 : 1;
    } else {
        return 1;
    }


@@ 113,7 113,7 @@ __attribute__((weak)) void matrix_init_pins(void) {
        for (int col = 0; col < MATRIX_COLS; col++) {
            pin_t pin = direct_pins[row][col];
            if (pin != NO_PIN) {
                setPinInputHigh(pin);
                gpio_set_pin_input_high(pin);
            }
        }
    }

M quantum/pointing_device/pointing_device.c => quantum/pointing_device/pointing_device.c +4 -4
@@ 149,9 149,9 @@ __attribute__((weak)) void pointing_device_init(void) {
        pointing_device_driver.init();
#ifdef POINTING_DEVICE_MOTION_PIN
#    ifdef POINTING_DEVICE_MOTION_PIN_ACTIVE_LOW
        setPinInputHigh(POINTING_DEVICE_MOTION_PIN);
        gpio_set_pin_input_high(POINTING_DEVICE_MOTION_PIN);
#    else
        setPinInput(POINTING_DEVICE_MOTION_PIN);
        gpio_set_pin_input(POINTING_DEVICE_MOTION_PIN);
#    endif
#endif
    }


@@ 247,9 247,9 @@ __attribute__((weak)) bool pointing_device_task(void) {
#        error POINTING_DEVICE_MOTION_PIN not supported when sharing the pointing device report between sides.
#    endif
#    ifdef POINTING_DEVICE_MOTION_PIN_ACTIVE_LOW
    if (!readPin(POINTING_DEVICE_MOTION_PIN))
    if (!gpio_read_pin(POINTING_DEVICE_MOTION_PIN))
#    else
    if (readPin(POINTING_DEVICE_MOTION_PIN))
    if (gpio_read_pin(POINTING_DEVICE_MOTION_PIN))
#    endif
    {
#endif

M quantum/split_common/split_util.c => quantum/split_common/split_util.c +8 -8
@@ 123,14 123,14 @@ void split_watchdog_task(void) {
void matrix_io_delay(void);

static uint8_t peek_matrix_intersection(pin_t out_pin, pin_t in_pin) {
    setPinInputHigh(in_pin);
    setPinOutput(out_pin);
    writePinLow(out_pin);
    gpio_set_pin_input_high(in_pin);
    gpio_set_pin_output(out_pin);
    gpio_write_pin_low(out_pin);
    // It's almost unnecessary, but wait until it's down to low, just in case.
    wait_us(1);
    uint8_t pin_state = readPin(in_pin);
    uint8_t pin_state = gpio_read_pin(in_pin);
    // Set out_pin to a setting that is less susceptible to noise.
    setPinInputHigh(out_pin);
    gpio_set_pin_input_high(out_pin);
    matrix_io_delay(); // Wait for the pull-up to go HIGH.
    return pin_state;
}


@@ 138,13 138,13 @@ static uint8_t peek_matrix_intersection(pin_t out_pin, pin_t in_pin) {

__attribute__((weak)) bool is_keyboard_left_impl(void) {
#if defined(SPLIT_HAND_PIN)
    setPinInput(SPLIT_HAND_PIN);
    gpio_set_pin_input(SPLIT_HAND_PIN);
    wait_us(100);
    // Test pin SPLIT_HAND_PIN for High/Low, if low it's right hand
#    ifdef SPLIT_HAND_PIN_LOW_IS_LEFT
    return !readPin(SPLIT_HAND_PIN);
    return !gpio_read_pin(SPLIT_HAND_PIN);
#    else
    return readPin(SPLIT_HAND_PIN);
    return gpio_read_pin(SPLIT_HAND_PIN);
#    endif
#elif defined(SPLIT_HAND_MATRIX_GRID)
#    ifdef SPLIT_HAND_MATRIX_GRID_LOW_IS_LEFT

M tmk_core/protocol/arm_atsam/shift_register.c => tmk_core/protocol/arm_atsam/shift_register.c +12 -12
@@ 28,27 28,27 @@ along with this program.  If not, see <http://www.gnu.org/licenses/>.
#    define CLOCK_DELAY 10

void shift_init_impl(void) {
    setPinOutput(SR_EXP_RCLK_PIN);
    setPinOutput(SPI_DATAOUT_PIN);
    setPinOutput(SPI_SCLK_PIN);
    gpio_set_pin_output(SR_EXP_RCLK_PIN);
    gpio_set_pin_output(SPI_DATAOUT_PIN);
    gpio_set_pin_output(SPI_SCLK_PIN);
}

void shift_out_impl(const uint8_t *data, uint16_t length) {
    writePinLow(SR_EXP_RCLK_PIN);
    gpio_write_pin_low(SR_EXP_RCLK_PIN);
    for (uint16_t i = 0; i < length; i++) {
        uint8_t val = data[i];

        // shift out lsb first
        for (uint8_t bit = 0; bit < 8; bit++) {
            writePin(SPI_DATAOUT_PIN, !!(val & (1 << bit)));
            writePin(SPI_SCLK_PIN, true);
            gpio_write_pin(SPI_DATAOUT_PIN, !!(val & (1 << bit)));
            gpio_write_pin(SPI_SCLK_PIN, true);
            wait_us(CLOCK_DELAY);

            writePin(SPI_SCLK_PIN, false);
            gpio_write_pin(SPI_SCLK_PIN, false);
            wait_us(CLOCK_DELAY);
        }
    }
    writePinHigh(SR_EXP_RCLK_PIN);
    gpio_write_pin_high(SR_EXP_RCLK_PIN);
    return SPI_STATUS_SUCCESS;
}



@@ 74,13 74,13 @@ void shift_out(const uint8_t *data, uint16_t length) {
}

void shift_enable(void) {
    setPinOutput(SR_EXP_OE_PIN);
    writePinLow(SR_EXP_OE_PIN);
    gpio_set_pin_output(SR_EXP_OE_PIN);
    gpio_write_pin_low(SR_EXP_OE_PIN);
}

void shift_disable(void) {
    setPinOutput(SR_EXP_OE_PIN);
    writePinHigh(SR_EXP_OE_PIN);
    gpio_set_pin_output(SR_EXP_OE_PIN);
    gpio_write_pin_high(SR_EXP_OE_PIN);
}

void shift_init(void) {

M tmk_core/protocol/arm_atsam/spi_master.c => tmk_core/protocol/arm_atsam/spi_master.c +4 -4
@@ 60,8 60,8 @@ bool spi_start(pin_t csPin, bool lsbFirst, uint8_t mode, uint16_t divisor) {
    }

    currentSelectPin = csPin;
    setPinOutput(currentSelectPin);
    writePinLow(currentSelectPin);
    gpio_set_pin_output(currentSelectPin);
    gpio_write_pin_low(currentSelectPin);

    SPI_SERCOM->SPI.CTRLA.bit.DORD = lsbFirst; // Data Order - LSB is transferred first
    SPI_SERCOM->SPI.CTRLA.bit.CPOL = 1;        // Clock Polarity - SCK high when idle. Leading edge of cycle is falling. Trailing rising.


@@ 94,8 94,8 @@ spi_status_t spi_transmit(const uint8_t *data, uint16_t length) {

void spi_stop(void) {
    if (currentSelectPin != NO_PIN) {
        setPinOutput(currentSelectPin);
        writePinHigh(currentSelectPin);
        gpio_set_pin_output(currentSelectPin);
        gpio_write_pin_high(currentSelectPin);
        currentSelectPin = NO_PIN;
    }
}

M tmk_core/protocol/usb_util.c => tmk_core/protocol/usb_util.c +2 -2
@@ 26,9 26,9 @@ __attribute__((weak)) bool usb_connected_state(void) {

__attribute__((weak)) bool usb_vbus_state(void) {
#ifdef USB_VBUS_PIN
    setPinInput(USB_VBUS_PIN);
    gpio_set_pin_input(USB_VBUS_PIN);
    wait_us(5);
    return readPin(USB_VBUS_PIN);
    return gpio_read_pin(USB_VBUS_PIN);
#else
    return true;
#endif

Do not follow this link