products/aocpu: Rollback the multi-proudct code modification. [1/1]
PD#SWPL-61630
Problem:
Rollback the multi-proudct code modification.
Solution:
Rollback the multi-proudct code modification.
Verify:
T5W_AT301/AT309
Change-Id: I405be4b77c691bc8660a0a1083435b522a5bdf31
Signed-off-by: Xiaohu.Huang <xiaohu.huang@amlogic.com>
diff --git a/CMakeLists.txt b/CMakeLists.txt
index b23984d..a9dbd7f 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -6,10 +6,10 @@
target_include_directories(${TARGET_NAME} PUBLIC include)
aml_sources(
- ${BOARD}/fsm.c
- ${BOARD}/btwake.c
- ${BOARD}/keypad.c
- ${BOARD}/power.c
- ${BOARD}/main.c
+ fsm.c
+ btwake.c
+ keypad.c
+ power.c
+ main.c
)
diff --git a/am301_t950d4/CMakeLists.txt b/am301_t950d4/CMakeLists.txt
deleted file mode 100644
index d529828..0000000
--- a/am301_t950d4/CMakeLists.txt
+++ /dev/null
@@ -1,18 +0,0 @@
-cmake_minimum_required(VERSION 3.13.1)
-project(aml-rtos)
-
-include($ENV{SDK_BASE}/build/cmake/root.cmake)
-
-message(STATUS "#################${SDK_BASE}/products/${PRODUCT}/${BOARD}/include")
-
-target_include_directories(${TARGET_NAME} PUBLIC include)
-
-aml_sources(
- util.c
- fsm.c
- btwake.c
- keypad.c
- power.c
- main.c
-)
-
diff --git a/at301_t962d4/btwake.c b/at301_t962d4/btwake.c
deleted file mode 100644
index bcd6f89..0000000
--- a/at301_t962d4/btwake.c
+++ /dev/null
@@ -1,44 +0,0 @@
-#include <string.h>
-#include <stdio.h>
-#include "FreeRTOS.h"
-#include "suspend.h"
-#include "task.h"
-#include "gpio.h"
-
-#include "queue.h" /* RTOS queue related API prototypes. */
-#include "timers.h" /* Software timer related API prototypes. */
-#include "semphr.h" /* Semaphore related API prototypes. */
-
-#define BT_WAKE_HOST GPIOB_13 //bt_wake_host pin
-#define INFO(fmt, args...) printf("[%s] " fmt "\n", __func__, ##args)
-
-void Bt_IRQHandle(void);
-void Bt_GpioIRQRegister(void);
-void Bt_GpioIRQFree(void);
-
-void Bt_IRQHandle(void)
-{
- uint32_t buf[4] = {0};
-
- INFO("bt resume");
- vDisableGpioIRQ(BT_WAKE_HOST);
- if (!xGpioGetValue(BT_WAKE_HOST)) {
- buf[0] = BT_WAKEUP;
- INFO("power key");
- STR_Wakeup_src_Queue_Send_FromISR(buf);
- }
-}
-
-void Bt_GpioIRQRegister(void)
-{
- INFO();
- xGpioSetDir(BT_WAKE_HOST, GPIO_DIR_IN);
- xRequestGpioIRQ(BT_WAKE_HOST, Bt_IRQHandle, IRQF_TRIGGER_FALLING);
-}
-
-void Bt_GpioIRQFree(void)
-{
- vFreeGpioIRQ(BT_WAKE_HOST);
-}
-
-
diff --git a/at301_t962d4/fsm.c b/at301_t962d4/fsm.c
deleted file mode 100644
index ffab7b2..0000000
--- a/at301_t962d4/fsm.c
+++ /dev/null
@@ -1,150 +0,0 @@
-/*
- * Copyright (C) 2014-2018 Amlogic, Inc. All rights reserved.
- *
- * All information contained herein is Amlogic confidential.
- *
- * This software is provided to you pursuant to Software License Agreement
- * (SLA) with Amlogic Inc ("Amlogic"). This software may be used
- * only in accordance with the terms of this agreement.
- *
- * Redistribution and use in source and binary forms, with or without
- * modification is strictly prohibited without prior written permission from
- * Amlogic.
- *
- * 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
- * OWNER 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.
- */
-
-
-#include "FreeRTOS.h" /* Must come first. */
-#include "task.h" /* RTOS task related API prototypes. */
-#include "queue.h" /* RTOS queue related API prototypes. */
-#include "timers.h" /* Software timer related API prototypes. */
-#include "semphr.h" /* Semaphore related API prototypes. */
-
-#include <stdio.h>
-#include <unistd.h>
-
-#include "n200_func.h"
-#include "common.h"
-#include "riscv_encoding.h"
-#include "mailbox-api.h"
-#include "irq.h"
-
-typedef enum a {
- PM_CPU_PWR,
- PM_CPU_CORE0,
- PM_CPU_CORE1,
- PM_CPU_CORE2,
- PM_CPU_CORE3,
-} PM_E;
-
-static void *xMboxCoreFsmIdle(void *msg)
-{
- PM_E domain = *(uint32_t *)msg;
-
- switch (domain) {
- case PM_CPU_CORE0:
- REG32_UPDATE_BITS(ISA_SOFT_IRQ, (1 << 0), 0);
- EnableIrq(IRQ_NUM_OUT_0);
- break;
- case PM_CPU_CORE1:
- REG32_UPDATE_BITS(ISA_SOFT_IRQ, (1 << 1), 0);
- EnableIrq(IRQ_NUM_OUT_1);
- break;
- case PM_CPU_CORE2:
- REG32_UPDATE_BITS(ISA_SOFT_IRQ, (1 << 2), 0);
- EnableIrq(IRQ_NUM_OUT_2);
- break;
- case PM_CPU_CORE3:
- REG32_UPDATE_BITS(ISA_SOFT_IRQ, (1 << 3), 0);
- EnableIrq(IRQ_NUM_OUT_3);
- break;
- default:
- break;
- }
- return NULL;
-}
-
-static void xSetCoreFsmAwakeIrq(int cpuid)
-{
- REG32_UPDATE_BITS(ISA_SOFT_IRQ, (1 << cpuid), (1 << cpuid));
-}
-static void xCore0FsmIdleHandleIsr(void)
-{
- xSetCoreFsmAwakeIrq(0);
- DisableIrq(IRQ_NUM_OUT_0);
-}
-
-static void xCore1FsmIdleHandleIsr(void)
-{
- xSetCoreFsmAwakeIrq(1);
- DisableIrq(IRQ_NUM_OUT_1);
-}
-
-static void xCore2FsmIdleHandleIsr(void)
-{
- xSetCoreFsmAwakeIrq(2);
- DisableIrq(IRQ_NUM_OUT_2);
-}
-
-static void xCore3FsmIdleHandleIsr(void)
-{
- xSetCoreFsmAwakeIrq(3);
- DisableIrq(IRQ_NUM_OUT_3);
-}
-
-#if 0
-#define PWRCTRL_CPU1_FSM_STS0 (0xff644000 + (0x097 << 2))
-void checkstatus(void)
-{
- unsigned value;
-
- printf("\n\n");
- value = REG32(PWRCTRL_CPU0_FSM_STS0);
- value = ((value >> 12) & 0x1f);
- if (value != 0)
- printf("sts0:%x\n", value);
-
- value = REG32(PWRCTRL_CPU1_FSM_STS0);
- value = ((value >> 12) & 0x1f);
- if (value != 0)
- printf("sts1:%x\n", value);
-
- value = REG32(PWRCTRL_CPU2_FSM_STS0);
- value = ((value >> 12) & 0x1f);
- if (value != 0)
- printf("sts2:%x\n", value);
-
- value = REG32(PWRCTRL_CPU3_FSM_STS0);
- value = ((value >> 12) & 0x1f);
- if (value != 0)
- printf("sts3:%x\n", value);
-}
-#endif
-
-void vCoreFsmIdleInit(void);
-void vCoreFsmIdleInit(void)
-{
- int ret;
-
- ret = xInstallRemoteMessageCallbackFeedBack(AOTEE_CHANNEL, MBX_CMD_CPU_FSM_IDLE,
- xMboxCoreFsmIdle, 0);
- if (ret == MBOX_CALL_MAX)
- printf("mbox cmd 0x%x register fail\n", MBX_CMD_CPU_FSM_IDLE);
-
- RegisterIrq(IRQ_NUM_OUT_0, 1, xCore0FsmIdleHandleIsr);
- RegisterIrq(IRQ_NUM_OUT_1, 1, xCore1FsmIdleHandleIsr);
- RegisterIrq(IRQ_NUM_OUT_2, 1, xCore2FsmIdleHandleIsr);
- RegisterIrq(IRQ_NUM_OUT_3, 1, xCore3FsmIdleHandleIsr);
- REG32_UPDATE_BITS(SEC_SYS_CPU_CFG10, 0xF << 10, 0xF << 10);
-}
diff --git a/at301_t962d4/include/keypad.h b/at301_t962d4/include/keypad.h
deleted file mode 100644
index f3aff62..0000000
--- a/at301_t962d4/include/keypad.h
+++ /dev/null
@@ -1,154 +0,0 @@
-/*
- * Copyright (C) 2014-2018 Amlogic, Inc. All rights reserved.
- *
- * All information contained herein is Amlogic confidential.
- *
- * This software is provided to you pursuant to Software License Agreement
- * (SLA) with Amlogic Inc ("Amlogic"). This software may be used
- * only in accordance with the terms of this agreement.
- *
- * Redistribution and use in source and binary forms, with or without
- * modification is strictly prohibited without prior written permission from
- * Amlogic.
- *
- * 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
- * OWNER 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.
- */
-#ifndef __MESON_Button_H
-#define __MESON_Button_H
-
-#ifdef __cplusplus
-extern "C" {
-#endif
-
-#include "common.h"
-#include <stdlib.h>
-#include <string.h>
-#include "FreeRTOS.h"
-#include <timers.h>
-#include <task.h>
-#include <gpio.h>
-#include <saradc.h>
-
-/*common macro*/
-#define TIMER_CYCLE_TIME 20
-#define KEY_JITTER_COUNT 1
-
-/* adc key param */
-#define SAMPLE_DEVIATION 40
-#define ADCKEY_ID_BASE 512
-
-/* key event */
-#define EVENT_SHORT (1 << 0)
-#define EVENT_LONG (1 << 1)
-
-/* key threshold */
-#define THRESHOLD_LONG 2000
-
-enum KeyType{
- GPIO_KEY = 0,
- ADC_KEY,
- KEY_TYPE_NUM
-};
-
-enum GpioLevel {
- LOW = 0,
- HIGH
-};
-
-enum KeyState{
- UP = 0,
- DOWN,
-};
-
-struct xReportEvent {
- uint32_t ulCode;
- uint32_t event;
- TickType_t responseTime;
- void *data;
-};
-
-struct xKeyInitInfo {
- uint32_t ulKeyId;
- uint32_t eventMask;
- uint32_t repeatTimeMs;
- uint32_t repeatDelayTimeMs;
- uint32_t longDTTMs;
- uint32_t doubleDTTMs;
- uint32_t combLongDTTMs;
- uint32_t combDTTMs;
- void (*CallBack)(struct xReportEvent);
- void *data;
-};
-
-struct xGpioKeyInfo {
- int ulInitLevel;
- struct xKeyInitInfo keyInitInfo;
-};
-
-struct xAdcKeyInfo {
- int32_t ulValue;
- AdcInstanceConfig_t xAdcDecp;
- struct xKeyInitInfo keyInitInfo;
-};
-
-#define KEY_INIT_INFO(_ulKeyId, _eventMask, _repeatTimeMs,\
- _repeatDelayTimeMs, _longDTTMs, _doubleDTTMs,\
- _combLongDTTMs, _combDTTMs, _CallBack, _data) { \
- .ulKeyId = _ulKeyId, \
- .eventMask = _eventMask, \
- .repeatTimeMs = _repeatTimeMs, \
- .repeatDelayTimeMs = _repeatDelayTimeMs, \
- .longDTTMs = _longDTTMs, \
- .doubleDTTMs = _doubleDTTMs, \
- .combLongDTTMs = _combLongDTTMs, \
- .combDTTMs = _combDTTMs, \
- .CallBack = _CallBack, \
- .data = _data, \
-}
-
-#define GPIO_KEY_INFO(_ulKeyId, _ulInitLevel, _eventMask,\
- _CallBack, _data) { \
- .ulInitLevel = _ulInitLevel, \
- .keyInitInfo = KEY_INIT_INFO(_ulKeyId, _eventMask, 0, 0, 0,\
- 0, 0, 0, _CallBack, _data),\
-}
-
-#define ADC_KEY_INFO(_ulKeyId, _ulValue, _adcChan, _eventMask,\
- _CallBack, _data) { \
- .ulValue = _ulValue, \
- .xAdcDecp = {_adcChan, NO_AVERAGING, 1}, \
- .keyInitInfo = KEY_INIT_INFO(_ulKeyId, _eventMask, 0, 0, 0,\
- 0, 0, 0, _CallBack, _data),\
-}
-
-void vCreateGpioKey(struct xGpioKeyInfo *keyArr, uint16_t keyNum);
-void vDestoryGpioKey(void);
-void vGpioKeyEnable(void);
-void vGpioKeyDisable(void);
-int vGpioKeyIsEmpty(void);
-
-void vCreateAdcKey(struct xAdcKeyInfo *keyArr, uint16_t keyNum);
-void vDestoryAdcKey(void);
-void vAdcKeyEnable(void);
-void vAdcKeyDisable(void);
-int vAdcKeyIsEmpty(void);
-
-void vKeyPadCreate(void);
-void vKeyPadInit(void);
-void vKeyPadDeinit(void);
-
-void vDynamicKeypadInit(void);
-#ifdef __cplusplus
-}
-#endif
-#endif
diff --git a/at301_t962d4/include/power.h b/at301_t962d4/include/power.h
deleted file mode 100644
index 97001b0..0000000
--- a/at301_t962d4/include/power.h
+++ /dev/null
@@ -1,32 +0,0 @@
-/*
- * Copyright (C) 2014-2018 Amlogic, Inc. All rights reserved.
- *
- * All information contained herein is Amlogic confidential.
- *
- * This software is provided to you pursuant to Software License Agreement
- * (SLA) with Amlogic Inc ("Amlogic"). This software may be used
- * only in accordance with the terms of this agreement.
- *
- * Redistribution and use in source and binary forms, with or without
- * modification is strictly prohibited without prior written permission from
- * Amlogic.
- *
- * 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
- * OWNER 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.
- */
-
-
-extern void str_hw_init(void);
-extern void str_hw_disable(void);
-extern void str_power_on(int shutdown_flag);
-extern void str_power_off(int shutdown_flag);
-
diff --git a/at301_t962d4/keypad.c b/at301_t962d4/keypad.c
deleted file mode 100644
index 5364973..0000000
--- a/at301_t962d4/keypad.c
+++ /dev/null
@@ -1,58 +0,0 @@
-#include <string.h>
-#include <stdio.h>
-#include "FreeRTOS.h"
-#include "ir.h"
-#include "keypad.h"
-#include "gpio.h"
-#include "saradc.h"
-#include "suspend.h"
-
-/*KEY ID*/
-#define ADC_KEY_ID_HOME 520
-
-static void vAdcKeyCallBack(struct xReportEvent event)
-{
- uint32_t buf[4] = {0};
-
- switch (event.ulCode) {
- case ADC_KEY_ID_HOME:
- buf[0] = POWER_KEY_WAKEUP;
- STR_Wakeup_src_Queue_Send(buf);
- break;
- default:
- break;
- }
-
- printf("ADC key event 0x%x, key code %d, responseTicks %d\n",
- event.event, event.ulCode, event.responseTime);
-}
-
-struct xAdcKeyInfo adcKeyInfo[] = {
- ADC_KEY_INFO(ADC_KEY_ID_HOME, 0, SARADC_CH1,
- EVENT_SHORT,
- vAdcKeyCallBack, NULL)
-};
-
-void vKeyPadCreate(void)
-{
- vCreateAdcKey(adcKeyInfo,
- sizeof(adcKeyInfo)/sizeof(struct xAdcKeyInfo));
-
- vDynamicKeypadInit();
-}
-
-void vKeyPadInit(void)
-{
- if (vAdcKeyIsEmpty())
- vCreateAdcKey(adcKeyInfo,
- sizeof(adcKeyInfo)/sizeof(struct xAdcKeyInfo));
-
- vAdcKeyEnable();
- vGpioKeyEnable();
-}
-
-void vKeyPadDeinit(void)
-{
- vAdcKeyDisable();
- vGpioKeyDisable();
-}
diff --git a/at301_t962d4/main.c b/at301_t962d4/main.c
deleted file mode 100644
index bc382dd..0000000
--- a/at301_t962d4/main.c
+++ /dev/null
@@ -1,255 +0,0 @@
-/*
- * IntTest.c
- *
- * Created on: 2018��10��17��
- * Author: danialxie
- *
- * This is an PIC interrupt nesting test for N200 SOC, NUCLEI, Inc.
- * Attention:
- * This test need hardware board supporting.
- * A GPIO interrupt is stimulated by another GPIO using wire connection.
- * Wire connection:
- * Source --> Target
- * GPIO 0 --> GPIO 8
- * GPIO 1 --> GPIO 9
- * GPIO 2 --> GPIO 10
- * GPIO 3 --> GPIO 11
- * GPIO 4 --> GPIO 12
- * GPIO 5 --> GPIO 13
- * GPIO 6 --> GPIO 14
- * GPIO 7 --> GPIO 15
- */
-
-/* Kernel includes. */
-#include "FreeRTOS.h" /* Must come first. */
-#include "task.h" /* RTOS task related API prototypes. */
-#include "queue.h" /* RTOS queue related API prototypes. */
-#include "timers.h" /* Software timer related API prototypes. */
-#include "semphr.h" /* Semaphore related API prototypes. */
-
-#include <stdio.h>
-#include <stdlib.h>
-#include <string.h>
-#include <unistd.h>
-
-#include "n200_pic_tmr.h"
-#include "n200_func.h"
-#include "uart.h"
-#include "common.h"
-#include "mailbox-api.h"
-#include "version.h"
-#include "hdmi_cec.h"
-#include "stick_mem.h"
-#include "keypad.h"
-
-#define INT_TEST_NEST_DEPTH 6
-#define INT_TEST_GPIO_NUM 6
-#define INT_TEST_TASK_DELAY 50 // ms
-#define TASK_TEST_STACK_DEPTH 200
-
-#define TASK_TEST_QUEUE_NUM 2
-#define TASK_TEST_QUEUE_LENGTH 3
-
-//#define GPIO_INT_SOURCE(x) (SOC_PIC_INT_GPIO_BASE + x)
-
-/* Configure board type:
- * Board under test : SIGNAL_BOARD_ENABLE 0
- * Signal generation board : SIGNAL_BOARD_ENABLE 1
- */
-#define SIGNAL_BOARD_ENABLE 0
-
-#define INT_TEST_INT_WAVE_ENABLE 1
-
-#if INT_TEST_INT_WAVE_ENABLE
- #define INT_TEST_TIMER_PERIOD 500 // ms
- #define INT_TEST_INT_DELAY 10 // ms
-#else
- #define INT_TEST_TIMER_PERIOD 500 // ms
- #define INT_TEST_INT_DELAY 0x3ff // ms
-#endif
-
-#define INT_TEST_MAX_TIMER_PERIOD 100 // ms
-#define INT_TEST_MIN_TIMER_PERIOD 50 // ms
-#define INT_TEST_MUTE_TIMER_PERIOD 200 // ms
-
-/* Interrupt handler */
-void GPIOInterruptHandler(uint32_t num, uint32_t priority);
-void vApplicationIdleHook( void );
-
-
-extern void trap_entry(void);
-extern void irq_entry(void);
-
-
-/* Binary Semaphore */
-QueueHandle_t xGPIOSemaphore[INT_TEST_NEST_DEPTH];
-QueueHandle_t xMessageQueue[TASK_TEST_QUEUE_NUM];
-
-/* Timer handle */
-#if BRINGUP_TEST
-TimerHandle_t xSoftTimer = NULL;
-#endif
-/*
-static void vPrintString(const char* msg)
-{
- taskENTER_CRITICAL();
-
- taskEXIT_CRITICAL();
-}
-*/
-/* function: vPICInit */
-static void vPICInit(void) {
-
- // Disable global interrupter
- clear_csr(mstatus, MSTATUS_MIE);
-
- // Initialize interrupter handler
- for (int i = 0; i < PIC_NUM_INTERRUPTS; i ++) {
- pic_interrupt_handlers[i] = DefaultInterruptHandler;
- }
-#if 0
-#if !(SIGNAL_BOARD_ENABLE)
-
- // Enable GPIO interrupter
- enable_interrupt(GPIO_INT_SOURCE(8), 1, GPIOInterruptHandler8);
- enable_interrupt(GPIO_INT_SOURCE(9), 2, GPIOInterruptHandler9);
- enable_interrupt(GPIO_INT_SOURCE(10), 3, GPIOInterruptHandler10);
- enable_interrupt(GPIO_INT_SOURCE(11), 4, GPIOInterruptHandler11);
- enable_interrupt(GPIO_INT_SOURCE(12), 5, GPIOInterruptHandler12);
- enable_interrupt(GPIO_INT_SOURCE(13), 6, GPIOInterruptHandler13);
- //enable_interrupt(GPIO_INT_SOURCE(14), 7, GPIOInterruptHandler14);
- //enable_interrupt(GPIO_INT_SOURCE(15), 7, GPIOInterruptHandler15);
-
-#endif
-#endif
- // Enable global interrupt
- set_csr(mstatus, MSTATUS_MIE);
-}
-
-#if BRINGUP_TEST
-static void vPrintSystemStatus(TimerHandle_t xTimer) {
- xTimer = xTimer;
- taskENTER_CRITICAL();
-
-// vUartPuts("\nTimer ...\n");
- taskEXIT_CRITICAL();
-}
-
-static void vPrintTask1( void *pvParameters )
-{
- /*make compiler happy*/
- pvParameters = pvParameters;
-
- for ( ;; )
- {
-// vUartPuts("\nvPTask1 %d\n");
-
- vTaskDelay(pdMS_TO_TICKS(50));
- }
-}
-
-static void vPrintTask2( void *pvParameters )
-{
- /*make compiler happy*/
- pvParameters = pvParameters;
- vTaskDelay(pdMS_TO_TICKS(50));
- for ( ;; )
- {
-// vUartPuts("\nvPTask2 %d\n");
- vTaskDelay(pdMS_TO_TICKS(50));
- }
-}
-#endif
-extern void vMbInit(void);
-extern void vCoreFsmIdleInit(void);
-extern void vRtcInit(void);
-extern void create_str_task(void);
-// Test target board
-int main(void)
-{
- vUartPuts("Starting AOCPU FreeRTOS\n");
- version();
-
- // Initialize GPIOs, PIC and timer
- //vGPIOInit();
- vPICInit();
- stick_mem_init();
- //write watchdog flag
- stick_mem_write(STICK_REBOOT_FLAG, 0xd);
-
- // Delay
- for (uint32_t i = 0; i < 0xffff; ++i);
-
- vMbInit();
- vCoreFsmIdleInit();
- // Create timer
-#if BRINGUP_TEST
- xSoftTimer = xTimerCreate("Timer", pdMS_TO_TICKS(INT_TEST_TIMER_PERIOD), pdTRUE, NULL, vPrintSystemStatus);
-
- vUartPuts("Starting timer ...\n");
- xTimerStart(xSoftTimer, 0);
-
- xTaskCreate( vPrintTask1, "Print1", configMINIMAL_STACK_SIZE, NULL, 2, NULL );
- xTaskCreate( vPrintTask2, "Print2", configMINIMAL_STACK_SIZE, NULL, 2, NULL );
-#endif
-
- vCecCallbackInit(CEC_CHIP_T5);
- write_csr(mtvec, &trap_entry);
- write_csr_mivec(&irq_entry);
-
- vRtcInit();
- create_str_task();
- vKeyPadCreate();
-
- vUartPuts("Starting task scheduler ...\n");
- vTaskStartScheduler();
-
- for (;;)
-
- return 0;
-}
-
-void vApplicationIdleHook( void )
-{
- //vPrintString("enter idle task\n");
-
- //write_csr(mie, 1); // open mstatue.mie
- //asm volatile ("wfi"); // enter low power mode
-}
-/*-----------------------------------------------------------*/
-void vApplicationMallocFailedHook( void );
-
-void vApplicationMallocFailedHook( void )
-{
- /* The malloc failed hook is enabled by setting
- configUSE_MALLOC_FAILED_HOOK to 1 in FreeRTOSConfig.h.
-
- Called if a call to pvPortMalloc() fails because there is insufficient
- free memory available in the FreeRTOS heap. pvPortMalloc() is called
- internally by FreeRTOS API functions that create tasks, queues, software
- timers, and semaphores. The size of the FreeRTOS heap is set by the
- configTOTAL_HEAP_SIZE configuration constant in FreeRTOSConfig.h. */
- //write(1,"malloc failed\n", 14);
-
- vUartPuts("vApplicationMallocFailedHook\n");
- vPrintFreeListAfterMallocFail();
- for ( ;; );
-}
-/*-----------------------------------------------------------*/
-
-void vApplicationStackOverflowHook( TaskHandle_t xTask, signed char *pcTaskName );
-
-void vApplicationStackOverflowHook( TaskHandle_t xTask, signed char *pcTaskName )
-{
- ( void ) pcTaskName;
- ( void ) xTask;
-
- /* Run time stack overflow checking is performed if
- configconfigCHECK_FOR_STACK_OVERFLOW is defined to 1 or 2. This hook
- function is called if a stack overflow is detected. pxCurrentTCB can be
- inspected in the debugger if the task name passed into this function is
- corrupt. */
- //write(1, "Stack Overflow\n", 15);
- for ( ;; );
-}
-/*-----------------------------------------------------------*/
diff --git a/at301_t962d4/power.c b/at301_t962d4/power.c
deleted file mode 100644
index b5001f0..0000000
--- a/at301_t962d4/power.c
+++ /dev/null
@@ -1,232 +0,0 @@
-/*
- * Copyright (C) 2014-2018 Amlogic, Inc. All rights reserved.
- *
- * All information contained herein is Amlogic confidential.
- *
- * This software is provided to you pursuant to Software License Agreement
- * (SLA) with Amlogic Inc ("Amlogic"). This software may be used
- * only in accordance with the terms of this agreement.
- *
- * Redistribution and use in source and binary forms, with or without
- * modification is strictly prohibited without prior written permission from
- * Amlogic.
- *
- * 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
- * OWNER 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.
- */
-#include "FreeRTOS.h"
-#include "common.h"
-#include "gpio.h"
-#include "ir.h"
-#include "suspend.h"
-#include "task.h"
-#include "gpio.h"
-#include "pwm.h"
-#include "pwm_plat.h"
-#include "keypad.h"
-
-#include "hdmi_cec.h"
-
-/*#define CONFIG_ETH_WAKEUP*/
-
-#ifdef CONFIG_ETH_WAKEUP
-#include "interrupt_control.h"
-#include "eth.h"
-#include "irq.h"
-#endif
-
-static TaskHandle_t cecTask = NULL;
-static int vdd_ee;
-static int vdd_cpu;
-
-static IRPowerKey_t prvPowerKeyList[] = {
- { 0xef10fe01, IR_NORMAL}, /* ref tv pwr */
- { 0xba45bd02, IR_NORMAL}, /* small ir pwr */
- { 0xef10fb04, IR_NORMAL}, /* old ref tv pwr */
- { 0xf20dfe01, IR_NORMAL},
- { 0xe51afb04, IR_NORMAL},
- { 0x3ac5bd02, IR_CUSTOM},
- {}
- /* add more */
-};
-
-static void vIRHandler(IRPowerKey_t *pkey)
-{
- uint32_t buf[4] = {0};
- if (pkey->type == IR_NORMAL)
- buf[0] = REMOTE_WAKEUP;
- else if (pkey->type == IR_CUSTOM)
- buf[0] = REMOTE_CUS_WAKEUP;
-
- /* do sth below to wakeup*/
- STR_Wakeup_src_Queue_Send_FromISR(buf);
-};
-
-void str_hw_init(void);
-void str_hw_disable(void);
-void str_power_on(int shutdown_flag);
-void str_power_off(int shutdown_flag);
-void Bt_GpioIRQRegister(void);
-void Bt_GpioIRQFree(void);
-
-void str_hw_init(void)
-{
- /*enable device & wakeup source interrupt*/
- vIRInit(MODE_HARD_NEC, GPIOD_5, PIN_FUNC1, prvPowerKeyList, ARRAY_SIZE(prvPowerKeyList), vIRHandler);
-#ifdef CONFIG_ETH_WAKEUP
- vETHInit(IRQ_ETH_PMT_NUM,eth_handler_t5);
-#endif
- xTaskCreate(vCEC_task, "CECtask", configMINIMAL_STACK_SIZE,
- NULL, CEC_TASK_PRI, &cecTask);
- vBackupAndClearGpioIrqReg();
- vKeyPadInit();
- vGpioIRQInit();
- Bt_GpioIRQRegister();
-}
-
-
-void str_hw_disable(void)
-{
- /*disable wakeup source interrupt*/
- vIRDeint();
-#ifdef CONFIG_ETH_WAKEUP
- vETHDeint_t5();
-#endif
- if (cecTask) {
- vTaskDelete(cecTask);
- cec_req_irq(0);
- }
- Bt_GpioIRQFree();
- vKeyPadDeinit();
- vRestoreGpioIrqReg();
-}
-
-void str_power_on(int shutdown_flag)
-{
- int ret;
-
- /***set vdd_ee val***/
- ret = vPwmMesonsetvoltage(VDDEE_VOLT,vdd_ee);
- if (ret < 0) {
- printf("vdd_EE pwm set fail\n");
- return;
- }
-
- /***set vdd_ee val***/
- ret = vPwmMesonsetvoltage(VDDCPU_VOLT,vdd_cpu);
- if (ret < 0) {
- printf("vdd_CPU pwm set fail\n");
- return;
- }
-
- /***power on vcc3.3***/
- ret = xGpioSetDir(GPIOD_10,GPIO_DIR_OUT);
- if (ret < 0) {
- printf("vcc3.3 set gpio dir fail\n");
- return;
- }
-
- ret = xGpioSetValue(GPIOD_10,GPIO_LEVEL_HIGH);
- if (ret < 0) {
- printf("vcc3.3 set gpio val fail\n");
- return;
- }
-
- if (shutdown_flag) {
- /***power on VDDQ/VDDCPU***/
- ret = xGpioSetDir(GPIOD_4,GPIO_DIR_OUT);
- if (ret < 0) {
- printf("VDDCPU/VDDQ set gpio dir fail\n");
- return;
- }
-
- ret = xGpioSetValue(GPIOD_4,GPIO_LEVEL_HIGH);
- if (ret < 0) {
- printf("VDDCPU/VDDQ set gpio val fail\n");
- return;
- }
- /*Wait 200ms for VDDCPU statble*/
- vTaskDelay(pdMS_TO_TICKS(200));
- }
-
- /***power on 5v***/
- REG32(AO_GPIO_TEST_N) = REG32(AO_GPIO_TEST_N) | (1 << 31);
-}
-
-void str_power_off(int shutdown_flag)
-{
- int ret;
-
- printf("poweroff 5v\n");
- printf("0x%x\n", REG32(AO_GPIO_TEST_N));
-
- REG32(AO_GPIO_TEST_N) = (REG32(AO_GPIO_TEST_N) << 1) >> 1;
-
- if (shutdown_flag) {
- /***power off VDDQ/VDDCPU***/
- ret = xGpioSetDir(GPIOD_4,GPIO_DIR_OUT);
- if (ret < 0) {
- printf("VDDCPU/VDDQ set gpio dir fail\n");
- return;
- }
-
- ret = xGpioSetValue(GPIOD_4,GPIO_LEVEL_LOW);
- if (ret < 0) {
- printf("VDDCPU/VDDQ set gpio val fail\n");
- return;
- }
- }
-
- /***power off vcc3.3***/
- ret = xGpioSetDir(GPIOD_10,GPIO_DIR_OUT);
- if (ret < 0) {
- printf("vcc3.3 set gpio dir fail\n");
- return;
- }
-
-#ifndef CONFIG_ETH_WAKEUP
- ret= xGpioSetValue(GPIOD_10,GPIO_LEVEL_LOW);
- if (ret < 0) {
- printf("vcc3.3 set gpio val fail\n");
- return;
- }
-#endif
-
- /***set vdd_cpu val***/
- vdd_cpu = vPwmMesongetvoltage(VDDCPU_VOLT);
- if (vdd_cpu < 0) {
- printf("vdd_CPU pwm get fail\n");
- return;
- }
-
- ret = vPwmMesonsetvoltage(VDDCPU_VOLT,700);
- if (ret < 0) {
- printf("vdd_CPU pwm set fail\n");
- return;
- }
-
- /***set vdd_ee val***/
- vdd_ee = vPwmMesongetvoltage(VDDEE_VOLT);
- if (vdd_ee < 0) {
- printf("vdd_EE pwm get fail\n");
- return;
- }
-
- ret = vPwmMesonsetvoltage(VDDEE_VOLT,770);
- if (ret < 0) {
- printf("vdd_EE pwm set fail\n");
- return;
- }
-
- //REG32( ((0x0000 << 2) + 0xff638c00)) = 0;
-}
-
diff --git a/at301_t962d4/util.c b/at301_t962d4/util.c
deleted file mode 100644
index e5a71e9..0000000
--- a/at301_t962d4/util.c
+++ /dev/null
@@ -1,167 +0,0 @@
-/* Copyright (c) 2013 The Chromium OS Authors. All rights reserved.
- * Use of this source code is governed by a BSD-style license that can be
- * found in the LICENSE file.
- */
-
-/* Utility functions for Chrome EC */
-
-#include "util.h"
-#include <string.h>
-#include <ctype.h>
-
-int parse_bool(const char *s, int *dest)
-{
- if (!strcasecmp(s, "off") || !strncasecmp(s, "dis", 3) ||
- tolower(*s) == 'f' || tolower(*s) == 'n') {
- *dest = 0;
- return 1;
- } else if (!strcasecmp(s, "on") || !strncasecmp(s, "ena", 3) ||
- tolower(*s) == 't' || tolower(*s) == 'y') {
- *dest = 1;
- return 1;
- } else {
- return 0;
- }
-}
-
-int uint64divmod(uint64_t *n, int d)
-{
- uint64_t q = 0, mask;
- int r = 0;
-
- /* Divide-by-zero returns zero */
- if (!d) {
- *n = 0;
- return 0;
- }
-
- /* Common powers of 2 = simple shifts */
- if (d == 2) {
- r = *n & 1;
- *n >>= 1;
- return r;
- } else if (d == 16) {
- r = *n & 0xf;
- *n >>= 4;
- return r;
- }
-
- /* If v fits in 32-bit, we're done. */
- if (*n <= 0xffffffff) {
- uint32_t v32 = *n;
- r = v32 % d;
- *n = v32 / d;
- return r;
- }
-
- /* Otherwise do integer division the slow way. */
- for (mask = (1ULL << 63); mask; mask >>= 1) {
- r <<= 1;
- if (*n & mask)
- r |= 1;
- if (r >= d) {
- r -= d;
- q |= mask;
- }
- }
- *n = q;
- return r;
-}
-
-int __clzsi2(int x)
-{
- int r = 0;
-
- if (!x)
- return 32;
- if (!(x & 0xffff0000u)) {
- x <<= 16;
- r += 16;
- }
- if (!(x & 0xff000000u)) {
- x <<= 8;
- r += 8;
- }
- if (!(x & 0xf0000000u)) {
- x <<= 4;
- r += 4;
- }
- if (!(x & 0xc0000000u)) {
- x <<= 2;
- r += 2;
- }
- if (!(x & 0x80000000u)) {
- x <<= 1;
- r += 1;
- }
- return r;
-}
-
-int get_next_bit(uint32_t *mask)
-{
- int bit = 31 - __clzsi2(*mask);
- *mask &= ~(1 << bit);
- return bit;
-}
-
-char *strncpy (char *s1, const char *s2, size_t n)
-{
- char c;
- char *s = s1;
-
- --s1;
-
- if (n >= 4)
- {
- size_t n4 = n >> 2;
-
- for (;;)
- {
- c = *s2++;
- *++s1 = c;
- if (c == '\0')
- break;
- c = *s2++;
- *++s1 = c;
- if (c == '\0')
- break;
- c = *s2++;
- *++s1 = c;
- if (c == '\0')
- break;
- c = *s2++;
- *++s1 = c;
- if (c == '\0')
- break;
- if (--n4 == 0)
- goto last_chars;
- }
- n = n - (s1 - s) - 1;
- if (n == 0)
- return s;
- goto zero_fill;
- }
-
- last_chars:
- n &= 3;
- if (n == 0)
- return s;
-
- do
- {
- c = *s2++;
- *++s1 = c;
- if (--n == 0)
- return s;
- }
- while (c != '\0');
-
- zero_fill:
- do
- *++s1 = '\0';
- while (--n > 0);
-
- return s;
-}
-
-
diff --git a/at309_t962d4/btwake.c b/at309_t962d4/btwake.c
deleted file mode 100644
index bcd6f89..0000000
--- a/at309_t962d4/btwake.c
+++ /dev/null
@@ -1,44 +0,0 @@
-#include <string.h>
-#include <stdio.h>
-#include "FreeRTOS.h"
-#include "suspend.h"
-#include "task.h"
-#include "gpio.h"
-
-#include "queue.h" /* RTOS queue related API prototypes. */
-#include "timers.h" /* Software timer related API prototypes. */
-#include "semphr.h" /* Semaphore related API prototypes. */
-
-#define BT_WAKE_HOST GPIOB_13 //bt_wake_host pin
-#define INFO(fmt, args...) printf("[%s] " fmt "\n", __func__, ##args)
-
-void Bt_IRQHandle(void);
-void Bt_GpioIRQRegister(void);
-void Bt_GpioIRQFree(void);
-
-void Bt_IRQHandle(void)
-{
- uint32_t buf[4] = {0};
-
- INFO("bt resume");
- vDisableGpioIRQ(BT_WAKE_HOST);
- if (!xGpioGetValue(BT_WAKE_HOST)) {
- buf[0] = BT_WAKEUP;
- INFO("power key");
- STR_Wakeup_src_Queue_Send_FromISR(buf);
- }
-}
-
-void Bt_GpioIRQRegister(void)
-{
- INFO();
- xGpioSetDir(BT_WAKE_HOST, GPIO_DIR_IN);
- xRequestGpioIRQ(BT_WAKE_HOST, Bt_IRQHandle, IRQF_TRIGGER_FALLING);
-}
-
-void Bt_GpioIRQFree(void)
-{
- vFreeGpioIRQ(BT_WAKE_HOST);
-}
-
-
diff --git a/at309_t962d4/fsm.c b/at309_t962d4/fsm.c
deleted file mode 100644
index ffab7b2..0000000
--- a/at309_t962d4/fsm.c
+++ /dev/null
@@ -1,150 +0,0 @@
-/*
- * Copyright (C) 2014-2018 Amlogic, Inc. All rights reserved.
- *
- * All information contained herein is Amlogic confidential.
- *
- * This software is provided to you pursuant to Software License Agreement
- * (SLA) with Amlogic Inc ("Amlogic"). This software may be used
- * only in accordance with the terms of this agreement.
- *
- * Redistribution and use in source and binary forms, with or without
- * modification is strictly prohibited without prior written permission from
- * Amlogic.
- *
- * 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
- * OWNER 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.
- */
-
-
-#include "FreeRTOS.h" /* Must come first. */
-#include "task.h" /* RTOS task related API prototypes. */
-#include "queue.h" /* RTOS queue related API prototypes. */
-#include "timers.h" /* Software timer related API prototypes. */
-#include "semphr.h" /* Semaphore related API prototypes. */
-
-#include <stdio.h>
-#include <unistd.h>
-
-#include "n200_func.h"
-#include "common.h"
-#include "riscv_encoding.h"
-#include "mailbox-api.h"
-#include "irq.h"
-
-typedef enum a {
- PM_CPU_PWR,
- PM_CPU_CORE0,
- PM_CPU_CORE1,
- PM_CPU_CORE2,
- PM_CPU_CORE3,
-} PM_E;
-
-static void *xMboxCoreFsmIdle(void *msg)
-{
- PM_E domain = *(uint32_t *)msg;
-
- switch (domain) {
- case PM_CPU_CORE0:
- REG32_UPDATE_BITS(ISA_SOFT_IRQ, (1 << 0), 0);
- EnableIrq(IRQ_NUM_OUT_0);
- break;
- case PM_CPU_CORE1:
- REG32_UPDATE_BITS(ISA_SOFT_IRQ, (1 << 1), 0);
- EnableIrq(IRQ_NUM_OUT_1);
- break;
- case PM_CPU_CORE2:
- REG32_UPDATE_BITS(ISA_SOFT_IRQ, (1 << 2), 0);
- EnableIrq(IRQ_NUM_OUT_2);
- break;
- case PM_CPU_CORE3:
- REG32_UPDATE_BITS(ISA_SOFT_IRQ, (1 << 3), 0);
- EnableIrq(IRQ_NUM_OUT_3);
- break;
- default:
- break;
- }
- return NULL;
-}
-
-static void xSetCoreFsmAwakeIrq(int cpuid)
-{
- REG32_UPDATE_BITS(ISA_SOFT_IRQ, (1 << cpuid), (1 << cpuid));
-}
-static void xCore0FsmIdleHandleIsr(void)
-{
- xSetCoreFsmAwakeIrq(0);
- DisableIrq(IRQ_NUM_OUT_0);
-}
-
-static void xCore1FsmIdleHandleIsr(void)
-{
- xSetCoreFsmAwakeIrq(1);
- DisableIrq(IRQ_NUM_OUT_1);
-}
-
-static void xCore2FsmIdleHandleIsr(void)
-{
- xSetCoreFsmAwakeIrq(2);
- DisableIrq(IRQ_NUM_OUT_2);
-}
-
-static void xCore3FsmIdleHandleIsr(void)
-{
- xSetCoreFsmAwakeIrq(3);
- DisableIrq(IRQ_NUM_OUT_3);
-}
-
-#if 0
-#define PWRCTRL_CPU1_FSM_STS0 (0xff644000 + (0x097 << 2))
-void checkstatus(void)
-{
- unsigned value;
-
- printf("\n\n");
- value = REG32(PWRCTRL_CPU0_FSM_STS0);
- value = ((value >> 12) & 0x1f);
- if (value != 0)
- printf("sts0:%x\n", value);
-
- value = REG32(PWRCTRL_CPU1_FSM_STS0);
- value = ((value >> 12) & 0x1f);
- if (value != 0)
- printf("sts1:%x\n", value);
-
- value = REG32(PWRCTRL_CPU2_FSM_STS0);
- value = ((value >> 12) & 0x1f);
- if (value != 0)
- printf("sts2:%x\n", value);
-
- value = REG32(PWRCTRL_CPU3_FSM_STS0);
- value = ((value >> 12) & 0x1f);
- if (value != 0)
- printf("sts3:%x\n", value);
-}
-#endif
-
-void vCoreFsmIdleInit(void);
-void vCoreFsmIdleInit(void)
-{
- int ret;
-
- ret = xInstallRemoteMessageCallbackFeedBack(AOTEE_CHANNEL, MBX_CMD_CPU_FSM_IDLE,
- xMboxCoreFsmIdle, 0);
- if (ret == MBOX_CALL_MAX)
- printf("mbox cmd 0x%x register fail\n", MBX_CMD_CPU_FSM_IDLE);
-
- RegisterIrq(IRQ_NUM_OUT_0, 1, xCore0FsmIdleHandleIsr);
- RegisterIrq(IRQ_NUM_OUT_1, 1, xCore1FsmIdleHandleIsr);
- RegisterIrq(IRQ_NUM_OUT_2, 1, xCore2FsmIdleHandleIsr);
- RegisterIrq(IRQ_NUM_OUT_3, 1, xCore3FsmIdleHandleIsr);
- REG32_UPDATE_BITS(SEC_SYS_CPU_CFG10, 0xF << 10, 0xF << 10);
-}
diff --git a/at309_t962d4/include/keypad.h b/at309_t962d4/include/keypad.h
deleted file mode 100644
index f3aff62..0000000
--- a/at309_t962d4/include/keypad.h
+++ /dev/null
@@ -1,154 +0,0 @@
-/*
- * Copyright (C) 2014-2018 Amlogic, Inc. All rights reserved.
- *
- * All information contained herein is Amlogic confidential.
- *
- * This software is provided to you pursuant to Software License Agreement
- * (SLA) with Amlogic Inc ("Amlogic"). This software may be used
- * only in accordance with the terms of this agreement.
- *
- * Redistribution and use in source and binary forms, with or without
- * modification is strictly prohibited without prior written permission from
- * Amlogic.
- *
- * 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
- * OWNER 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.
- */
-#ifndef __MESON_Button_H
-#define __MESON_Button_H
-
-#ifdef __cplusplus
-extern "C" {
-#endif
-
-#include "common.h"
-#include <stdlib.h>
-#include <string.h>
-#include "FreeRTOS.h"
-#include <timers.h>
-#include <task.h>
-#include <gpio.h>
-#include <saradc.h>
-
-/*common macro*/
-#define TIMER_CYCLE_TIME 20
-#define KEY_JITTER_COUNT 1
-
-/* adc key param */
-#define SAMPLE_DEVIATION 40
-#define ADCKEY_ID_BASE 512
-
-/* key event */
-#define EVENT_SHORT (1 << 0)
-#define EVENT_LONG (1 << 1)
-
-/* key threshold */
-#define THRESHOLD_LONG 2000
-
-enum KeyType{
- GPIO_KEY = 0,
- ADC_KEY,
- KEY_TYPE_NUM
-};
-
-enum GpioLevel {
- LOW = 0,
- HIGH
-};
-
-enum KeyState{
- UP = 0,
- DOWN,
-};
-
-struct xReportEvent {
- uint32_t ulCode;
- uint32_t event;
- TickType_t responseTime;
- void *data;
-};
-
-struct xKeyInitInfo {
- uint32_t ulKeyId;
- uint32_t eventMask;
- uint32_t repeatTimeMs;
- uint32_t repeatDelayTimeMs;
- uint32_t longDTTMs;
- uint32_t doubleDTTMs;
- uint32_t combLongDTTMs;
- uint32_t combDTTMs;
- void (*CallBack)(struct xReportEvent);
- void *data;
-};
-
-struct xGpioKeyInfo {
- int ulInitLevel;
- struct xKeyInitInfo keyInitInfo;
-};
-
-struct xAdcKeyInfo {
- int32_t ulValue;
- AdcInstanceConfig_t xAdcDecp;
- struct xKeyInitInfo keyInitInfo;
-};
-
-#define KEY_INIT_INFO(_ulKeyId, _eventMask, _repeatTimeMs,\
- _repeatDelayTimeMs, _longDTTMs, _doubleDTTMs,\
- _combLongDTTMs, _combDTTMs, _CallBack, _data) { \
- .ulKeyId = _ulKeyId, \
- .eventMask = _eventMask, \
- .repeatTimeMs = _repeatTimeMs, \
- .repeatDelayTimeMs = _repeatDelayTimeMs, \
- .longDTTMs = _longDTTMs, \
- .doubleDTTMs = _doubleDTTMs, \
- .combLongDTTMs = _combLongDTTMs, \
- .combDTTMs = _combDTTMs, \
- .CallBack = _CallBack, \
- .data = _data, \
-}
-
-#define GPIO_KEY_INFO(_ulKeyId, _ulInitLevel, _eventMask,\
- _CallBack, _data) { \
- .ulInitLevel = _ulInitLevel, \
- .keyInitInfo = KEY_INIT_INFO(_ulKeyId, _eventMask, 0, 0, 0,\
- 0, 0, 0, _CallBack, _data),\
-}
-
-#define ADC_KEY_INFO(_ulKeyId, _ulValue, _adcChan, _eventMask,\
- _CallBack, _data) { \
- .ulValue = _ulValue, \
- .xAdcDecp = {_adcChan, NO_AVERAGING, 1}, \
- .keyInitInfo = KEY_INIT_INFO(_ulKeyId, _eventMask, 0, 0, 0,\
- 0, 0, 0, _CallBack, _data),\
-}
-
-void vCreateGpioKey(struct xGpioKeyInfo *keyArr, uint16_t keyNum);
-void vDestoryGpioKey(void);
-void vGpioKeyEnable(void);
-void vGpioKeyDisable(void);
-int vGpioKeyIsEmpty(void);
-
-void vCreateAdcKey(struct xAdcKeyInfo *keyArr, uint16_t keyNum);
-void vDestoryAdcKey(void);
-void vAdcKeyEnable(void);
-void vAdcKeyDisable(void);
-int vAdcKeyIsEmpty(void);
-
-void vKeyPadCreate(void);
-void vKeyPadInit(void);
-void vKeyPadDeinit(void);
-
-void vDynamicKeypadInit(void);
-#ifdef __cplusplus
-}
-#endif
-#endif
diff --git a/at309_t962d4/include/power.h b/at309_t962d4/include/power.h
deleted file mode 100644
index 97001b0..0000000
--- a/at309_t962d4/include/power.h
+++ /dev/null
@@ -1,32 +0,0 @@
-/*
- * Copyright (C) 2014-2018 Amlogic, Inc. All rights reserved.
- *
- * All information contained herein is Amlogic confidential.
- *
- * This software is provided to you pursuant to Software License Agreement
- * (SLA) with Amlogic Inc ("Amlogic"). This software may be used
- * only in accordance with the terms of this agreement.
- *
- * Redistribution and use in source and binary forms, with or without
- * modification is strictly prohibited without prior written permission from
- * Amlogic.
- *
- * 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
- * OWNER 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.
- */
-
-
-extern void str_hw_init(void);
-extern void str_hw_disable(void);
-extern void str_power_on(int shutdown_flag);
-extern void str_power_off(int shutdown_flag);
-
diff --git a/at309_t962d4/keypad.c b/at309_t962d4/keypad.c
deleted file mode 100644
index 5364973..0000000
--- a/at309_t962d4/keypad.c
+++ /dev/null
@@ -1,58 +0,0 @@
-#include <string.h>
-#include <stdio.h>
-#include "FreeRTOS.h"
-#include "ir.h"
-#include "keypad.h"
-#include "gpio.h"
-#include "saradc.h"
-#include "suspend.h"
-
-/*KEY ID*/
-#define ADC_KEY_ID_HOME 520
-
-static void vAdcKeyCallBack(struct xReportEvent event)
-{
- uint32_t buf[4] = {0};
-
- switch (event.ulCode) {
- case ADC_KEY_ID_HOME:
- buf[0] = POWER_KEY_WAKEUP;
- STR_Wakeup_src_Queue_Send(buf);
- break;
- default:
- break;
- }
-
- printf("ADC key event 0x%x, key code %d, responseTicks %d\n",
- event.event, event.ulCode, event.responseTime);
-}
-
-struct xAdcKeyInfo adcKeyInfo[] = {
- ADC_KEY_INFO(ADC_KEY_ID_HOME, 0, SARADC_CH1,
- EVENT_SHORT,
- vAdcKeyCallBack, NULL)
-};
-
-void vKeyPadCreate(void)
-{
- vCreateAdcKey(adcKeyInfo,
- sizeof(adcKeyInfo)/sizeof(struct xAdcKeyInfo));
-
- vDynamicKeypadInit();
-}
-
-void vKeyPadInit(void)
-{
- if (vAdcKeyIsEmpty())
- vCreateAdcKey(adcKeyInfo,
- sizeof(adcKeyInfo)/sizeof(struct xAdcKeyInfo));
-
- vAdcKeyEnable();
- vGpioKeyEnable();
-}
-
-void vKeyPadDeinit(void)
-{
- vAdcKeyDisable();
- vGpioKeyDisable();
-}
diff --git a/at309_t962d4/main.c b/at309_t962d4/main.c
deleted file mode 100644
index bc382dd..0000000
--- a/at309_t962d4/main.c
+++ /dev/null
@@ -1,255 +0,0 @@
-/*
- * IntTest.c
- *
- * Created on: 2018��10��17��
- * Author: danialxie
- *
- * This is an PIC interrupt nesting test for N200 SOC, NUCLEI, Inc.
- * Attention:
- * This test need hardware board supporting.
- * A GPIO interrupt is stimulated by another GPIO using wire connection.
- * Wire connection:
- * Source --> Target
- * GPIO 0 --> GPIO 8
- * GPIO 1 --> GPIO 9
- * GPIO 2 --> GPIO 10
- * GPIO 3 --> GPIO 11
- * GPIO 4 --> GPIO 12
- * GPIO 5 --> GPIO 13
- * GPIO 6 --> GPIO 14
- * GPIO 7 --> GPIO 15
- */
-
-/* Kernel includes. */
-#include "FreeRTOS.h" /* Must come first. */
-#include "task.h" /* RTOS task related API prototypes. */
-#include "queue.h" /* RTOS queue related API prototypes. */
-#include "timers.h" /* Software timer related API prototypes. */
-#include "semphr.h" /* Semaphore related API prototypes. */
-
-#include <stdio.h>
-#include <stdlib.h>
-#include <string.h>
-#include <unistd.h>
-
-#include "n200_pic_tmr.h"
-#include "n200_func.h"
-#include "uart.h"
-#include "common.h"
-#include "mailbox-api.h"
-#include "version.h"
-#include "hdmi_cec.h"
-#include "stick_mem.h"
-#include "keypad.h"
-
-#define INT_TEST_NEST_DEPTH 6
-#define INT_TEST_GPIO_NUM 6
-#define INT_TEST_TASK_DELAY 50 // ms
-#define TASK_TEST_STACK_DEPTH 200
-
-#define TASK_TEST_QUEUE_NUM 2
-#define TASK_TEST_QUEUE_LENGTH 3
-
-//#define GPIO_INT_SOURCE(x) (SOC_PIC_INT_GPIO_BASE + x)
-
-/* Configure board type:
- * Board under test : SIGNAL_BOARD_ENABLE 0
- * Signal generation board : SIGNAL_BOARD_ENABLE 1
- */
-#define SIGNAL_BOARD_ENABLE 0
-
-#define INT_TEST_INT_WAVE_ENABLE 1
-
-#if INT_TEST_INT_WAVE_ENABLE
- #define INT_TEST_TIMER_PERIOD 500 // ms
- #define INT_TEST_INT_DELAY 10 // ms
-#else
- #define INT_TEST_TIMER_PERIOD 500 // ms
- #define INT_TEST_INT_DELAY 0x3ff // ms
-#endif
-
-#define INT_TEST_MAX_TIMER_PERIOD 100 // ms
-#define INT_TEST_MIN_TIMER_PERIOD 50 // ms
-#define INT_TEST_MUTE_TIMER_PERIOD 200 // ms
-
-/* Interrupt handler */
-void GPIOInterruptHandler(uint32_t num, uint32_t priority);
-void vApplicationIdleHook( void );
-
-
-extern void trap_entry(void);
-extern void irq_entry(void);
-
-
-/* Binary Semaphore */
-QueueHandle_t xGPIOSemaphore[INT_TEST_NEST_DEPTH];
-QueueHandle_t xMessageQueue[TASK_TEST_QUEUE_NUM];
-
-/* Timer handle */
-#if BRINGUP_TEST
-TimerHandle_t xSoftTimer = NULL;
-#endif
-/*
-static void vPrintString(const char* msg)
-{
- taskENTER_CRITICAL();
-
- taskEXIT_CRITICAL();
-}
-*/
-/* function: vPICInit */
-static void vPICInit(void) {
-
- // Disable global interrupter
- clear_csr(mstatus, MSTATUS_MIE);
-
- // Initialize interrupter handler
- for (int i = 0; i < PIC_NUM_INTERRUPTS; i ++) {
- pic_interrupt_handlers[i] = DefaultInterruptHandler;
- }
-#if 0
-#if !(SIGNAL_BOARD_ENABLE)
-
- // Enable GPIO interrupter
- enable_interrupt(GPIO_INT_SOURCE(8), 1, GPIOInterruptHandler8);
- enable_interrupt(GPIO_INT_SOURCE(9), 2, GPIOInterruptHandler9);
- enable_interrupt(GPIO_INT_SOURCE(10), 3, GPIOInterruptHandler10);
- enable_interrupt(GPIO_INT_SOURCE(11), 4, GPIOInterruptHandler11);
- enable_interrupt(GPIO_INT_SOURCE(12), 5, GPIOInterruptHandler12);
- enable_interrupt(GPIO_INT_SOURCE(13), 6, GPIOInterruptHandler13);
- //enable_interrupt(GPIO_INT_SOURCE(14), 7, GPIOInterruptHandler14);
- //enable_interrupt(GPIO_INT_SOURCE(15), 7, GPIOInterruptHandler15);
-
-#endif
-#endif
- // Enable global interrupt
- set_csr(mstatus, MSTATUS_MIE);
-}
-
-#if BRINGUP_TEST
-static void vPrintSystemStatus(TimerHandle_t xTimer) {
- xTimer = xTimer;
- taskENTER_CRITICAL();
-
-// vUartPuts("\nTimer ...\n");
- taskEXIT_CRITICAL();
-}
-
-static void vPrintTask1( void *pvParameters )
-{
- /*make compiler happy*/
- pvParameters = pvParameters;
-
- for ( ;; )
- {
-// vUartPuts("\nvPTask1 %d\n");
-
- vTaskDelay(pdMS_TO_TICKS(50));
- }
-}
-
-static void vPrintTask2( void *pvParameters )
-{
- /*make compiler happy*/
- pvParameters = pvParameters;
- vTaskDelay(pdMS_TO_TICKS(50));
- for ( ;; )
- {
-// vUartPuts("\nvPTask2 %d\n");
- vTaskDelay(pdMS_TO_TICKS(50));
- }
-}
-#endif
-extern void vMbInit(void);
-extern void vCoreFsmIdleInit(void);
-extern void vRtcInit(void);
-extern void create_str_task(void);
-// Test target board
-int main(void)
-{
- vUartPuts("Starting AOCPU FreeRTOS\n");
- version();
-
- // Initialize GPIOs, PIC and timer
- //vGPIOInit();
- vPICInit();
- stick_mem_init();
- //write watchdog flag
- stick_mem_write(STICK_REBOOT_FLAG, 0xd);
-
- // Delay
- for (uint32_t i = 0; i < 0xffff; ++i);
-
- vMbInit();
- vCoreFsmIdleInit();
- // Create timer
-#if BRINGUP_TEST
- xSoftTimer = xTimerCreate("Timer", pdMS_TO_TICKS(INT_TEST_TIMER_PERIOD), pdTRUE, NULL, vPrintSystemStatus);
-
- vUartPuts("Starting timer ...\n");
- xTimerStart(xSoftTimer, 0);
-
- xTaskCreate( vPrintTask1, "Print1", configMINIMAL_STACK_SIZE, NULL, 2, NULL );
- xTaskCreate( vPrintTask2, "Print2", configMINIMAL_STACK_SIZE, NULL, 2, NULL );
-#endif
-
- vCecCallbackInit(CEC_CHIP_T5);
- write_csr(mtvec, &trap_entry);
- write_csr_mivec(&irq_entry);
-
- vRtcInit();
- create_str_task();
- vKeyPadCreate();
-
- vUartPuts("Starting task scheduler ...\n");
- vTaskStartScheduler();
-
- for (;;)
-
- return 0;
-}
-
-void vApplicationIdleHook( void )
-{
- //vPrintString("enter idle task\n");
-
- //write_csr(mie, 1); // open mstatue.mie
- //asm volatile ("wfi"); // enter low power mode
-}
-/*-----------------------------------------------------------*/
-void vApplicationMallocFailedHook( void );
-
-void vApplicationMallocFailedHook( void )
-{
- /* The malloc failed hook is enabled by setting
- configUSE_MALLOC_FAILED_HOOK to 1 in FreeRTOSConfig.h.
-
- Called if a call to pvPortMalloc() fails because there is insufficient
- free memory available in the FreeRTOS heap. pvPortMalloc() is called
- internally by FreeRTOS API functions that create tasks, queues, software
- timers, and semaphores. The size of the FreeRTOS heap is set by the
- configTOTAL_HEAP_SIZE configuration constant in FreeRTOSConfig.h. */
- //write(1,"malloc failed\n", 14);
-
- vUartPuts("vApplicationMallocFailedHook\n");
- vPrintFreeListAfterMallocFail();
- for ( ;; );
-}
-/*-----------------------------------------------------------*/
-
-void vApplicationStackOverflowHook( TaskHandle_t xTask, signed char *pcTaskName );
-
-void vApplicationStackOverflowHook( TaskHandle_t xTask, signed char *pcTaskName )
-{
- ( void ) pcTaskName;
- ( void ) xTask;
-
- /* Run time stack overflow checking is performed if
- configconfigCHECK_FOR_STACK_OVERFLOW is defined to 1 or 2. This hook
- function is called if a stack overflow is detected. pxCurrentTCB can be
- inspected in the debugger if the task name passed into this function is
- corrupt. */
- //write(1, "Stack Overflow\n", 15);
- for ( ;; );
-}
-/*-----------------------------------------------------------*/
diff --git a/at309_t962d4/power.c b/at309_t962d4/power.c
deleted file mode 100644
index b5001f0..0000000
--- a/at309_t962d4/power.c
+++ /dev/null
@@ -1,232 +0,0 @@
-/*
- * Copyright (C) 2014-2018 Amlogic, Inc. All rights reserved.
- *
- * All information contained herein is Amlogic confidential.
- *
- * This software is provided to you pursuant to Software License Agreement
- * (SLA) with Amlogic Inc ("Amlogic"). This software may be used
- * only in accordance with the terms of this agreement.
- *
- * Redistribution and use in source and binary forms, with or without
- * modification is strictly prohibited without prior written permission from
- * Amlogic.
- *
- * 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
- * OWNER 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.
- */
-#include "FreeRTOS.h"
-#include "common.h"
-#include "gpio.h"
-#include "ir.h"
-#include "suspend.h"
-#include "task.h"
-#include "gpio.h"
-#include "pwm.h"
-#include "pwm_plat.h"
-#include "keypad.h"
-
-#include "hdmi_cec.h"
-
-/*#define CONFIG_ETH_WAKEUP*/
-
-#ifdef CONFIG_ETH_WAKEUP
-#include "interrupt_control.h"
-#include "eth.h"
-#include "irq.h"
-#endif
-
-static TaskHandle_t cecTask = NULL;
-static int vdd_ee;
-static int vdd_cpu;
-
-static IRPowerKey_t prvPowerKeyList[] = {
- { 0xef10fe01, IR_NORMAL}, /* ref tv pwr */
- { 0xba45bd02, IR_NORMAL}, /* small ir pwr */
- { 0xef10fb04, IR_NORMAL}, /* old ref tv pwr */
- { 0xf20dfe01, IR_NORMAL},
- { 0xe51afb04, IR_NORMAL},
- { 0x3ac5bd02, IR_CUSTOM},
- {}
- /* add more */
-};
-
-static void vIRHandler(IRPowerKey_t *pkey)
-{
- uint32_t buf[4] = {0};
- if (pkey->type == IR_NORMAL)
- buf[0] = REMOTE_WAKEUP;
- else if (pkey->type == IR_CUSTOM)
- buf[0] = REMOTE_CUS_WAKEUP;
-
- /* do sth below to wakeup*/
- STR_Wakeup_src_Queue_Send_FromISR(buf);
-};
-
-void str_hw_init(void);
-void str_hw_disable(void);
-void str_power_on(int shutdown_flag);
-void str_power_off(int shutdown_flag);
-void Bt_GpioIRQRegister(void);
-void Bt_GpioIRQFree(void);
-
-void str_hw_init(void)
-{
- /*enable device & wakeup source interrupt*/
- vIRInit(MODE_HARD_NEC, GPIOD_5, PIN_FUNC1, prvPowerKeyList, ARRAY_SIZE(prvPowerKeyList), vIRHandler);
-#ifdef CONFIG_ETH_WAKEUP
- vETHInit(IRQ_ETH_PMT_NUM,eth_handler_t5);
-#endif
- xTaskCreate(vCEC_task, "CECtask", configMINIMAL_STACK_SIZE,
- NULL, CEC_TASK_PRI, &cecTask);
- vBackupAndClearGpioIrqReg();
- vKeyPadInit();
- vGpioIRQInit();
- Bt_GpioIRQRegister();
-}
-
-
-void str_hw_disable(void)
-{
- /*disable wakeup source interrupt*/
- vIRDeint();
-#ifdef CONFIG_ETH_WAKEUP
- vETHDeint_t5();
-#endif
- if (cecTask) {
- vTaskDelete(cecTask);
- cec_req_irq(0);
- }
- Bt_GpioIRQFree();
- vKeyPadDeinit();
- vRestoreGpioIrqReg();
-}
-
-void str_power_on(int shutdown_flag)
-{
- int ret;
-
- /***set vdd_ee val***/
- ret = vPwmMesonsetvoltage(VDDEE_VOLT,vdd_ee);
- if (ret < 0) {
- printf("vdd_EE pwm set fail\n");
- return;
- }
-
- /***set vdd_ee val***/
- ret = vPwmMesonsetvoltage(VDDCPU_VOLT,vdd_cpu);
- if (ret < 0) {
- printf("vdd_CPU pwm set fail\n");
- return;
- }
-
- /***power on vcc3.3***/
- ret = xGpioSetDir(GPIOD_10,GPIO_DIR_OUT);
- if (ret < 0) {
- printf("vcc3.3 set gpio dir fail\n");
- return;
- }
-
- ret = xGpioSetValue(GPIOD_10,GPIO_LEVEL_HIGH);
- if (ret < 0) {
- printf("vcc3.3 set gpio val fail\n");
- return;
- }
-
- if (shutdown_flag) {
- /***power on VDDQ/VDDCPU***/
- ret = xGpioSetDir(GPIOD_4,GPIO_DIR_OUT);
- if (ret < 0) {
- printf("VDDCPU/VDDQ set gpio dir fail\n");
- return;
- }
-
- ret = xGpioSetValue(GPIOD_4,GPIO_LEVEL_HIGH);
- if (ret < 0) {
- printf("VDDCPU/VDDQ set gpio val fail\n");
- return;
- }
- /*Wait 200ms for VDDCPU statble*/
- vTaskDelay(pdMS_TO_TICKS(200));
- }
-
- /***power on 5v***/
- REG32(AO_GPIO_TEST_N) = REG32(AO_GPIO_TEST_N) | (1 << 31);
-}
-
-void str_power_off(int shutdown_flag)
-{
- int ret;
-
- printf("poweroff 5v\n");
- printf("0x%x\n", REG32(AO_GPIO_TEST_N));
-
- REG32(AO_GPIO_TEST_N) = (REG32(AO_GPIO_TEST_N) << 1) >> 1;
-
- if (shutdown_flag) {
- /***power off VDDQ/VDDCPU***/
- ret = xGpioSetDir(GPIOD_4,GPIO_DIR_OUT);
- if (ret < 0) {
- printf("VDDCPU/VDDQ set gpio dir fail\n");
- return;
- }
-
- ret = xGpioSetValue(GPIOD_4,GPIO_LEVEL_LOW);
- if (ret < 0) {
- printf("VDDCPU/VDDQ set gpio val fail\n");
- return;
- }
- }
-
- /***power off vcc3.3***/
- ret = xGpioSetDir(GPIOD_10,GPIO_DIR_OUT);
- if (ret < 0) {
- printf("vcc3.3 set gpio dir fail\n");
- return;
- }
-
-#ifndef CONFIG_ETH_WAKEUP
- ret= xGpioSetValue(GPIOD_10,GPIO_LEVEL_LOW);
- if (ret < 0) {
- printf("vcc3.3 set gpio val fail\n");
- return;
- }
-#endif
-
- /***set vdd_cpu val***/
- vdd_cpu = vPwmMesongetvoltage(VDDCPU_VOLT);
- if (vdd_cpu < 0) {
- printf("vdd_CPU pwm get fail\n");
- return;
- }
-
- ret = vPwmMesonsetvoltage(VDDCPU_VOLT,700);
- if (ret < 0) {
- printf("vdd_CPU pwm set fail\n");
- return;
- }
-
- /***set vdd_ee val***/
- vdd_ee = vPwmMesongetvoltage(VDDEE_VOLT);
- if (vdd_ee < 0) {
- printf("vdd_EE pwm get fail\n");
- return;
- }
-
- ret = vPwmMesonsetvoltage(VDDEE_VOLT,770);
- if (ret < 0) {
- printf("vdd_EE pwm set fail\n");
- return;
- }
-
- //REG32( ((0x0000 << 2) + 0xff638c00)) = 0;
-}
-
diff --git a/at309_t962d4/util.c b/at309_t962d4/util.c
deleted file mode 100644
index e5a71e9..0000000
--- a/at309_t962d4/util.c
+++ /dev/null
@@ -1,167 +0,0 @@
-/* Copyright (c) 2013 The Chromium OS Authors. All rights reserved.
- * Use of this source code is governed by a BSD-style license that can be
- * found in the LICENSE file.
- */
-
-/* Utility functions for Chrome EC */
-
-#include "util.h"
-#include <string.h>
-#include <ctype.h>
-
-int parse_bool(const char *s, int *dest)
-{
- if (!strcasecmp(s, "off") || !strncasecmp(s, "dis", 3) ||
- tolower(*s) == 'f' || tolower(*s) == 'n') {
- *dest = 0;
- return 1;
- } else if (!strcasecmp(s, "on") || !strncasecmp(s, "ena", 3) ||
- tolower(*s) == 't' || tolower(*s) == 'y') {
- *dest = 1;
- return 1;
- } else {
- return 0;
- }
-}
-
-int uint64divmod(uint64_t *n, int d)
-{
- uint64_t q = 0, mask;
- int r = 0;
-
- /* Divide-by-zero returns zero */
- if (!d) {
- *n = 0;
- return 0;
- }
-
- /* Common powers of 2 = simple shifts */
- if (d == 2) {
- r = *n & 1;
- *n >>= 1;
- return r;
- } else if (d == 16) {
- r = *n & 0xf;
- *n >>= 4;
- return r;
- }
-
- /* If v fits in 32-bit, we're done. */
- if (*n <= 0xffffffff) {
- uint32_t v32 = *n;
- r = v32 % d;
- *n = v32 / d;
- return r;
- }
-
- /* Otherwise do integer division the slow way. */
- for (mask = (1ULL << 63); mask; mask >>= 1) {
- r <<= 1;
- if (*n & mask)
- r |= 1;
- if (r >= d) {
- r -= d;
- q |= mask;
- }
- }
- *n = q;
- return r;
-}
-
-int __clzsi2(int x)
-{
- int r = 0;
-
- if (!x)
- return 32;
- if (!(x & 0xffff0000u)) {
- x <<= 16;
- r += 16;
- }
- if (!(x & 0xff000000u)) {
- x <<= 8;
- r += 8;
- }
- if (!(x & 0xf0000000u)) {
- x <<= 4;
- r += 4;
- }
- if (!(x & 0xc0000000u)) {
- x <<= 2;
- r += 2;
- }
- if (!(x & 0x80000000u)) {
- x <<= 1;
- r += 1;
- }
- return r;
-}
-
-int get_next_bit(uint32_t *mask)
-{
- int bit = 31 - __clzsi2(*mask);
- *mask &= ~(1 << bit);
- return bit;
-}
-
-char *strncpy (char *s1, const char *s2, size_t n)
-{
- char c;
- char *s = s1;
-
- --s1;
-
- if (n >= 4)
- {
- size_t n4 = n >> 2;
-
- for (;;)
- {
- c = *s2++;
- *++s1 = c;
- if (c == '\0')
- break;
- c = *s2++;
- *++s1 = c;
- if (c == '\0')
- break;
- c = *s2++;
- *++s1 = c;
- if (c == '\0')
- break;
- c = *s2++;
- *++s1 = c;
- if (c == '\0')
- break;
- if (--n4 == 0)
- goto last_chars;
- }
- n = n - (s1 - s) - 1;
- if (n == 0)
- return s;
- goto zero_fill;
- }
-
- last_chars:
- n &= 3;
- if (n == 0)
- return s;
-
- do
- {
- c = *s2++;
- *++s1 = c;
- if (--n == 0)
- return s;
- }
- while (c != '\0');
-
- zero_fill:
- do
- *++s1 = '\0';
- while (--n > 0);
-
- return s;
-}
-
-
diff --git a/am301_t950d4/btwake.c b/btwake.c
similarity index 100%
rename from am301_t950d4/btwake.c
rename to btwake.c
diff --git a/am301_t950d4/fsm.c b/fsm.c
similarity index 100%
rename from am301_t950d4/fsm.c
rename to fsm.c
diff --git a/am301_t950d4/keypad.c b/keypad.c
similarity index 100%
rename from am301_t950d4/keypad.c
rename to keypad.c
diff --git a/am301_t950d4/include/keypad.h b/keypad.h
similarity index 100%
rename from am301_t950d4/include/keypad.h
rename to keypad.h
diff --git a/am301_t950d4/main.c b/main.c
similarity index 100%
rename from am301_t950d4/main.c
rename to main.c
diff --git a/am301_t950d4/power.c b/power.c
similarity index 100%
rename from am301_t950d4/power.c
rename to power.c
diff --git a/am301_t950d4/include/power.h b/power.h
similarity index 100%
rename from am301_t950d4/include/power.h
rename to power.h
diff --git a/am301_t950d4/util.c b/util.c
similarity index 100%
rename from am301_t950d4/util.c
rename to util.c