diff --git a/keycluster/Makefile b/keycluster/Makefile new file mode 100644 index 0000000..6a6dda7 --- /dev/null +++ b/keycluster/Makefile @@ -0,0 +1,58 @@ +# Copyright (C) 2018 Kristian Lauszus. All rights reserved. +# +# This program is free software; you can redistribute it and/or modify +# it under the terms of the GNU General Public License as published by +# the Free Software Foundation; either version 2 of the License, or +# (at your option) any later version. +# +# Contact information +# ------------------- +# Kristian Lauszus +# Web : http://www.lauszus.com +# e-mail : lauszus@gmail.com + +# Set project name. +PROJECT_NAME = uhk_keycluster + +# Defines the part type that this project uses. +PART = MKL03Z32VFK4 + +# Defines the linker script to use for the application. +LDSCRIPT = ../lib/KSDK_2.0_MKL03Z8xxx4/devices/MKL03Z4/gcc/MKL03Z32xxx4_flash.ld + +# Size of the heap and stack. +HEAP_SIZE = 0 +STACK_SIZE = 0x0050 + +# Set the compiler CPU and FPU options. +CPU = -mcpu=cortex-m0plus +FPU = -mfloat-abi=soft + +# Command for flashing the key cluster module. +FLASH_CMD = node ../lib/agent/packages/usb/update-module-firmware.js keyCluster $(PROJECT_OBJ:.axf=.bin) + +# Path to the JLink script used for the key cluster module. +JLINK_SCRIPT = ../scripts/flash-keycluster.jlink + +# Source files. +SOURCE = $(wildcard src/*.c) \ + ../lib/KSDK_2.0_MKL03Z8xxx4/devices/MKL03Z4/system_MKL03Z4.c \ + ../lib/KSDK_2.0_MKL03Z8xxx4/devices/MKL03Z4/gcc/startup_MKL03Z4.S \ + ../lib/KSDK_2.0_MKL03Z8xxx4/devices/MKL03Z4/drivers/fsl_clock.c \ + ../lib/KSDK_2.0_MKL03Z8xxx4/devices/MKL03Z4/drivers/fsl_gpio.c \ + ../lib/KSDK_2.0_MKL03Z8xxx4/devices/MKL03Z4/drivers/fsl_i2c.c \ + ../lib/KSDK_2.0_MKL03Z8xxx4/devices/MKL03Z4/drivers/fsl_lptmr.c \ + ../lib/KSDK_2.0_MKL03Z8xxx4/devices/MKL03Z4/drivers/fsl_spi.c \ + ../lib/KSDK_2.0_MKL03Z8xxx4/devices/MKL03Z4/drivers/fsl_tpm.c \ + $(wildcard ../shared/*.c) \ + $(wildcard ../shared/slave/*.c) + +# Header files. +IPATH = src \ + ../lib/KSDK_2.0_MKL03Z8xxx4/CMSIS/Include \ + ../lib/KSDK_2.0_MKL03Z8xxx4/devices/MKL03Z4 \ + ../lib/KSDK_2.0_MKL03Z8xxx4/devices/MKL03Z4/drivers \ + ../shared + +# Include main Makefile. +include ../scripts/Makedefs.mk diff --git a/keycluster/README.md b/keycluster/README.md new file mode 100644 index 0000000..3b5ec1b --- /dev/null +++ b/keycluster/README.md @@ -0,0 +1,3 @@ +# Key cluster module firmware + +This directory contains the firmware of the key cluster module. diff --git a/keycluster/build/.cproject b/keycluster/build/.cproject new file mode 100644 index 0000000..d67ac60 --- /dev/null +++ b/keycluster/build/.cproject @@ -0,0 +1,350 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/keycluster/build/.gitignore b/keycluster/build/.gitignore new file mode 100644 index 0000000..ba43611 --- /dev/null +++ b/keycluster/build/.gitignore @@ -0,0 +1,4 @@ +/.settings/ +/uhk60-keycluster_debug/ +/uhk60-keycluster_release/ +/uhk60-keycluster_release/ diff --git a/keycluster/build/.project b/keycluster/build/.project new file mode 100644 index 0000000..dcfc10f --- /dev/null +++ b/keycluster/build/.project @@ -0,0 +1,155 @@ + + + uhk-keycluster + + + + + + com.freescale.processorexpert.core.expertprojectbuilder + + + + + org.eclipse.cdt.managedbuilder.core.genmakebuilder + clean,full,incremental, + + + + + org.eclipse.cdt.managedbuilder.core.ScannerConfigBuilder + full,incremental, + + + + + + com.freescale.processorexpert.core.expertprojectnature + org.eclipse.cdt.core.cnature + org.eclipse.cdt.core.ccnature + org.eclipse.cdt.managedbuilder.core.managedBuildNature + org.eclipse.cdt.managedbuilder.core.ScannerConfigNature + + + + Makedefs.mk + 1 + PARENT-2-PROJECT_LOC/scripts/Makedefs.mk + + + Makefile + 1 + PARENT-1-PROJECT_LOC/Makefile + + + drivers + 2 + virtual:/virtual + + + shared + 2 + PARENT-2-PROJECT_LOC/shared + + + src + 2 + PARENT-1-PROJECT_LOC/src + + + startup + 2 + virtual:/virtual + + + drivers/fsl_clock.c + 1 + PARENT-2-PROJECT_LOC/lib/KSDK_2.0_MKL03Z8xxx4/devices/MKL03Z4/drivers/fsl_clock.c + + + drivers/fsl_clock.h + 1 + PARENT-2-PROJECT_LOC/lib/KSDK_2.0_MKL03Z8xxx4/devices/MKL03Z4/drivers/fsl_clock.h + + + drivers/fsl_gpio.c + 1 + PARENT-2-PROJECT_LOC/lib/KSDK_2.0_MKL03Z8xxx4/devices/MKL03Z4/drivers/fsl_gpio.c + + + drivers/fsl_gpio.h + 1 + PARENT-2-PROJECT_LOC/lib/KSDK_2.0_MKL03Z8xxx4/devices/MKL03Z4/drivers/fsl_gpio.h + + + drivers/fsl_i2c.c + 1 + PARENT-2-PROJECT_LOC/lib/KSDK_2.0_MKL03Z8xxx4/devices/MKL03Z4/drivers/fsl_i2c.c + + + drivers/fsl_i2c.h + 1 + PARENT-2-PROJECT_LOC/lib/KSDK_2.0_MKL03Z8xxx4/devices/MKL03Z4/drivers/fsl_i2c.h + + + drivers/fsl_lptmr.c + 1 + PARENT-2-PROJECT_LOC/lib/KSDK_2.0_MKL03Z8xxx4/devices/MKL03Z4/drivers/fsl_lptmr.c + + + drivers/fsl_lptmr.h + 1 + PARENT-2-PROJECT_LOC/lib/KSDK_2.0_MKL03Z8xxx4/devices/MKL03Z4/drivers/fsl_lptmr.h + + + drivers/fsl_port.h + 1 + PARENT-2-PROJECT_LOC/lib/KSDK_2.0_MKL03Z8xxx4/devices/MKL03Z4/drivers/fsl_port.h + + + drivers/fsl_smc.c + 1 + PARENT-2-PROJECT_LOC/lib/KSDK_2.0_MKL03Z8xxx4/devices/MKL03Z4/drivers/fsl_smc.c + + + drivers/fsl_smc.h + 1 + PARENT-2-PROJECT_LOC/lib/KSDK_2.0_MKL03Z8xxx4/devices/MKL03Z4/drivers/fsl_smc.h + + + drivers/fsl_spi.c + 1 + PARENT-2-PROJECT_LOC/lib/KSDK_2.0_MKL03Z8xxx4/devices/MKL03Z4/drivers/fsl_spi.c + + + drivers/fsl_spi.h + 1 + PARENT-2-PROJECT_LOC/lib/KSDK_2.0_MKL03Z8xxx4/devices/MKL03Z4/drivers/fsl_spi.h + + + drivers/fsl_tpm.c + 1 + PARENT-2-PROJECT_LOC/lib/KSDK_2.0_MKL03Z8xxx4/devices/MKL03Z4/drivers/fsl_tpm.c + + + drivers/fsl_tpm.h + 1 + PARENT-2-PROJECT_LOC/lib/KSDK_2.0_MKL03Z8xxx4/devices/MKL03Z4/drivers/fsl_tpm.h + + + startup/startup_MKL03Z4.S + 1 + PARENT-2-PROJECT_LOC/lib/KSDK_2.0_MKL03Z8xxx4/devices/MKL03Z4/gcc/startup_MKL03Z4.S + + + startup/system_MKL03Z4.c + 1 + PARENT-2-PROJECT_LOC/lib/KSDK_2.0_MKL03Z8xxx4/devices/MKL03Z4/system_MKL03Z4.c + + + startup/system_MKL03Z4.h + 1 + PARENT-2-PROJECT_LOC/lib/KSDK_2.0_MKL03Z8xxx4/devices/MKL03Z4/system_MKL03Z4.h + + + diff --git a/keycluster/build/uhk60-keycluster_debug_jlink.launch b/keycluster/build/uhk60-keycluster_debug_jlink.launch new file mode 100644 index 0000000..a63b4e2 --- /dev/null +++ b/keycluster/build/uhk60-keycluster_debug_jlink.launch @@ -0,0 +1,82 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/keycluster/build/uhk60-keycluster_debug_kboot.launch b/keycluster/build/uhk60-keycluster_debug_kboot.launch new file mode 100644 index 0000000..3cb1139 --- /dev/null +++ b/keycluster/build/uhk60-keycluster_debug_kboot.launch @@ -0,0 +1,7 @@ + + + + + + + diff --git a/keycluster/build/uhk60-keycluster_release_jlink.launch b/keycluster/build/uhk60-keycluster_release_jlink.launch new file mode 100644 index 0000000..e665310 --- /dev/null +++ b/keycluster/build/uhk60-keycluster_release_jlink.launch @@ -0,0 +1,82 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/keycluster/build/uhk60-keycluster_release_kboot.launch b/keycluster/build/uhk60-keycluster_release_kboot.launch new file mode 100644 index 0000000..4cb108e --- /dev/null +++ b/keycluster/build/uhk60-keycluster_release_kboot.launch @@ -0,0 +1,7 @@ + + + + + + + diff --git a/keycluster/src/i2c.h b/keycluster/src/i2c.h new file mode 100644 index 0000000..4d34f7c --- /dev/null +++ b/keycluster/src/i2c.h @@ -0,0 +1,19 @@ +#ifndef __I2C_H__ +#define __I2C_H__ + +// Macros: + + #define I2C_BUS_BASEADDR I2C0 + #define I2C_BUS_CLK_SRC I2C0_CLK_SRC + #define I2C_BUS_BAUD_RATE 100000 // 100 kHz works even with a 20 meter long bridge cable. + #define I2C_BUS_MUX kPORT_MuxAlt2 + + #define I2C_BUS_SDA_PORT PORTB + #define I2C_BUS_SDA_CLOCK kCLOCK_PortB + #define I2C_BUS_SDA_PIN 4 + + #define I2C_BUS_SCL_PORT PORTB + #define I2C_BUS_SCL_CLOCK kCLOCK_PortB + #define I2C_BUS_SCL_PIN 3 + +#endif diff --git a/keycluster/src/i2c_watchdog.c b/keycluster/src/i2c_watchdog.c new file mode 100644 index 0000000..51c07dd --- /dev/null +++ b/keycluster/src/i2c_watchdog.c @@ -0,0 +1,33 @@ +#include "fsl_i2c.h" +#include "i2c.h" +#include "i2c_watchdog.h" +#include "test_led.h" +#include "init_peripherals.h" + +// NOTE: Because of a bug in the ROM bootloader of the KL03Z, the watchdog timer is disabled and cannot be re-enabled. +// See https://community.nxp.com/thread/457893 +// Therefore the hardware watchdog timer cannot be used without an extra way to enter bootloader or application mode. +static uint32_t prevWatchdogCounter = 0; +static uint32_t I2cWatchdog_RecoveryCounter; // Counter for how many times we had to recover and restart + +void RunWatchdog(void) +{ + static volatile uint32_t I2cWatchdog_WatchCounter = 0; // Counter for timer + static int counter = 0; + + counter++; + if (counter == 100) { // We get called from KEY_SCANNER_HANDLER() which runs at 1ms, thus scaling down by 100 here to get 100 ms period + counter=0; + TestLed_Toggle(); + I2cWatchdog_WatchCounter++; + + if (I2cWatchdog_WatchCounter > 10) { // Do not check within the first 1000 ms, as I2C might not be running yet + if (I2C_Watchdog == prevWatchdogCounter) { // Restart I2C if there hasn't been any interrupt during 100 ms. I2C_Watchdog gets incremented for every I2C transaction + I2cWatchdog_RecoveryCounter++; + I2C_SlaveDeinit(I2C_BUS_BASEADDR); + initI2c(); + } + } + prevWatchdogCounter = I2C_Watchdog; + } +} diff --git a/keycluster/src/i2c_watchdog.h b/keycluster/src/i2c_watchdog.h new file mode 100644 index 0000000..3817793 --- /dev/null +++ b/keycluster/src/i2c_watchdog.h @@ -0,0 +1,18 @@ +#ifndef __I2C_WATCHDOG_H__ +#define __I2C_WATCHDOG_H__ + +// Includes: + + #include "fsl_lptmr.h" + +// Macros: + + #define I2C_WATCHDOG_LPTMR_HANDLER LPTMR0_IRQHandler + #define LPTMR_SOURCE_CLOCK CLOCK_GetFreq(kCLOCK_LpoClk) + #define LPTMR_USEC_COUNT 100000U + +// Functions: + + void RunWatchdog(void); + +#endif diff --git a/keycluster/src/init_peripherals.c b/keycluster/src/init_peripherals.c new file mode 100644 index 0000000..79ec3dd --- /dev/null +++ b/keycluster/src/init_peripherals.c @@ -0,0 +1,88 @@ +#include "fsl_common.h" +#include "fsl_port.h" +#include "test_led.h" +#include "init_peripherals.h" +#include "i2c_addresses.h" +#include "fsl_i2c.h" +#include "fsl_clock.h" +#include "i2c.h" +#include "led_pwm.h" +#include "slave_protocol_handler.h" +#include "i2c_watchdog.h" +#include "main.h" + +i2c_slave_config_t slaveConfig; +i2c_slave_handle_t slaveHandle; + +uint8_t userData; +uint8_t rxMessagePos; +uint8_t dosBuffer[2]; + +static void i2cSlaveCallback(I2C_Type *base, i2c_slave_transfer_t *xfer, void *userDataArg) +{ + dosBuffer[0] = xfer->event; + dosBuffer[1] = userData; + + switch (xfer->event) { + case kI2C_SlaveTransmitEvent: + SlaveTxHandler(); + xfer->data = (uint8_t*)&TxMessage; + xfer->dataSize = TxMessage.length + I2C_MESSAGE_HEADER_LENGTH; + break; + case kI2C_SlaveAddressMatchEvent: + rxMessagePos = 0; + break; + case kI2C_SlaveReceiveEvent: + ((uint8_t*)&RxMessage)[rxMessagePos++] = userData; + if (RxMessage.length == rxMessagePos-I2C_MESSAGE_HEADER_LENGTH) { + SlaveRxHandler(); + } + break; + default: + break; + } +} + +void initInterruptPriorities(void) +{ + NVIC_SetPriority(I2C0_IRQn, 1); + NVIC_SetPriority(TPM1_IRQn, 1); + NVIC_SetPriority(SPI0_IRQn, 1); +} + +void initI2c(void) +{ + port_pin_config_t pinConfig = { + .pullSelect = kPORT_PullUp, + }; + + CLOCK_EnableClock(I2C_BUS_SDA_CLOCK); + CLOCK_EnableClock(I2C_BUS_SCL_CLOCK); + + pinConfig.mux = I2C_BUS_MUX; + PORT_SetPinConfig(I2C_BUS_SDA_PORT, I2C_BUS_SDA_PIN, &pinConfig); + PORT_SetPinConfig(I2C_BUS_SCL_PORT, I2C_BUS_SCL_PIN, &pinConfig); + + I2C_SlaveGetDefaultConfig(&slaveConfig); + slaveConfig.slaveAddress = I2C_ADDRESS_LEFT_KEYBOARD_HALF_FIRMWARE; + I2C_SlaveInit(I2C_BUS_BASEADDR, &slaveConfig); + I2C_SlaveTransferCreateHandle(I2C_BUS_BASEADDR, &slaveHandle, i2cSlaveCallback, &userData); + I2C_SlaveTransferNonBlocking(I2C_BUS_BASEADDR, &slaveHandle, kI2C_SlaveAddressMatchEvent); +} + +void InitLedDriver(void) +{ + CLOCK_EnableClock(LED_DRIVER_SDB_CLOCK); + PORT_SetPinMux(LED_DRIVER_SDB_PORT, LED_DRIVER_SDB_PIN, kPORT_MuxAsGpio); + GPIO_PinInit(LED_DRIVER_SDB_GPIO, LED_DRIVER_SDB_PIN, &(gpio_pin_config_t){kGPIO_DigitalOutput, 0}); + GPIO_WritePinOutput(LED_DRIVER_SDB_GPIO, LED_DRIVER_SDB_PIN, 1); +} + +void InitPeripherals(void) +{ + initInterruptPriorities(); + InitLedDriver(); + TestLed_Init(); + LedPwm_Init(); + initI2c(); +} diff --git a/keycluster/src/init_peripherals.h b/keycluster/src/init_peripherals.h new file mode 100644 index 0000000..d6912b0 --- /dev/null +++ b/keycluster/src/init_peripherals.h @@ -0,0 +1,16 @@ +#ifndef __INIT_PERIPHERALS_H__ +#define __INIT_PERIPHERALS_H__ + +// Macros: + + #define LED_DRIVER_SDB_PORT PORTB + #define LED_DRIVER_SDB_GPIO GPIOB + #define LED_DRIVER_SDB_CLOCK kCLOCK_PortB + #define LED_DRIVER_SDB_PIN 1 + +// Functions: + + void InitPeripherals(void); + void initI2c(void); + +#endif diff --git a/keycluster/src/key_scanner.c b/keycluster/src/key_scanner.c new file mode 100644 index 0000000..6de9efc --- /dev/null +++ b/keycluster/src/key_scanner.c @@ -0,0 +1,22 @@ +#include "fsl_lptmr.h" +#include "key_scanner.h" +#include "i2c_watchdog.h" + +void KEY_SCANNER_HANDLER(void) +{ + KeyMatrix_ScanRow(&keyMatrix); + RunWatchdog(); + LPTMR_ClearStatusFlags(KEY_SCANNER_LPTMR_BASEADDR, kLPTMR_TimerCompareFlag); +} + +void InitKeyScanner(void) +{ + lptmr_config_t lptmrConfig; + LPTMR_GetDefaultConfig(&lptmrConfig); + LPTMR_Init(KEY_SCANNER_LPTMR_BASEADDR, &lptmrConfig); + + LPTMR_SetTimerPeriod(KEY_SCANNER_LPTMR_BASEADDR, USEC_TO_COUNT(KEY_SCANNER_INTERVAL_USEC, LPTMR_SOURCE_CLOCK)); + LPTMR_EnableInterrupts(KEY_SCANNER_LPTMR_BASEADDR, kLPTMR_TimerInterruptEnable); + EnableIRQ(KEY_SCANNER_LPTMR_IRQ_ID); + LPTMR_StartTimer(KEY_SCANNER_LPTMR_BASEADDR); +} diff --git a/keycluster/src/key_scanner.h b/keycluster/src/key_scanner.h new file mode 100644 index 0000000..11906b5 --- /dev/null +++ b/keycluster/src/key_scanner.h @@ -0,0 +1,22 @@ +#ifndef __KEY_SCANNER_H__ +#define __KEY_SCANNER_H__ + +// Includes: + + #include "main.h" + +// Macros: + + #define LPTMR_SOURCE_CLOCK CLOCK_GetFreq(kCLOCK_LpoClk) + + #define KEY_SCANNER_LPTMR_BASEADDR LPTMR0 + #define KEY_SCANNER_LPTMR_IRQ_ID LPTMR0_IRQn + #define KEY_SCANNER_HANDLER LPTMR0_IRQHandler + + #define KEY_SCANNER_INTERVAL_USEC (1000 / KEYBOARD_MATRIX_ROWS_NUM) + +// Functions: + + void InitKeyScanner(void); + +#endif diff --git a/keycluster/src/led_pwm.c b/keycluster/src/led_pwm.c new file mode 100644 index 0000000..b1d5bcb --- /dev/null +++ b/keycluster/src/led_pwm.c @@ -0,0 +1,30 @@ +#include "led_pwm.h" +#include "fsl_port.h" + +void LedPwm_Init(void) +{ + CLOCK_EnableClock(LED_PWM_CLOCK); + PORT_SetPinMux(LED_PWM_PORT, LED_PWM_PIN, kPORT_MuxAlt2); + + // Select the clock source for the TPM counter as MCGPLLCLK. + CLOCK_SetTpmClock(1U); + + tpm_config_t tpmInfo; + TPM_GetDefaultConfig(&tpmInfo); + TPM_Init(LED_PWM_TPM_BASEADDR, &tpmInfo); + + tpm_chnl_pwm_signal_param_t tpmParam[1]; + tpmParam[0].chnlNumber = LED_PWM_TPM_CHANNEL; + tpmParam[0].level = kTPM_LowTrue; + tpmParam[0].dutyCyclePercent = 100 - INITIAL_DUTY_CYCLE_PERCENT; + TPM_SetupPwm(LED_PWM_TPM_BASEADDR, tpmParam, 1, + kTPM_EdgeAlignedPwm, TPM_PWM_FREQUENCY, TPM_SOURCE_CLOCK); + + TPM_StartTimer(LED_PWM_TPM_BASEADDR, kTPM_SystemClock); +} + +void LedPwm_SetBrightness(uint8_t brightnessPercent) +{ + TPM_UpdatePwmDutycycle(LED_PWM_TPM_BASEADDR, LED_PWM_TPM_CHANNEL, + kTPM_EdgeAlignedPwm, 100 - brightnessPercent); +} diff --git a/keycluster/src/led_pwm.h b/keycluster/src/led_pwm.h new file mode 100644 index 0000000..a237e7a --- /dev/null +++ b/keycluster/src/led_pwm.h @@ -0,0 +1,27 @@ +#ifndef __LED_PWM_H__ +#define __LED_PWM_H__ + +// Includes: + + #include "fsl_tpm.h" + +// Macros: + + #define LED_PWM_PORT PORTB + #define LED_PWM_CLOCK kCLOCK_PortB + #define LED_PWM_PIN 5 + + #define LED_PWM_TPM_BASEADDR TPM1 + #define LED_PWM_TPM_CHANNEL kTPM_Chnl_1 + + #define TPM_SOURCE_CLOCK CLOCK_GetFreq(kCLOCK_BusClk) + #define TPM_PWM_FREQUENCY 24000U + + #define INITIAL_DUTY_CYCLE_PERCENT 100U + +// Functions: + + void LedPwm_Init(void); + void LedPwm_SetBrightness(uint8_t brightnessPercent); + +#endif diff --git a/keycluster/src/main.c b/keycluster/src/main.c new file mode 100644 index 0000000..6d868ee --- /dev/null +++ b/keycluster/src/main.c @@ -0,0 +1,41 @@ +#include "main.h" +#include "slave/init_clock.h" +#include "init_peripherals.h" +#include "bootloader.h" +#include +#include "key_scanner.h" + +DEFINE_BOOTLOADER_CONFIG_AREA(I2C_ADDRESS_LEFT_KEYBOARD_HALF_BOOTLOADER) + +key_matrix_t keyMatrix = { + .colNum = KEYBOARD_MATRIX_COLS_NUM, + .rowNum = KEYBOARD_MATRIX_ROWS_NUM, + .cols = (key_matrix_pin_t[]) { + {PORTB, GPIOB, kCLOCK_PortB, 11}, + {PORTA, GPIOA, kCLOCK_PortA, 6}, + {PORTA, GPIOA, kCLOCK_PortA, 8}, + {PORTB, GPIOB, kCLOCK_PortB, 0}, + {PORTB, GPIOB, kCLOCK_PortB, 6}, + {PORTA, GPIOA, kCLOCK_PortA, 3}, + {PORTA, GPIOA, kCLOCK_PortA, 12} + }, + .rows = (key_matrix_pin_t[]) { + {PORTB, GPIOB, kCLOCK_PortB, 7}, + {PORTB, GPIOB, kCLOCK_PortB, 10}, + {PORTA, GPIOA, kCLOCK_PortA, 5}, + {PORTA, GPIOA, kCLOCK_PortA, 7}, + {PORTA, GPIOA, kCLOCK_PortA, 4} + } +}; + +int main(void) +{ + InitClock(); + InitPeripherals(); + KeyMatrix_Init(&keyMatrix); + InitKeyScanner(); + + while (1) { + __WFI(); + } +} diff --git a/keycluster/src/main.h b/keycluster/src/main.h new file mode 100644 index 0000000..7df0c8c --- /dev/null +++ b/keycluster/src/main.h @@ -0,0 +1,17 @@ +#ifndef __MAIN_H__ +#define __MAIN_H__ + +// Includes: + + #include "key_matrix.h" + +// Macros: + + #define KEYBOARD_MATRIX_COLS_NUM 7 + #define KEYBOARD_MATRIX_ROWS_NUM 5 + +// Variables: + + extern key_matrix_t keyMatrix; + +#endif diff --git a/keycluster/src/module.h b/keycluster/src/module.h new file mode 100644 index 0000000..79cba53 --- /dev/null +++ b/keycluster/src/module.h @@ -0,0 +1,11 @@ +#ifndef __MODULE_H__ +#define __MODULE_H__ + +// Macros: + + #define MODULE_PROTOCOL_VERSION 1 + #define MODULE_ID ModuleId_LeftKeyboardHalf + #define MODULE_KEY_COUNT (KEYBOARD_MATRIX_ROWS_NUM * KEYBOARD_MATRIX_COLS_NUM) + #define MODULE_POINTER_COUNT 0 + +#endif diff --git a/keycluster/src/slave_protocol_handler.c b/keycluster/src/slave_protocol_handler.c new file mode 100644 index 0000000..4ceb40f --- /dev/null +++ b/keycluster/src/slave_protocol_handler.c @@ -0,0 +1,102 @@ +#include "slave_protocol_handler.h" +#include "test_led.h" +#include "main.h" +#include "i2c_addresses.h" +#include "i2c.h" +#include "led_pwm.h" +#include "slave_protocol.h" +#include "main.h" +#include "init_peripherals.h" +#include "bool_array_converter.h" +#include "bootloader.h" +#include "module.h" +#include "versions.h" + +i2c_message_t RxMessage; +i2c_message_t TxMessage; + +static version_t moduleProtocolVersion = { + MODULE_PROTOCOL_MAJOR_VERSION, + MODULE_PROTOCOL_MINOR_VERSION, + MODULE_PROTOCOL_PATCH_VERSION, +}; + +static version_t firmwareVersion = { + FIRMWARE_MAJOR_VERSION, + FIRMWARE_MINOR_VERSION, + FIRMWARE_PATCH_VERSION, +}; + +void SlaveRxHandler(void) +{ + if (!CRC16_IsMessageValid(&RxMessage)) { + TxMessage.length = 0; + return; + } + + uint8_t commandId = RxMessage.data[0]; + switch (commandId) { + case SlaveCommand_JumpToBootloader: + NVIC_SystemReset(); + break; + case SlaveCommand_SetTestLed: + TxMessage.length = 0; + bool isLedOn = RxMessage.data[1]; + TestLed_Set(isLedOn); + break; + case SlaveCommand_SetLedPwmBrightness: + TxMessage.length = 0; + uint8_t brightnessPercent = RxMessage.data[1]; + LedPwm_SetBrightness(brightnessPercent); + break; + } +} + +void SlaveTxHandler(void) +{ + uint8_t commandId = RxMessage.data[0]; + switch (commandId) { + case SlaveCommand_RequestProperty: { + uint8_t propertyId = RxMessage.data[1]; + switch (propertyId) { + case SlaveProperty_Sync: { + memcpy(TxMessage.data, SlaveSyncString, SLAVE_SYNC_STRING_LENGTH); + TxMessage.length = SLAVE_SYNC_STRING_LENGTH; + break; + } + case SlaveProperty_ModuleProtocolVersion: { + memcpy(TxMessage.data, &moduleProtocolVersion, sizeof(version_t)); + TxMessage.length = sizeof(version_t); + break; + } + case SlaveProperty_FirmwareVersion: { + memcpy(TxMessage.data, &firmwareVersion, sizeof(version_t)); + TxMessage.length = sizeof(version_t); + break; + } + case SlaveProperty_ModuleId: { + TxMessage.data[0] = MODULE_ID; + TxMessage.length = 1; + break; + } + case SlaveProperty_KeyCount: { + TxMessage.data[0] = MODULE_KEY_COUNT; + TxMessage.length = 1; + break; + } + case SlaveProperty_PointerCount: { + TxMessage.data[0] = MODULE_POINTER_COUNT; + TxMessage.length = 1; + break; + } + } + break; + } + case SlaveCommand_RequestKeyStates: + BoolBytesToBits(keyMatrix.keyStates, TxMessage.data, MODULE_KEY_COUNT); + TxMessage.length = BOOL_BYTES_TO_BITS_COUNT(MODULE_KEY_COUNT); + break; + } + + CRC16_UpdateMessageChecksum(&TxMessage); +} diff --git a/keycluster/src/slave_protocol_handler.h b/keycluster/src/slave_protocol_handler.h new file mode 100644 index 0000000..a5d8984 --- /dev/null +++ b/keycluster/src/slave_protocol_handler.h @@ -0,0 +1,20 @@ +#ifndef __SLAVE_PROTOCOL_HANDLER_H__ +#define __SLAVE_PROTOCOL_HANDLER_H__ + +// Includes: + + #include "fsl_port.h" + #include "crc16.h" + #include "slave_protocol.h" + +// Variables: + + extern i2c_message_t RxMessage; + extern i2c_message_t TxMessage; + +// Functions: + + void SlaveRxHandler(void); + void SlaveTxHandler(void); + +#endif diff --git a/keycluster/src/test_led.c b/keycluster/src/test_led.c new file mode 100644 index 0000000..0f084d3 --- /dev/null +++ b/keycluster/src/test_led.c @@ -0,0 +1,10 @@ +#include "test_led.h" +#include "fsl_port.h" + +extern void TestLed_Init(void) +{ + CLOCK_EnableClock(TEST_LED_CLOCK); + PORT_SetPinMux(TEST_LED_PORT, TEST_LED_PIN, kPORT_MuxAsGpio); + GPIO_PinInit(TEST_LED_GPIO, TEST_LED_PIN, &(gpio_pin_config_t){kGPIO_DigitalOutput, 0}); + TestLed_On(); +} diff --git a/keycluster/src/test_led.h b/keycluster/src/test_led.h new file mode 100644 index 0000000..7f4df88 --- /dev/null +++ b/keycluster/src/test_led.h @@ -0,0 +1,42 @@ +#ifndef __TEST_LED_H__ +#define __TEST_LED_H__ + +// Includes: + + #include "fsl_gpio.h" + +// Macros: + + #define LOGIC_LED_ON 0U + #define LOGIC_LED_OFF 1U + + #define TEST_LED_GPIO GPIOB + #define TEST_LED_PORT PORTB + #define TEST_LED_CLOCK kCLOCK_PortB + #define TEST_LED_PIN 13 + + static inline void TestLed_On(void) + { + GPIO_SetPinsOutput(TEST_LED_GPIO, 1U << TEST_LED_PIN); + } + + static inline void TestLed_Off(void) + { + GPIO_ClearPinsOutput(TEST_LED_GPIO, 1U << TEST_LED_PIN); + } + + static inline void TestLed_Set(bool state) + { + GPIO_WritePinOutput(TEST_LED_GPIO, TEST_LED_PIN, state); + } + + static inline void TestLed_Toggle(void) + { + GPIO_TogglePinsOutput(TEST_LED_GPIO, 1U << TEST_LED_PIN); + } + +// Functions: + + void TestLed_Init(void); + +#endif diff --git a/scripts/flash-keycluster.jlink b/scripts/flash-keycluster.jlink new file mode 100644 index 0000000..5e3523d --- /dev/null +++ b/scripts/flash-keycluster.jlink @@ -0,0 +1,7 @@ +speed 4000 +device MKL03Z32xxx4 +connect +loadfile build_make/uhk_keycluster.hex +RSetType 2 +r +qc