summaryrefslogtreecommitdiff
path: root/app/src
diff options
context:
space:
mode:
Diffstat (limited to 'app/src')
-rw-r--r--app/src/adc_task.c365
-rw-r--r--app/src/can_task.c470
-rw-r--r--app/src/com_task.c279
-rw-r--r--app/src/gpio_ext.c132
-rw-r--r--app/src/main.c139
5 files changed, 1385 insertions, 0 deletions
diff --git a/app/src/adc_task.c b/app/src/adc_task.c
new file mode 100644
index 0000000..daf4716
--- /dev/null
+++ b/app/src/adc_task.c
@@ -0,0 +1,365 @@
+/*
+ * adc_task.c
+ *
+ */
+
+#include "com_task.h"
+#include "adc_task.h"
+#include "fsl_adc16.h"
+#include "fsl_port.h"
+#include "errno.h"
+#include "stdlib.h"
+
+struct adc_data {
+ uint16_t adc[ADC0_CHANNEL_CNT];
+ uint16_t tsc_xm;
+ uint16_t tsc_xp;
+ uint16_t tsc_ym;
+ uint16_t tsc_yp;
+} adc_data;
+
+/*
+ * Apalis ADC0 -> PTB0 -> ADC0_SE8
+ * Apalis ADC1 -> PTB1 -> ADC0_SE9
+ * Apalis ADC2 -> PTB2 -> ADC0_SE12
+ * Apalis ADC3 -> PTB3 -> ADC0_SE13
+ *
+ * Touch screen:
+ * Force:
+ * PTE6 X+ hi-off
+ * PTB9 X- lo-off
+ * PTC5 Y+ hi-off
+ * PTC13 Y- lo-off
+ * Sense:
+ * PTB7 -> ADC1_SE13 X-
+ * PTB6 -> ADC1_SE12 X+
+ * PTC9 -> ADC1_SE5b Y-
+ * PTC8 -> ADC1_SE4b Y+
+ */
+const uint8_t adc0_channels[ADC0_CHANNEL_CNT] = {8, 9, 12, 13};
+const uint8_t tsc_channels[TSC0_CHANNEL_CNT] = {13, 12, 5, 4};
+
+static int adc_task_init(void)
+{
+ adc16_config_t adc_config;
+#ifdef BOARD_USES_ADC
+ ADC16_GetDefaultConfig(&adc_config);
+ adc_config.resolution = kADC16_ResolutionSE16Bit;
+ adc_config.longSampleMode = kADC16_LongSampleDisabled;
+ adc_config.clockDivider = kADC16_ClockDivider8;
+ ADC16_Init(ADC0, &adc_config);
+ ADC16_SetHardwareAverage(ADC0, kADC16_HardwareAverageDisabled);
+ PRINTF("ADC init done \r\n");
+ return 0;
+#else
+ return -ENODEV;
+#endif
+}
+
+static int tsc_task_init(void)
+{
+ adc16_config_t adc_config;
+#ifdef BOARD_USES_ADC
+ ADC16_GetDefaultConfig(&adc_config);
+ adc_config.resolution = kADC16_ResolutionSE12Bit;
+ adc_config.longSampleMode = kADC16_LongSampleCycle10;
+ adc_config.clockDivider = kADC16_ClockDivider8;
+ ADC16_Init(ADC1, &adc_config);
+ ADC16_SetChannelMuxMode(ADC1, kADC16_ChannelMuxB);
+ ADC16_SetHardwareAverage(ADC1, kADC16_HardwareAverageCount32);
+ PRINTF("TSC init done \r\n");
+ return 0;
+#else
+ return -ENODEV;
+#endif
+}
+
+#ifdef BOARD_USES_ADC
+static void ts_force_drive(uint8_t xm, uint8_t xp, uint8_t ym, uint8_t yp)
+{
+ if (xp == 0)
+ GPIO_SetPinsOutput(GPIOE, 1 << 6);
+ else
+ GPIO_ClearPinsOutput(GPIOE, 1 << 6);
+
+ if (xm > 0)
+ GPIO_SetPinsOutput(GPIOB, 1 << 9);
+ else
+ GPIO_ClearPinsOutput(GPIOB, 1 << 9);
+
+ if (yp == 0)
+ GPIO_SetPinsOutput(GPIOC, 1 << 5);
+ else
+ GPIO_ClearPinsOutput(GPIOC, 1 << 5);
+
+ if (ym > 0)
+ GPIO_SetPinsOutput(GPIOC, 1 << 13);
+ else
+ GPIO_ClearPinsOutput(GPIOC, 1 << 13);
+}
+
+static inline uint16_t do_adc_conversion(ADC_Type *base, adc16_channel_config_t *channel)
+{
+ ADC16_SetChannelConfig(base, 0, channel);
+ while(ADC16_GetChannelStatusFlags(base, 0) == 0){vTaskDelay(0);}
+ return (uint16_t)ADC16_GetChannelConversionValue(base, 0);
+}
+
+void adc_task(void *pvParameters)
+{
+ adc16_channel_config_t channel;
+ int i;
+ if (adc_task_init() < 0)
+ return;
+
+ channel.enableDifferentialConversion = false;
+ channel.enableInterruptOnConversionCompleted = false;
+
+ while(1) {
+ for (i = 0; i < ADC0_CHANNEL_CNT;i ++){
+ channel.channelNumber = adc0_channels[i];
+ adc_data.adc[i] = do_adc_conversion(ADC0, &channel);
+ registers[APALIS_TK1_K20_ADC_CH0L + 2 * i] = adc_data.adc[i] & 0xFF;
+ registers[APALIS_TK1_K20_ADC_CH0L + 2 * i + 1] = (adc_data.adc[i] >> 8) & 0xFF;
+ }
+ vTaskDelay(5);
+ }
+
+}
+
+enum touch_status {
+ PEN_UP,
+ PEN_DOWN
+};
+
+#define MIN_TOUCH_DET 5
+
+/* PTB7 -> ADC1_SE13 X-
+ * PTB6 -> ADC1_SE12 X+
+ * PTC9 -> ADC1_SE5b Y-
+ * PTC8 -> ADC1_SE4b Y+
+ */
+void tsc_task(void *pvParameters)
+{
+ adc16_channel_config_t channel;
+ port_pin_config_t pin_config_pd, pin_config_ana;
+ int old_status, status = PEN_UP;
+ int irq_stat = 0, press;
+ uint16_t tsc_xm;
+ uint16_t tsc_xp;
+ uint16_t tsc_ym;
+ uint16_t tsc_yp;
+
+ if (tsc_task_init() < 0)
+ return;
+
+ pin_config_pd.mux = kPORT_MuxAsGpio;
+ pin_config_pd.openDrainEnable = kPORT_OpenDrainDisable;
+ pin_config_pd.pullSelect = kPORT_PullUp;
+ pin_config_pd.slewRate = kPORT_FastSlewRate;
+ pin_config_pd.passiveFilterEnable = kPORT_PassiveFilterDisable;
+ pin_config_pd.driveStrength = kPORT_LowDriveStrength;
+ pin_config_pd.lockRegister = kPORT_UnlockRegister;
+
+ pin_config_ana.mux = kPORT_PinDisabledOrAnalog;
+ pin_config_ana.openDrainEnable = kPORT_OpenDrainDisable;
+ pin_config_ana.pullSelect = kPORT_PullDisable;
+ pin_config_ana.slewRate = kPORT_FastSlewRate;
+ pin_config_ana.passiveFilterEnable = kPORT_PassiveFilterDisable;
+ pin_config_ana.driveStrength = kPORT_LowDriveStrength;
+ pin_config_ana.lockRegister = kPORT_UnlockRegister;
+
+ channel.enableDifferentialConversion = false;
+ channel.enableInterruptOnConversionCompleted = false;
+
+ while(1) {
+ //Touch detect: power Y-, enable pullup on xp and read xp GPIO
+ ts_force_drive(0, 0, 1, 0);
+ PORT_SetPinConfig(PORTB, 6u, &pin_config_pd);
+ vTaskDelay(5);
+ old_status = status;
+ status = GPIO_ReadPinInput(GPIOB, 6u) ? PEN_UP:PEN_DOWN;
+ PORT_SetPinConfig(PORTB, 6u, &pin_config_ana);
+
+ if (status != old_status)
+ irq_stat = 0;
+
+ if (status == PEN_DOWN) {
+ //probe ym with power across Y plane
+ ts_force_drive(0, 0, 1, 1);
+ channel.channelNumber = tsc_channels[0];
+ tsc_ym = do_adc_conversion(ADC1, &channel);
+
+ //probe yp with power across Y plane
+ channel.channelNumber = tsc_channels[1];
+ tsc_yp = do_adc_conversion(ADC1, &channel);
+
+ //probe xm with power across X plane
+ ts_force_drive(1, 1, 0, 0);
+ channel.channelNumber = tsc_channels[2];
+ tsc_xm = do_adc_conversion(ADC1, &channel);
+
+ //probe xp with power across X plane
+ channel.channelNumber = tsc_channels[3];
+ tsc_xp = do_adc_conversion(ADC1, &channel);
+
+#ifdef TOUCH_STRONG_FILTERING
+ /* additional filtering */
+ //probe ym with power across Y plane
+ ts_force_drive(0, 0, 1, 1);
+ channel.channelNumber = tsc_channels[0];
+ tsc_ym += do_adc_conversion(ADC1, &channel);
+ tsc_ym >>= 1;
+
+ //probe yp with power across Y plane
+ channel.channelNumber = tsc_channels[1];
+ tsc_yp += do_adc_conversion(ADC1, &channel);
+ tsc_yp >>= 1;
+
+ //probe xm with power across X plane
+ ts_force_drive(1, 1, 0, 0);
+ channel.channelNumber = tsc_channels[2];
+ tsc_xm += do_adc_conversion(ADC1, &channel);
+ tsc_xm >>= 1;
+
+ //probe xp with power across X plane
+ channel.channelNumber = tsc_channels[3];
+ tsc_xp += do_adc_conversion(ADC1, &channel);
+ tsc_xp >>= 1;
+#endif
+
+ /* make sure that pen is making good contact */
+ press = (abs(tsc_yp - tsc_ym)
+ + abs(tsc_xp - tsc_xm)) / 2;
+#ifdef TOUCH_STRONG_FILTERING
+ if (press > 9) {
+#else
+ if (press > 15) {
+#endif
+ continue;
+ } else {
+ adc_data.tsc_xm = tsc_xm;
+ adc_data.tsc_xp = tsc_xp;
+ adc_data.tsc_ym = tsc_ym;
+ adc_data.tsc_yp = tsc_yp;
+ }
+
+ } else {
+ adc_data.tsc_xm = 0;
+ adc_data.tsc_xp = 0;
+ adc_data.tsc_ym = 0;
+ adc_data.tsc_yp = 0;
+ vTaskDelay(10);
+ }
+
+ if (irq_stat == 0) {
+ generate_irq(APALIS_TK1_K20_TSC_IRQ);
+ irq_stat = 1;
+ }
+
+ vTaskDelay(5);
+ }
+
+}
+
+int tsc_registers(dspi_transfer_t *spi_transfer)
+{
+ uint8_t *rx_buf = spi_transfer->rxData;
+ uint8_t *tx_buf = &spi_transfer->txData[0];
+
+ if (rx_buf[0] == APALIS_TK1_K20_WRITE_INST) {
+ switch (rx_buf[1]) {
+ case APALIS_TK1_K20_TSCREG:
+ return 0;
+ default:
+ return -ENOENT;
+ }
+ } else if (rx_buf[0] == APALIS_TK1_K20_BULK_READ_INST) {
+ if (rx_buf[1] == APALIS_TK1_K20_TSC_XML) {
+ if (rx_buf[2] == 2) {
+ tx_buf[0] = adc_data.tsc_xm & 0xFF;
+ tx_buf[1] = (adc_data.tsc_xm >> 8) & 0xFF;
+ return 2;
+ } else if (rx_buf[2] == 8) {
+ tx_buf[0] = adc_data.tsc_xm & 0xFF;
+ tx_buf[1] = (adc_data.tsc_xm >> 8) & 0xFF;
+ tx_buf[2] = adc_data.tsc_xp & 0xFF;
+ tx_buf[3] = (adc_data.tsc_xp >> 8) & 0xFF;
+ tx_buf[4] = adc_data.tsc_ym & 0xFF;
+ tx_buf[5] = (adc_data.tsc_ym >> 8) & 0xFF;
+ tx_buf[6] = adc_data.tsc_yp & 0xFF;
+ tx_buf[7] = (adc_data.tsc_yp >> 8) & 0xFF;
+ return 8;
+ }
+ }
+ switch (rx_buf[1]) {
+ case APALIS_TK1_K20_TSC_XPL:
+ tx_buf[0] = adc_data.tsc_xp & 0xFF;
+ tx_buf[1] = (adc_data.tsc_xp >> 8) & 0xFF;
+ return 2;
+ case APALIS_TK1_K20_TSC_YML:
+ tx_buf[0] = adc_data.tsc_ym & 0xFF;
+ tx_buf[1] = (adc_data.tsc_ym >> 8) & 0xFF;
+ return 2;
+ case APALIS_TK1_K20_TSC_YPL:
+ tx_buf[0] = adc_data.tsc_yp & 0xFF;
+ tx_buf[1] = (adc_data.tsc_yp >> 8) & 0xFF;
+ return 2;
+ default:
+ return -ENOENT;
+ }
+ }
+ return -ENOENT;
+}
+
+int adc_registers(dspi_transfer_t *spi_transfer)
+{
+ uint8_t *rx_buf = spi_transfer->rxData;
+ uint8_t *tx_buf = &spi_transfer->txData[0];
+
+ if (rx_buf[0] == APALIS_TK1_K20_WRITE_INST) {
+ switch (rx_buf[1]) {
+ case APALIS_TK1_K20_ADCREG:
+ return 0;
+ default:
+ return -ENOENT;
+ }
+ } else if (rx_buf[0] == APALIS_TK1_K20_BULK_READ_INST) {
+ if (rx_buf[1] == APALIS_TK1_K20_ADC_CH0L) {
+ if (rx_buf[2] == 2) {
+ tx_buf[0] = adc_data.adc[0] & 0xFF;
+ tx_buf[1] = (adc_data.adc[0] >> 8) & 0xFF;
+ return 2;
+ } else if (rx_buf[2] == 8) {
+ tx_buf[0] = adc_data.adc[0] & 0xFF;
+ tx_buf[1] = (adc_data.adc[0] >> 8) & 0xFF;
+ tx_buf[2] = adc_data.adc[1] & 0xFF;
+ tx_buf[3] = (adc_data.adc[1] >> 8) & 0xFF;
+ tx_buf[4] = adc_data.adc[2] & 0xFF;
+ tx_buf[5] = (adc_data.adc[2] >> 8) & 0xFF;
+ tx_buf[6] = adc_data.adc[3] & 0xFF;
+ tx_buf[7] = (adc_data.adc[3] >> 8) & 0xFF;
+ return 8;
+ }
+ }
+ switch (rx_buf[1]){
+ case APALIS_TK1_K20_ADC_CH1L:
+ tx_buf[0] = adc_data.adc[1] & 0xFF;
+ tx_buf[1] = (adc_data.adc[1] >> 8) & 0xFF;
+ return 2;
+ case APALIS_TK1_K20_ADC_CH2L:
+ tx_buf[0] = adc_data.adc[2] & 0xFF;
+ tx_buf[1] = (adc_data.adc[2] >> 8) & 0xFF;
+ return 2;
+ case APALIS_TK1_K20_ADC_CH3L:
+ tx_buf[0] = adc_data.adc[3] & 0xFF;
+ tx_buf[1] = (adc_data.adc[3] >> 8) & 0xFF;
+ return 2;
+
+ default:
+ return -ENOENT;
+ }
+ }
+ return -ENOENT;
+}
+#endif
diff --git a/app/src/can_task.c b/app/src/can_task.c
new file mode 100644
index 0000000..e34d35d
--- /dev/null
+++ b/app/src/can_task.c
@@ -0,0 +1,470 @@
+
+#include "can_task.h"
+#include "com_task.h"
+#include "fsl_flexcan.h"
+
+/* special address description flags for the CAN_ID */
+#define CAN_EFF_FLAG 0x80000000U /* EFF/SFF is set in the MSB */
+#define CAN_RTR_FLAG 0x40000000U /* remote transmission request */
+#define CAN_ERR_FLAG 0x20000000U /* error message frame */
+
+#define TX_MESSAGE_BUFFER_NUM0 (9)
+
+#define CAN_FRAME_MAX_LEN 8
+#define CAN_HEADER_MAX_LEN 5
+#define CAN_TRANSFER_BUF_LEN (CAN_HEADER_MAX_LEN + CAN_FRAME_MAX_LEN)
+
+#define CANCTRL_MODMASK (BIT(1) | BIT(0))
+#define CANCTRL_INTEN BIT(2)
+#define CANINTF_RX BIT(3)
+#define CANINTF_TX BIT(4)
+#define CANINTF_ERR BIT(5)
+#define CANCTRL_ENABLE BIT(6)
+#define CANCTRL_INTMASK (CANINTF_RX | CANINTF_TX | CANINTF_ERR)
+
+#define EFLG_EWARN 0x01
+#define EFLG_RXWAR 0x02
+#define EFLG_TXWAR 0x04
+#define EFLG_RXEP 0x08
+#define EFLG_TXEP 0x10
+#define EFLG_TXBO 0x20
+#define EFLG_RXOVR 0x40
+
+struct can_registers {
+ CAN_Type *base;
+ flexcan_handle_t handle;
+ uint8_t can_enable;
+ uint8_t can_err_reg;
+ uint8_t can_mode;
+ uint8_t frames_in_buf;
+ uint8_t rx_buf_top;
+ uint8_t rx_buf_bottom;
+ uint8_t tx_counter;
+};
+
+static uint8_t data_buffer[2][CAN_RX_BUF_SIZE][CAN_TRANSFER_BUF_LEN];
+
+static struct can_registers can_regs[2];
+
+static inline void generate_can_irq(uint8_t id)
+{
+ if (id == 0) {
+ GPIO_TogglePinsOutput(GPIOB, 1u << 8u);
+ } else {
+ GPIO_TogglePinsOutput(GPIOE, 1u << 26u);
+ }
+}
+
+void can_tx_notify_task(void *pvParameters)
+{
+ uint32_t ulInterruptStatus;
+
+ while(1){
+ xTaskNotifyWait( 0x00, 0xFFFFFFFF, &ulInterruptStatus, portMAX_DELAY);
+ if (ulInterruptStatus & 0x01) {
+ registers[APALIS_TK1_K20_CANREG + APALIS_TK1_K20_CAN_DEV_OFFSET(0)] &= ~CANINTF_TX;
+ generate_can_irq(0);
+ }
+ if (ulInterruptStatus & 0x02) {
+ registers[APALIS_TK1_K20_CANREG + APALIS_TK1_K20_CAN_DEV_OFFSET(1)] &= ~CANINTF_TX;
+ generate_can_irq(1);
+ }
+ if (ulInterruptStatus & 0x04) {
+ registers[APALIS_TK1_K20_CANREG + APALIS_TK1_K20_CAN_DEV_OFFSET(0)] |= CANINTF_ERR;
+ generate_can_irq(0);
+ }
+ if (ulInterruptStatus & 0x08) {
+ registers[APALIS_TK1_K20_CANREG + APALIS_TK1_K20_CAN_DEV_OFFSET(1)] |= CANINTF_ERR;
+ generate_can_irq(1);
+ }
+ }
+}
+
+static BaseType_t flexcan_callback(CAN_Type *base, flexcan_handle_t *handle, status_t status, uint32_t result, void *userData)
+{
+ callback_message_t * cb = (callback_message_t*) userData;
+ BaseType_t reschedule = pdFALSE;
+
+ switch (status)
+ {
+ case kStatus_FLEXCAN_RxFifoIdle:
+ cb->async_status = pdTRUE;
+ xSemaphoreGiveFromISR(cb->sem, &reschedule);
+ break;
+
+ case kStatus_FLEXCAN_TxIdle:
+ if (TX_MESSAGE_BUFFER_NUM0 == result)
+ {
+ switch ((int)base)
+ {
+ case (int)CAN0:
+
+ xTaskNotifyFromISR(can_tx_notify_task_handle, 0x01, eSetBits, &reschedule);
+ break;
+ case (int)CAN1:
+ xTaskNotifyFromISR(can_tx_notify_task_handle, 0x02, eSetBits, &reschedule);
+ break;
+ }
+
+ }
+ break;
+
+ case kStatus_FLEXCAN_ErrorStatus:
+ if ((result & (kFLEXCAN_TxWarningIntFlag)) != 0) {
+ switch ((int)base)
+ {
+ case (int)CAN0:
+ registers[APALIS_TK1_K20_CANERR + APALIS_TK1_K20_CAN_DEV_OFFSET(0)] |= EFLG_TXWAR;
+ xTaskNotifyFromISR(can_tx_notify_task_handle, 0x04, eSetBits, &reschedule);
+ break;
+ case (int)CAN1:
+ registers[APALIS_TK1_K20_CANERR + APALIS_TK1_K20_CAN_DEV_OFFSET(1)] |= EFLG_TXWAR;
+ xTaskNotifyFromISR(can_tx_notify_task_handle, 0x08, eSetBits, &reschedule);
+ break;
+ }
+ }
+
+ if ((result & (kFLEXCAN_BusOffIntFlag)) != 0) {
+ switch ((int)base)
+ {
+ case (int)CAN0:
+ registers[APALIS_TK1_K20_CANERR + APALIS_TK1_K20_CAN_DEV_OFFSET(0)] |= EFLG_TXBO;
+ xTaskNotifyFromISR(can_tx_notify_task_handle, 0x04, eSetBits, &reschedule);
+ break;
+ case (int)CAN1:
+ registers[APALIS_TK1_K20_CANERR + APALIS_TK1_K20_CAN_DEV_OFFSET(1)] |= EFLG_TXBO;
+ xTaskNotifyFromISR(can_tx_notify_task_handle, 0x08, eSetBits, &reschedule);
+ break;
+ }
+ }
+ break;
+ default:
+ break;
+ }
+
+ return reschedule;
+}
+
+static void CAN_Init(uint8_t id)
+{
+ flexcan_config_t flexcanConfig;
+ flexcan_rx_fifo_config_t fifoConfig;
+ uint32_t fifoFilter = 0xFFFFFFFF;
+
+ FLEXCAN_GetDefaultConfig(&flexcanConfig);
+
+ flexcanConfig.baudRate = 1000000U; /* set default to 1Mbit/s*/
+
+ /* Init FlexCAN module. */
+ flexcanConfig.clkSrc = kFLEXCAN_ClkSrcPeri;
+ FLEXCAN_Init(can_regs[id].base, &flexcanConfig, CLOCK_GetFreq(kCLOCK_BusClk));
+
+ /* Create FlexCAN handle structure and set call back function. */
+ FLEXCAN_TransferCreateHandle(can_regs[id].base, &can_regs[id].handle, flexcan_callback,
+ can_regs[id].handle.userData);
+
+ /* Set Rx Mask to don't care on all bits. */
+ FLEXCAN_SetRxMbGlobalMask(can_regs[id].base, FLEXCAN_RX_MB_EXT_MASK(0x00, 0, 0));
+ FLEXCAN_SetRxFifoGlobalMask(can_regs[id].base, FLEXCAN_RX_MB_EXT_MASK(0x00, 0, 0));
+
+ fifoConfig.idFilterNum = 0;
+ fifoConfig.idFilterTable = &fifoFilter;
+ fifoConfig.idFilterType = kFLEXCAN_RxFifoFilterTypeC;
+ fifoConfig.priority = kFLEXCAN_RxFifoPrioHigh;
+ FLEXCAN_SetRxFifoConfig(can_regs[id].base, &fifoConfig, true);
+
+ /* errata #5641 */
+ can_regs[id].base->MB[TX_MESSAGE_BUFFER_NUM0 - 1].ID = 0x0;
+ can_regs[id].base->MB[TX_MESSAGE_BUFFER_NUM0 - 1].WORD0 = 0x0;
+ can_regs[id].base->MB[TX_MESSAGE_BUFFER_NUM0 - 1].WORD1 = 0x0;
+ can_regs[id].base->MB[TX_MESSAGE_BUFFER_NUM0 - 1].CS = CAN_CS_CODE(0x8);
+ can_regs[id].base->MB[TX_MESSAGE_BUFFER_NUM0 - 1].CS = CAN_CS_CODE(0x8);
+
+ /* Setup Tx Message Buffer. */
+ FLEXCAN_SetTxMbConfig(can_regs[id].base, TX_MESSAGE_BUFFER_NUM0, true);
+}
+
+uint8_t available_data[2];
+
+static void can_calculate_available_data(uint8_t id) {
+ taskENTER_CRITICAL();
+ if ( can_regs[id].rx_buf_bottom <= can_regs[id].rx_buf_top)
+ available_data[id] = can_regs[id].rx_buf_top - can_regs[id].rx_buf_bottom;
+ else
+ available_data[id] = CAN_RX_BUF_SIZE - can_regs[id].rx_buf_bottom;
+
+ available_data[id] = (available_data[id] > APALIS_TK1_MAX_CAN_DMA_XREF) ? APALIS_TK1_MAX_CAN_DMA_XREF:available_data[id];
+ registers[APALIS_TK1_K20_CAN_IN_BUF_CNT + APALIS_TK1_K20_CAN_DEV_OFFSET(id)] = available_data[id];
+
+ if (can_regs[id].rx_buf_bottom == can_regs[id].rx_buf_top)
+ registers[APALIS_TK1_K20_CANREG + APALIS_TK1_K20_CAN_DEV_OFFSET(id)] &= ~CANINTF_RX;
+ else
+ registers[APALIS_TK1_K20_CANREG + APALIS_TK1_K20_CAN_DEV_OFFSET(id)] |= CANINTF_RX;
+ taskEXIT_CRITICAL();
+}
+
+void can_spi_read_complete(uint8_t id)
+{
+ can_calculate_available_data(id);
+}
+
+static void frame_to_buffer(flexcan_frame_t *frame, uint8_t id) {
+ uint8_t top_frame = can_regs[id].rx_buf_top;
+ switch (frame->format){
+ case kFLEXCAN_FrameFormatExtend:
+ data_buffer[id][top_frame][0] = frame->id & 0xFF;
+ data_buffer[id][top_frame][1] = (frame->id >> 8 ) & 0xFF;
+ data_buffer[id][top_frame][2] = (frame->id >> 16 ) & 0xFF;
+ data_buffer[id][top_frame][3] = (frame->id >> 24 ) & 0x1F;
+ data_buffer[id][top_frame][3] |= CAN_EFF_FLAG >> 24;
+ break;
+ case kFLEXCAN_FrameFormatStandard:
+ data_buffer[id][top_frame][0] = (frame->id >> 18) & 0xFF;
+ data_buffer[id][top_frame][1] = ((frame->id >> 18) >> 8 ) & 0x7F;
+ data_buffer[id][top_frame][2] = 0x00;
+ data_buffer[id][top_frame][3] = 0x00;
+ break;
+ }
+
+ data_buffer[id][top_frame][3] |= frame->type ? (CAN_RTR_FLAG >> 24):0x00;
+ data_buffer[id][top_frame][4] = frame->length;
+
+ switch (frame->length) {
+ case 8:data_buffer[id][top_frame][5 + 7] = frame->dataByte7;
+ case 7:data_buffer[id][top_frame][5 + 6] = frame->dataByte6;
+ case 6:data_buffer[id][top_frame][5 + 5] = frame->dataByte5;
+ case 5:data_buffer[id][top_frame][5 + 4] = frame->dataByte4;
+ case 4:data_buffer[id][top_frame][5 + 3] = frame->dataByte3;
+ case 3:data_buffer[id][top_frame][5 + 2] = frame->dataByte2;
+ case 2:data_buffer[id][top_frame][5 + 1] = frame->dataByte1;
+ case 1:data_buffer[id][top_frame][5] = frame->dataByte0;
+ }
+
+ can_regs[id].rx_buf_top++;
+ can_regs[id].rx_buf_top %= CAN_RX_BUF_SIZE;
+
+ can_calculate_available_data(id);
+}
+
+static inline void can_fifo_rx(uint8_t id, flexcan_fifo_transfer_t * rxXfer)
+{
+ callback_message_t *can_msg = (callback_message_t *) can_regs[id].handle.userData;
+
+ FLEXCAN_TransferReceiveFifoNonBlocking(can_regs[id].base, &can_regs[id].handle, rxXfer);
+ xSemaphoreTake(can_msg->sem, portMAX_DELAY);
+ if (can_msg->async_status == pdTRUE) {
+ frame_to_buffer(rxXfer->frame, id);
+ can_regs[id].frames_in_buf++;
+ generate_can_irq(id);
+ if (can_regs[id].frames_in_buf >= CAN_RX_BUF_SIZE)
+ vTaskSuspend(NULL);
+ }
+}
+
+void can0_task(void *pvParameters) {
+ flexcan_frame_t rxFrame;
+ flexcan_fifo_transfer_t rxXfer;
+ callback_message_t can_msg;
+
+ can_msg.sem = xSemaphoreCreateBinary();
+ can_msg.async_status = pdFALSE;
+ memset(&can_regs[0], 0x00u, sizeof(struct can_registers));
+ can_regs[0].handle.userData = (void *) &can_msg;
+ can_regs[0].base = CAN0;
+
+ CAN_Init(0);
+ PRINTF("CAN0 init done \r\n");
+
+ rxXfer.frame = &rxFrame;
+
+ while(1)
+ {
+ can_fifo_rx(0, &rxXfer);
+ }
+ vSemaphoreDelete(can_msg.sem);
+}
+
+void can1_task(void *pvParameters) {
+ flexcan_frame_t rxFrame;
+ flexcan_fifo_transfer_t rxXfer;
+ callback_message_t can_msg;
+
+ can_msg.sem = xSemaphoreCreateBinary();
+ can_msg.async_status = pdFALSE;
+ memset(&can_regs[1], 0x00u, sizeof(struct can_registers));
+ can_regs[1].handle.userData = (void *) &can_msg;
+ can_regs[1].base = CAN1;
+
+ CAN_Init(1);
+ PRINTF("CAN1 init done \r\n");
+ rxXfer.frame = &rxFrame;
+
+ while(1)
+ {
+ can_fifo_rx(1, &rxXfer);
+ }
+ vSemaphoreDelete(can_msg.sem);
+
+}
+
+static void can_change_mode(int id, uint8_t new_mode)
+{
+ can_regs[id].can_mode = new_mode;
+
+ FLEXCAN_SetMode(can_regs[id].base, new_mode);
+
+}
+
+static void can_enable(int id, uint8_t enable)
+{
+ can_regs[id].can_mode = enable;
+
+ if (enable) {
+ callback_message_t *can_msg = (callback_message_t *) can_regs[id].handle.userData;
+ FLEXCAN_ExitFreezeMode(can_regs[id].base);
+ can_msg->async_status = pdFALSE;
+ xSemaphoreGive(can_msg->sem);
+ generate_can_irq(id);
+ } else {
+ FLEXCAN_TransferAbortReceiveFifo(can_regs[id].base, &can_regs[id].handle);
+ FLEXCAN_EnterFreezeMode(can_regs[id].base);
+ }
+
+}
+
+static uint8_t set_canreg (int id, uint8_t value)
+{
+ registers[APALIS_TK1_K20_CANREG + APALIS_TK1_K20_CAN_DEV_OFFSET(id)] = value;
+ if ( can_regs[id].can_mode != (value & CANCTRL_MODMASK) )
+ can_change_mode(id, (value & CANCTRL_MODMASK));
+ if (can_regs[id].can_enable != (value & CANCTRL_ENABLE))
+ can_enable(id, (value & CANCTRL_ENABLE));
+ return 0;
+}
+
+static uint8_t clr_canreg (int id, uint8_t mask)
+{
+ mask &= (CANINTF_RX | CANINTF_TX | CANINTF_ERR);
+ registers[APALIS_TK1_K20_CANREG + APALIS_TK1_K20_CAN_DEV_OFFSET(id)] &= ~mask;
+ return 0;
+}
+
+static uint8_t set_canerr (int id, uint8_t value)
+{
+ registers[APALIS_TK1_K20_CANERR + APALIS_TK1_K20_CAN_DEV_OFFSET(id)] = value;
+ return 0;
+}
+
+static uint8_t set_canbadreg (int id, uint8_t value)
+{
+
+ FLEXCAN_SetBitRate(can_regs[id].base, CLOCK_GetFreq(kCLOCK_BusClk), value * APALIS_TK1_CAN_CLK_UNIT);
+ return 0;
+}
+
+static uint8_t set_canbittiming (int id, uint16_t value, int16_t mask)
+{
+ /* According to NXP we should use default settings */
+ return 0;
+}
+
+uint8_t can_sendframe(uint8_t id, uint8_t *data, uint8_t len)
+{
+ flexcan_mb_transfer_t txXfer;
+ flexcan_frame_t tx_frame;
+
+ tx_frame.length = data[4];
+ tx_frame.id = (data[3] << 24) + (data[2] << 16) + (data[1] << 8) + data[0];
+
+ tx_frame.format = (data[3] << 24 & CAN_EFF_FLAG) ?
+ kFLEXCAN_FrameFormatExtend:kFLEXCAN_FrameFormatStandard;
+ tx_frame.type = (data[3] << 24 & CAN_RTR_FLAG) ?
+ kFLEXCAN_FrameTypeRemote:kFLEXCAN_FrameTypeData;
+
+ if (tx_frame.format == kFLEXCAN_FrameFormatExtend)
+ tx_frame.id = FLEXCAN_ID_EXT(tx_frame.id);
+ else
+ tx_frame.id = FLEXCAN_ID_STD(tx_frame.id);
+
+ tx_frame.dataByte0 = data[5];
+ tx_frame.dataByte1 = data[5 + 1];
+ tx_frame.dataByte2 = data[5 + 2];
+ tx_frame.dataByte3 = data[5 + 3];
+ tx_frame.dataByte4 = data[5 + 4];
+ tx_frame.dataByte5 = data[5 + 5];
+ tx_frame.dataByte6 = data[5 + 6];
+ tx_frame.dataByte7 = data[5 + 7];
+
+ txXfer.frame = &tx_frame;
+ txXfer.mbIdx = TX_MESSAGE_BUFFER_NUM0;
+ if( tx_frame.length <= 8 ) {
+ FLEXCAN_TransferSendNonBlocking(can_regs[id].base , &can_regs[id].handle, &txXfer);
+ registers[APALIS_TK1_K20_CANREG + APALIS_TK1_K20_CAN_DEV_OFFSET(id)] |= CANINTF_TX;
+ return 0;
+ }
+ else {
+ registers[APALIS_TK1_K20_CANREG + APALIS_TK1_K20_CAN_DEV_OFFSET(id)] &= ~CANINTF_TX;
+ generate_can_irq(id);
+ return -EIO;
+ }
+}
+
+uint16_t can_readframe(uint8_t id, dspi_transfer_t *spi_transfer)
+{
+ uint8_t rx_size;
+ spi_transfer->txData = data_buffer[id][can_regs[id].rx_buf_bottom];
+ rx_size = spi_transfer->rxData[2] / CAN_TRANSFER_BUF_LEN; /* size in frames, not bytes */
+ if (rx_size > available_data[id])
+ rx_size = available_data[id];
+
+ can_regs[id].rx_buf_bottom = can_regs[id].rx_buf_bottom + rx_size;
+ can_regs[id].rx_buf_bottom %= CAN_RX_BUF_SIZE;
+
+ can_regs[id].frames_in_buf -= rx_size;
+
+ return rx_size * CAN_TRANSFER_BUF_LEN;
+}
+
+int canx_registers(dspi_transfer_t *spi_transfer, int id)
+{
+ uint8_t *rx_buf = spi_transfer->rxData;
+ if (rx_buf[0] == APALIS_TK1_K20_WRITE_INST) {
+ rx_buf[1] -= APALIS_TK1_K20_CAN_DEV_OFFSET(id);
+ switch (rx_buf[1]) {
+ case APALIS_TK1_K20_CANREG:
+ return set_canreg(id, rx_buf[2]);
+ case APALIS_TK1_K20_CANREG_CLR:
+ return clr_canreg(id, rx_buf[2]);
+ case APALIS_TK1_K20_CANERR:
+ return set_canerr(id, rx_buf[2]);
+ case APALIS_TK1_K20_CAN_BAUD_REG:
+ return set_canbadreg(id, rx_buf[2]);
+ case APALIS_TK1_K20_CAN_BIT_1:
+ return set_canbittiming(id, rx_buf[2], 0x00FF);
+ case APALIS_TK1_K20_CAN_BIT_2:
+ return set_canbittiming(id, (rx_buf[2] << 8), 0xFF00);
+ default:
+ return -EIO;
+ }
+
+ } else if (rx_buf[0] == APALIS_TK1_K20_BULK_READ_INST) {
+ rx_buf[1] -= APALIS_TK1_K20_CAN_DEV_OFFSET(id);
+ switch (rx_buf[1]) {
+ case APALIS_TK1_K20_CAN_IN_BUF:
+ return can_readframe(id, spi_transfer);
+ default:
+ return -EIO;
+ }
+ } else if (rx_buf[0] == APALIS_TK1_K20_BULK_WRITE_INST) {
+ rx_buf[1] -= APALIS_TK1_K20_CAN_DEV_OFFSET(id);
+ switch (rx_buf[1]) {
+ case APALIS_TK1_K20_CAN_OUT_BUF:
+ can_sendframe(id, &rx_buf[3], rx_buf[2]);
+ return 0;
+ default:
+ return -EIO;
+ }
+ }
+ return -EIO;
+}
+
diff --git a/app/src/com_task.c b/app/src/com_task.c
new file mode 100644
index 0000000..d6bc97d
--- /dev/null
+++ b/app/src/com_task.c
@@ -0,0 +1,279 @@
+
+#include "com_task.h"
+#include "can_task.h"
+#include "gpio_ext.h"
+#include "adc_task.h"
+
+volatile uint8_t registers[APALIS_TK1_K20_LAST_REG];
+volatile uint8_t regRxHandled;
+
+/* Put FW version at known address in a binary. Make it 32-bit to have room for the future */
+#ifndef TESTER_BUILD
+const uint32_t __attribute__((section(".FwVersion"), used)) fw_version = APALIS_TK1_K20_FW_VER;
+#else
+const uint32_t __attribute__((section(".FwVersion"), used)) fw_version = APALIS_TK1_K20_TESTER_FW_VER;
+#endif
+
+static dspi_slave_handle_t spi_handle;
+static uint8_t slaveRxData[APALIS_TK1_K20_MAX_BULK + APALIS_TK1_K20_HEADER];
+static uint8_t slaveTxData[APALIS_TK1_K20_MAX_BULK + APALIS_TK1_K20_HEADER];
+
+#ifdef SPI_DMA
+dspi_slave_edma_handle_t g_dspi_edma_s_handle;
+edma_handle_t dspiEdmaSlaveRxHandle;
+edma_handle_t dspiEdmaSlaveTxHandle;
+#endif
+
+void generate_irq(uint8_t irq) {
+ if (!(registers[APALIS_TK1_K20_MSQREG] & BIT(irq))) {
+ taskENTER_CRITICAL();
+ registers[APALIS_TK1_K20_IRQREG] |= BIT(irq);
+ /* Toggle INT1 pin */
+ GPIO_TogglePinsOutput(GPIOA, 1u << 16u);
+ taskEXIT_CRITICAL();
+ }
+}
+
+void clear_irq_flag(uint8_t irq) {
+ registers[APALIS_TK1_K20_IRQREG] &= ~irq;
+}
+
+uint8_t get_control_reg()
+{
+ return registers[APALIS_TK1_K20_CTRREG];
+
+}
+
+void set_control_reg(uint8_t value)
+{
+ registers[APALIS_TK1_K20_CTRREG] = value;
+}
+
+uint8_t get_status_reg()
+{
+ return registers[APALIS_TK1_K20_STAREG];
+
+}
+
+void set_status_reg(uint8_t value)
+{
+ registers[APALIS_TK1_K20_STAREG] = value;
+}
+
+uint8_t get_mask_reg()
+{
+ return registers[APALIS_TK1_K20_MSQREG];
+
+}
+
+void set_mask_reg(uint8_t value)
+{
+ registers[APALIS_TK1_K20_MSQREG] = value;
+}
+
+uint8_t get_irq_reg()
+{
+ return registers[APALIS_TK1_K20_IRQREG];
+
+}
+
+void set_irq_reg(uint8_t value)
+{
+ /* Clear IRQ flag on 1 */
+ clear_irq_flag(value);
+
+}
+
+inline int general_registers(dspi_transfer_t * spi_transfer)
+{
+ uint8_t *rx_buf = spi_transfer->rxData;
+
+ if (rx_buf[0] == APALIS_TK1_K20_WRITE_INST) {
+ switch (rx_buf[1]) {
+ case APALIS_TK1_K20_STAREG:
+ set_status_reg(rx_buf[2]);
+ return 1;
+ case APALIS_TK1_K20_REVREG:
+ return -ENOENT;
+ case APALIS_TK1_K20_IRQREG:
+ set_irq_reg(rx_buf[2]);
+ return 1;
+ case APALIS_TK1_K20_CTRREG:
+ set_control_reg(rx_buf[2]);
+ return 1;
+ case APALIS_TK1_K20_MSQREG:
+ set_mask_reg(rx_buf[2]);
+ return 1;
+ default:
+ return -ESRCH;
+ }
+ }
+
+
+ return -ENXIO;
+}
+
+
+inline void SPI_main_callback(status_t status, void *userData)
+{
+ callback_message_t * cb = (callback_message_t*) userData;
+ BaseType_t reschedule = pdFALSE;
+
+ if (status == kStatus_Success)
+ {
+ xSemaphoreGiveFromISR(cb->sem, &reschedule);
+ }
+#if 0
+ if (status == kStatus_DSPI_Error)
+ {
+ __NOP();
+ }
+#endif
+ portYIELD_FROM_ISR(reschedule);
+}
+
+static void SPI_callback(SPI_Type *base, dspi_slave_handle_t *handle, status_t status, void *userData)
+{
+ SPI_main_callback(status, userData);
+}
+
+static void SPI_EDMA_callback(SPI_Type *base, dspi_slave_edma_handle_t *handle, status_t status, void *userData)
+{
+ SPI_main_callback(status, userData);
+}
+
+static dspi_slave_config_t spi2_slaveConfig;
+
+static void SPI_init() {
+ gpio_pin_config_t gpio_out_config = {
+ kGPIO_DigitalOutput, 0,
+ };
+ GPIO_PinInit(GPIOD, 11u, &gpio_out_config);
+ /* Slave config */
+ spi2_slaveConfig.whichCtar = kDSPI_Ctar0;
+ spi2_slaveConfig.ctarConfig.bitsPerFrame = 8;
+ spi2_slaveConfig.ctarConfig.cpol = kDSPI_ClockPolarityActiveHigh;
+ spi2_slaveConfig.ctarConfig.cpha = kDSPI_ClockPhaseSecondEdge;
+ spi2_slaveConfig.enableContinuousSCK = false;
+ spi2_slaveConfig.enableRxFifoOverWrite = true;
+ spi2_slaveConfig.enableModifiedTimingFormat = false;
+ spi2_slaveConfig.samplePoint = kDSPI_SckToSin0Clock;
+ PRINTF("SPI init \r\n");
+ DSPI_SlaveInit(SPI2, &spi2_slaveConfig);
+ DSPI_SlaveTransferCreateHandle(SPI2, &spi_handle, SPI_callback, spi_handle.userData);
+
+ /* Set dspi slave interrupt priority higher. */
+ NVIC_SetPriority(SPI2_IRQn, 5U);
+ GPIO_ClearPinsOutput(GPIOA, 1u << 29u); /* INT2 active */
+ PRINTF("SPI init done \r\n");
+
+}
+
+void spi_task(void *pvParameters) {
+ callback_message_t spi_msg;
+ dspi_transfer_t slaveXfer;
+ int ret = 0;
+ int can_read = -1;
+#ifdef SPI_DMA
+ uint32_t slaveRxChannel, slaveTxChannel;
+ edma_config_t userConfig;
+#endif
+
+ spi_msg.sem = xSemaphoreCreateBinary();
+ spi_handle.userData = &spi_msg;
+ SPI_init();
+#ifdef SPI_DMA
+ slaveRxChannel = 0U;
+ slaveTxChannel = 1U;
+
+ DMAMUX_Init(DMAMUX);
+ DMAMUX_SetSource(DMAMUX, slaveRxChannel, kDmaRequestMux0SPI2Rx);
+ DMAMUX_EnableChannel(DMAMUX, slaveRxChannel);
+ DMAMUX_SetSource(DMAMUX, slaveTxChannel, kDmaRequestMux0SPI2Tx);
+ DMAMUX_EnableChannel(DMAMUX, slaveTxChannel);
+
+ EDMA_GetDefaultConfig(&userConfig);
+ EDMA_Init(DMA0, &userConfig);
+
+ EDMA_CreateHandle(&dspiEdmaSlaveRxHandle, DMA0, slaveRxChannel);
+ EDMA_CreateHandle(&dspiEdmaSlaveTxHandle, DMA0, slaveTxChannel);
+
+ g_dspi_edma_s_handle.userData = &spi_msg;
+ DSPI_SlaveTransferCreateHandleEDMA(SPI2, &g_dspi_edma_s_handle, SPI_EDMA_callback,
+ &spi_msg, &dspiEdmaSlaveRxHandle, &dspiEdmaSlaveTxHandle);
+#endif
+ memset((uint8_t *)registers, 0x00, APALIS_TK1_K20_LAST_REG);
+ registers[APALIS_TK1_K20_REVREG] = APALIS_TK1_K20_FW_VER;
+ GPIO_SetPinsOutput(GPIOA, 1u << 29u); /* INT2 idle */
+ slaveXfer.configFlags = kDSPI_SlaveCtar0;
+
+ while(1){
+ slaveXfer.txData = NULL;/* no MISO traffic*/
+ slaveXfer.rxData = slaveRxData;
+ slaveXfer.dataSize = 3;
+ /* Wait for instructions from SoC */
+ ret = DSPI_SlaveTransferNonBlocking(SPI2, &spi_handle, &slaveXfer);
+ if ( ret == kStatus_Success) {
+ xSemaphoreTake(spi_msg.sem, portMAX_DELAY);
+
+ if (slaveRxData[0] != APALIS_TK1_K20_READ_INST) {
+ taskENTER_CRITICAL();
+ slaveXfer.txData = slaveTxData;
+ slaveXfer.rxData = slaveRxData;
+ if (slaveRxData[1] <= 0x05) {
+ ret = general_registers(&slaveXfer);
+#ifndef TESTER_BUILD
+ } else if ((slaveRxData[1] >= APALIS_TK1_K20_CANREG + APALIS_TK1_K20_CAN_DEV_OFFSET(0))
+ && (slaveRxData[1] <= APALIS_TK1_K20_CAN_OUT_BUF_END + APALIS_TK1_K20_CAN_DEV_OFFSET(0))) {
+ ret = canx_registers(&slaveXfer, 0);
+ can_read = 0;
+
+ } else if ((slaveRxData[1] >= APALIS_TK1_K20_CANREG + APALIS_TK1_K20_CAN_DEV_OFFSET(1))
+ && (slaveRxData[1] <= APALIS_TK1_K20_CAN_OUT_BUF_END + APALIS_TK1_K20_CAN_DEV_OFFSET(1))) {
+ ret = canx_registers(&slaveXfer, 1);
+ can_read = 1;
+#endif
+#ifdef BOARD_USES_ADC
+ } else if ((slaveRxData[1] >= APALIS_TK1_K20_ADCREG) && (slaveRxData[1] <= APALIS_TK1_K20_ADC_CH3H)) {
+ ret = adc_registers(&slaveXfer);
+
+ } else if ((slaveRxData[1] >= APALIS_TK1_K20_TSCREG) && (slaveRxData[1] <= APALIS_TK1_K20_TSC_YPH)) {
+ ret = tsc_registers(&slaveXfer);
+#endif
+ } else if ((slaveRxData[1] >= APALIS_TK1_K20_GPIOREG) && (slaveRxData[1] <= APALIS_TK1_K20_GPIO_STA)) {
+ ret = gpio_registers(&slaveXfer);
+ } else {
+ /* Register not defined */
+ ret = -EINVAL;
+ }
+
+ if (ret < 0) {
+ PRINTF("Invalid read/write ret = %d rx[0] = 0x%x, rx[1] = 0x%x, rx[2] = 0x%x\r\n",
+ ret, slaveRxData[0], slaveRxData[1], slaveRxData[2]);
+ }
+
+ if (slaveRxData[0] == APALIS_TK1_K20_BULK_READ_INST) {
+ slaveXfer.dataSize = ret;
+ slaveXfer.rxData = NULL;
+#ifdef SPI_DMA
+ DSPI_SlaveTransferEDMA(SPI2, &g_dspi_edma_s_handle, &slaveXfer);
+#else
+ DSPI_SlaveTransferNonBlocking(SPI2, &spi_handle, &slaveXfer);
+#endif
+ taskEXIT_CRITICAL();
+ xSemaphoreTake(spi_msg.sem, portMAX_DELAY);
+
+ if (can_read >= 0) {
+ can_spi_read_complete(can_read);
+ can_read = -1;
+ }
+ } else {
+ taskEXIT_CRITICAL();
+ }
+ }
+ } else {
+ /* Something went wrong, retry */
+ DSPI_SlaveTransferAbort(SPI2, &spi_handle);
+ }
+ }
+}
diff --git a/app/src/gpio_ext.c b/app/src/gpio_ext.c
new file mode 100644
index 0000000..e0d55fb
--- /dev/null
+++ b/app/src/gpio_ext.c
@@ -0,0 +1,132 @@
+/*
+ * gpio_ext.c
+ *
+ */
+
+#include "gpio_ext.h"
+#include "com_task.h"
+#include "errno.h"
+
+extern const struct gpio_id *gpio_list;
+
+
+static inline int port_type_to_int(PORT_Type *port)
+{
+ switch ((int) port) {
+ case PORTA_BASE:
+ return 0;
+ case PORTB_BASE:
+ return 1;
+ case PORTC_BASE:
+ return 2;
+ case PORTD_BASE:
+ return 3;
+ case PORTE_BASE:
+ return 4;
+ default:
+ return -EINVAL;
+ }
+}
+
+/* returns GPIO index in gpio_list table and -EINVAL
+ * if there is no entry for this gpio.
+ */
+static int is_gpio_valid(uint8_t pin)
+{
+ uint16_t i;
+ int temp;
+ if (pin == 0xFF)
+ return -EINVAL;
+
+ for (i = 0; i < sizeof(gpio_list)/sizeof(struct gpio_id); i++){
+ temp = port_type_to_int(gpio_list[i].port) * 32;
+ temp += gpio_list[i].pin;
+ if ( temp == pin ) {
+ return i;
+ }
+ if (temp > pin)
+ return -EINVAL;
+ }
+
+ return -EINVAL;
+}
+
+static int set_gpio_status(uint8_t status, int index)
+{
+ gpio_pin_config_t gpio_config;
+
+ gpio_config.pinDirection = (status & APALIS_TK1_K20_GPIO_STA_OE) ? kGPIO_DigitalOutput : kGPIO_DigitalInput;
+ gpio_config.outputLogic = (status & APALIS_TK1_K20_GPIO_STA_VAL);
+
+ if (index >= 0)
+ GPIO_PinInit(gpio_list[index].gpio, gpio_list[index].pin, &gpio_config);
+ else
+ return index;
+
+ return 0;
+}
+
+
+static uint8_t get_gpio_status(int index)
+{
+ uint8_t status;
+ GPIO_Type *base;
+ uint32_t gpio_pin;
+
+ if (index == -EINVAL)
+ return 0xFF;
+ base = gpio_list[index].gpio;
+ gpio_pin = gpio_list[index].pin;
+
+ if (((base->PDDR) >> gpio_pin) & 0x01U) {
+ status = APALIS_TK1_K20_GPIO_STA_OE;
+ status += (((base->PDOR) >> gpio_pin) & 0x01U) ? APALIS_TK1_K20_GPIO_STA_VAL : 0x00;
+ } else {
+ status = 0x00;
+ status += (((base->PDIR) >> gpio_pin) & 0x01U) ? APALIS_TK1_K20_GPIO_STA_VAL : 0x00;
+ }
+
+ return status;
+}
+
+int gpio_registers(dspi_transfer_t *spi_transfer)
+{
+ uint8_t *rx_buf = spi_transfer->rxData;
+ int index;
+
+ if (rx_buf[0] == APALIS_TK1_K20_WRITE_INST) {
+ switch (rx_buf[1]) {
+ case APALIS_TK1_K20_GPIOREG:
+ return -ENOENT;
+ break;
+ case APALIS_TK1_K20_GPIO_NO:
+ index = is_gpio_valid(rx_buf[2]);
+ if (index >= 0){
+ registers[APALIS_TK1_K20_GPIO_NO]= rx_buf[2];
+ registers[APALIS_TK1_K20_GPIO_STA] = get_gpio_status(index);
+ return 1;
+ } else {
+ registers[APALIS_TK1_K20_GPIO_NO] = 0xFF;
+ return -ENOENT;
+ }
+ break;
+ case APALIS_TK1_K20_GPIO_STA:
+ index = is_gpio_valid(registers[APALIS_TK1_K20_GPIO_NO]);
+ if (index >= 0){
+ set_gpio_status(rx_buf[2], index);
+ registers[APALIS_TK1_K20_GPIO_STA] = get_gpio_status(index);
+ return 1;
+ } else {
+ return -ENOENT;
+ }
+ break;
+ default:
+ return -ENOENT;
+ }
+ }
+ return -ENOENT;
+}
+
+
+
+
diff --git a/app/src/main.c b/app/src/main.c
new file mode 100644
index 0000000..1c36984
--- /dev/null
+++ b/app/src/main.c
@@ -0,0 +1,139 @@
+/*
+ * Copyright (c) 2013 - 2016, Freescale Semiconductor, Inc.
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without modification,
+ * are permitted provided that the following conditions are met:
+ *
+ * o Redistributions of source code must retain the above copyright notice, this list
+ * of conditions and the following disclaimer.
+ *
+ * o Redistributions in binary form must reproduce the above copyright notice, this
+ * list of conditions and the following disclaimer in the documentation and/or
+ * other materials provided with the distribution.
+ *
+ * o Neither the name of Freescale Semiconductor, Inc. nor the names of its
+ * contributors may be used to endorse or promote products derived from this
+ * software without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
+ * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
+ * WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
+ * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
+ * ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
+ * (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+ * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
+ * ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+ * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
+ * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ */
+
+/**
+ * This is template for main module created by New Kinetis SDK 2.x Project Wizard. Enjoy!
+ **/
+
+#include <string.h>
+
+#include "board.h"
+#include "pin_mux.h"
+#include "clock_config.h"
+#include "fsl_debug_console.h"
+#include "com_task.h"
+#include "can_task.h"
+#include "adc_task.h"
+
+/* FreeRTOS kernel includes. */
+#include "FreeRTOS.h"
+#include "task.h"
+#include "queue.h"
+#include "timers.h"
+
+
+#if ((defined USB_HOST_CONFIG_KHCI) && (USB_HOST_CONFIG_KHCI))
+#define CONTROLLER_ID kUSB_ControllerKhci0
+#endif
+#if ((defined USB_HOST_CONFIG_EHCI) && (USB_HOST_CONFIG_EHCI))
+#define CONTROLLER_ID kUSB_ControllerEhci0
+#endif
+
+#ifdef BOARD_USES_ADC
+TaskHandle_t adc_task_handle;
+TaskHandle_t tsc_task_handle;
+#endif
+#ifndef TESTER_BUILD
+TaskHandle_t can0_task_handle;
+TaskHandle_t can1_task_handle;
+TaskHandle_t can_tx_notify_task_handle;
+#endif
+TaskHandle_t spi_task_handle;
+
+
+/*!
+ * @brief Application entry point.
+ */
+int main(void) {
+
+ /* Init board hardware. */
+ BOARD_InitPins();
+ BOARD_BootClockRUN();
+#ifndef TESTER_BUILD
+ BOARD_InitDebugConsole();
+#endif
+ PRINTF("Apalis K20 Firmware Version %d.%d\r\n", FW_MAJOR, FW_MINOR);
+
+ /* Create RTOS task */
+ if(xTaskCreate(spi_task, "SPI_task", 1000L / sizeof(portSTACK_TYPE), NULL, 4, &spi_task_handle) != pdPASS)
+ {
+ PRINTF("create SPI task error\r\n");
+ }
+#ifndef TESTER_BUILD
+ if(xTaskCreate(can0_task, "CAN0_task", 1000L / sizeof(portSTACK_TYPE), NULL, 2, &can0_task_handle) != pdPASS)
+ {
+ PRINTF("create CAN0 task error\r\n");
+ }
+
+ if(xTaskCreate(can1_task, "CAN1_task", 1000L / sizeof(portSTACK_TYPE), NULL, 2, &can1_task_handle) != pdPASS)
+ {
+ PRINTF("create CAN1 task error\r\n");
+ }
+
+ if(xTaskCreate(can_tx_notify_task, "CAN_tx_notify_task", 1000L / sizeof(portSTACK_TYPE), NULL, 3, &can_tx_notify_task_handle) != pdPASS)
+ {
+ PRINTF("create CAN TX notify task error\r\n");
+ }
+#endif
+#ifdef BOARD_USES_ADC
+ if(xTaskCreate(adc_task, "ADC_task", 1000L / sizeof(portSTACK_TYPE), NULL, 2, &adc_task_handle) != pdPASS)
+ {
+ PRINTF("create ADC task error\r\n");
+ }
+
+ if(xTaskCreate(tsc_task, "TSC_task", 1000L / sizeof(portSTACK_TYPE), NULL, 2, &tsc_task_handle) != pdPASS)
+ {
+ PRINTF("create TSC task error\r\n");
+ }
+#endif
+
+ NVIC_SetPriority(CAN0_ORed_Message_buffer_IRQn, 7u);
+ NVIC_SetPriority(CAN0_Bus_Off_IRQn, 8u);
+ NVIC_SetPriority(CAN0_Error_IRQn, 8u);
+ NVIC_SetPriority(CAN0_Tx_Warning_IRQn, 8u);
+ NVIC_SetPriority(CAN0_Rx_Warning_IRQn, 8u);
+ NVIC_SetPriority(CAN0_Wake_Up_IRQn, 8u);
+ NVIC_SetPriority(CAN1_ORed_Message_buffer_IRQn, 7u);
+ NVIC_SetPriority(CAN1_Bus_Off_IRQn, 8u);
+ NVIC_SetPriority(CAN1_Error_IRQn, 8u);
+ NVIC_SetPriority(CAN1_Tx_Warning_IRQn, 8u);
+ NVIC_SetPriority(CAN1_Rx_Warning_IRQn, 8u);
+ NVIC_SetPriority(CAN1_Wake_Up_IRQn, 8u);
+ NVIC_SetPriority(SPI2_IRQn, 5u);
+ NVIC_SetPriority(DMA0_IRQn, 6u);
+ vTaskStartScheduler();
+
+ for(;;) { /* Infinite loop to avoid leaving the main function */
+ __asm("NOP"); /* something to use as a breakpoint stop while looping */
+ }
+}
+
+
+