forked from xuos/xiuos
Merge branch 'master' of https://git.trustie.net/IACU/xiuos into spi_flash_test
This commit is contained in:
commit
03e646e0d0
2
Makefile
2
Makefile
|
@ -5,7 +5,7 @@ MAKEFLAGS += --no-print-directory
|
|||
.PHONY:COMPILE_APP COMPILE_KERNEL
|
||||
|
||||
|
||||
support :=kd233 stm32f407-st-discovery maix-go stm32f407zgt6 aiit-riscv64-board aiit-arm32-board hifive1-rev-B hifive1-emulator k210-emulator
|
||||
support :=kd233 stm32f407-st-discovery maix-go stm32f407zgt6 aiit-riscv64-board aiit-arm32-board hifive1-rev-B hifive1-emulator k210-emulator cortex-m3-emulator
|
||||
SRC_DIR:=
|
||||
|
||||
export BOARD ?=kd233
|
||||
|
|
|
@ -1,4 +1,12 @@
|
|||
#公共部分
|
||||
SRC_DIR := shared cortex-m4
|
||||
SRC_DIR := shared
|
||||
|
||||
ifeq ($(CONFIG_BOARD_CORTEX_M3_EVB),y)
|
||||
SRC_DIR +=cortex-m3
|
||||
endif
|
||||
|
||||
ifeq ($(CONFIG_BOARD_STM32F407_EVB),y)
|
||||
SRC_DIR +=cortex-m4
|
||||
endif
|
||||
|
||||
include $(KERNEL_ROOT)/compiler.mk
|
||||
|
|
|
@ -0,0 +1,3 @@
|
|||
SRC_FILES := boot.c interrupt.c interrupt_vector.S
|
||||
|
||||
include $(KERNEL_ROOT)/compiler.mk
|
|
@ -0,0 +1,28 @@
|
|||
/*
|
||||
* Copyright (c) 2020 AIIT XUOS Lab
|
||||
* XiUOS is licensed under Mulan PSL v2.
|
||||
* You can use this software according to the terms and conditions of the Mulan PSL v2.
|
||||
* You may obtain a copy of Mulan PSL v2 at:
|
||||
* http://license.coscl.org.cn/MulanPSL2
|
||||
* THIS SOFTWARE IS PROVIDED ON AN "AS IS" BASIS, WITHOUT WARRANTIES OF ANY KIND,
|
||||
* EITHER EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO NON-INFRINGEMENT,
|
||||
* MERCHANTABILITY OR FIT FOR A PARTICULAR PURPOSE.
|
||||
* See the Mulan PSL v2 for more details.
|
||||
*/
|
||||
|
||||
#ifndef ARCH_INTERRUPT_H__
|
||||
#define ARCH_INTERRUPT_H__
|
||||
|
||||
#include <xs_base.h>
|
||||
|
||||
#define ARCH_MAX_IRQ_NUM (256)
|
||||
|
||||
#define ARCH_IRQ_NUM_OFFSET 0
|
||||
|
||||
#define SYSTICK_IRQN 15
|
||||
#define UART1_IRQn 21
|
||||
|
||||
int32 ArchEnableHwIrq(uint32 irq_num);
|
||||
int32 ArchDisableHwIrq(uint32 irq_num);
|
||||
|
||||
#endif
|
|
@ -0,0 +1,97 @@
|
|||
//*****************************************************************************
|
||||
//
|
||||
// startup_gcc.c - Startup code for use with GNU tools.
|
||||
//
|
||||
// Copyright (c) 2013 Texas Instruments Incorporated. All rights reserved.
|
||||
// Software License Agreement
|
||||
//
|
||||
// Redistribution and use in source and binary forms, with or without
|
||||
// modification, are permitted provided that the following conditions
|
||||
// are met:
|
||||
//
|
||||
// Redistributions of source code must retain the above copyright
|
||||
// notice, this list of conditions and the following disclaimer.
|
||||
//
|
||||
// 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.
|
||||
//
|
||||
// Neither the name of Texas Instruments Incorporated 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
|
||||
// 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.
|
||||
//
|
||||
// This is part of revision 10636 of the Stellaris Firmware Development Package.
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
/**
|
||||
* @file boot.c
|
||||
* @brief derived from Stellaris Firmware Development Package
|
||||
* @version 1.0
|
||||
* @author AIIT XUOS Lab
|
||||
* @date 2021-05-13
|
||||
*/
|
||||
|
||||
/*************************************************
|
||||
File name: boot.c
|
||||
Description: Reset and init function
|
||||
Others:
|
||||
History:
|
||||
1. Date: 2021-05-13
|
||||
Author: AIIT XUOS Lab
|
||||
Modification:
|
||||
1. take startup_gcc.c from revision 10636 of the Stellaris Firmware Development Package for XiUOS
|
||||
*************************************************/
|
||||
|
||||
extern unsigned long _sidata;
|
||||
extern unsigned long _sdata;
|
||||
extern unsigned long _edata;
|
||||
extern unsigned long _sbss;
|
||||
extern unsigned long _ebss;
|
||||
extern int entry(void);
|
||||
|
||||
void
|
||||
Reset_Handler(void)
|
||||
{
|
||||
unsigned long *pulSrc, *pulDest;
|
||||
|
||||
//
|
||||
// Copy the data segment initializers from flash to SRAM.
|
||||
//
|
||||
pulSrc = &_sidata;
|
||||
for(pulDest = &_sdata; pulDest < &_edata; )
|
||||
{
|
||||
*pulDest++ = *pulSrc++;
|
||||
}
|
||||
|
||||
//
|
||||
// Zero fill the bss segment.
|
||||
//
|
||||
__asm(" ldr r0, =_sbss\n"
|
||||
" ldr r1, =_ebss\n"
|
||||
" mov r2, #0\n"
|
||||
" .thumb_func\n"
|
||||
"zero_loop:\n"
|
||||
" cmp r0, r1\n"
|
||||
" it lt\n"
|
||||
" strlt r2, [r0], #4\n"
|
||||
" blt zero_loop");
|
||||
|
||||
//
|
||||
// Call the application's entry point.
|
||||
//
|
||||
entry();
|
||||
}
|
|
@ -0,0 +1,84 @@
|
|||
/*
|
||||
* Copyright (c) 2020 AIIT XUOS Lab
|
||||
* XiUOS is licensed under Mulan PSL v2.
|
||||
* You can use this software according to the terms and conditions of the Mulan PSL v2.
|
||||
* You may obtain a copy of Mulan PSL v2 at:
|
||||
* http://license.coscl.org.cn/MulanPSL2
|
||||
* THIS SOFTWARE IS PROVIDED ON AN "AS IS" BASIS, WITHOUT WARRANTIES OF ANY KIND,
|
||||
* EITHER EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO NON-INFRINGEMENT,
|
||||
* MERCHANTABILITY OR FIT FOR A PARTICULAR PURPOSE.
|
||||
* See the Mulan PSL v2 for more details.
|
||||
*/
|
||||
|
||||
/**
|
||||
* @file interrupt.c
|
||||
* @brief support arm cortex-m4 interrupt function
|
||||
* @version 1.0
|
||||
* @author AIIT XUOS Lab
|
||||
* @date 2021-04-29
|
||||
*/
|
||||
|
||||
#include <xs_base.h>
|
||||
#include <xs_isr.h>
|
||||
|
||||
|
||||
x_base __attribute__((naked)) DisableLocalInterrupt()
|
||||
{
|
||||
asm volatile ("MRS r0, PRIMASK");
|
||||
asm volatile ("CPSID I");
|
||||
asm volatile ("BX LR ");
|
||||
}
|
||||
|
||||
void __attribute__((naked)) EnableLocalInterrupt(x_base level)
|
||||
{
|
||||
asm volatile ("MSR PRIMASK, r0");
|
||||
asm volatile ("BX LR");
|
||||
}
|
||||
|
||||
int32 ArchEnableHwIrq(uint32 irq_num)
|
||||
{
|
||||
return EOK;
|
||||
}
|
||||
|
||||
int32 ArchDisableHwIrq(uint32 irq_num)
|
||||
{
|
||||
return EOK;
|
||||
}
|
||||
|
||||
extern void KTaskOsAssignAfterIrq(void *context);
|
||||
|
||||
void IsrEntry()
|
||||
{
|
||||
uint32 ipsr;
|
||||
|
||||
__asm__ volatile("MRS %0, IPSR" : "=r"(ipsr));
|
||||
|
||||
isrManager.done->incCounter();
|
||||
isrManager.done->handleIrq(ipsr);
|
||||
KTaskOsAssignAfterIrq(NONE);
|
||||
isrManager.done->decCounter();
|
||||
|
||||
}
|
||||
|
||||
void UsageFault_Handler(int irqn, void *arg)
|
||||
{
|
||||
/* Go to infinite loop when Usage Fault exception occurs */
|
||||
while (1)
|
||||
{
|
||||
}
|
||||
}
|
||||
|
||||
void BusFault_Handler(int irqn, void *arg)
|
||||
{
|
||||
/* Go to infinite loop when Bus Fault exception occurs */
|
||||
while (1)
|
||||
{
|
||||
}
|
||||
}
|
||||
|
||||
void NMI_Handler(int irqn, void *arg)
|
||||
{
|
||||
while (1)
|
||||
{
|
||||
}
|
||||
}
|
|
@ -0,0 +1,138 @@
|
|||
//*****************************************************************************
|
||||
//
|
||||
// startup_gcc.c - Startup code for use with GNU tools.
|
||||
//
|
||||
// Copyright (c) 2013 Texas Instruments Incorporated. All rights reserved.
|
||||
// Software License Agreement
|
||||
//
|
||||
// Redistribution and use in source and binary forms, with or without
|
||||
// modification, are permitted provided that the following conditions
|
||||
// are met:
|
||||
//
|
||||
// Redistributions of source code must retain the above copyright
|
||||
// notice, this list of conditions and the following disclaimer.
|
||||
//
|
||||
// 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.
|
||||
//
|
||||
// Neither the name of Texas Instruments Incorporated 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
|
||||
// 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.
|
||||
//
|
||||
// This is part of revision 10636 of the Stellaris Firmware Development Package.
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
/**
|
||||
* @file interrupt_vector.S
|
||||
* @brief derived from Stellaris Firmware Development Package
|
||||
* @version 1.0
|
||||
* @author AIIT XUOS Lab
|
||||
* @date 2021-05-13
|
||||
*/
|
||||
|
||||
/*************************************************
|
||||
File name: interrupt_vector.S
|
||||
Description: vector table for a Cortex M3
|
||||
Others:
|
||||
History:
|
||||
1. Date: 2021-05-13
|
||||
Author: AIIT XUOS Lab
|
||||
Modification:
|
||||
1. take startup_gcc.c from revision 10636 of the Stellaris Firmware Development Package for XiUOS
|
||||
*************************************************/
|
||||
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The vector table. Note that the proper constructs must be placed on this to
|
||||
// ensure that it ends up at physical address 0x0000.0000.
|
||||
//
|
||||
//*****************************************************************************
|
||||
.globl InterruptVectors
|
||||
|
||||
/******************************************************************************
|
||||
*******************************************************************************/
|
||||
.section .isr_vector,"a",%progbits
|
||||
.type InterruptVectors, %object
|
||||
.size InterruptVectors, .-InterruptVectors
|
||||
|
||||
InterruptVectors:
|
||||
.word _sp
|
||||
.word Reset_Handler
|
||||
.word NMI_Handler //NMI_Handler
|
||||
.word HardFaultHandler
|
||||
.word MemFaultHandler //MemManage_Handler
|
||||
.word BusFault_Handler //BusFault_Handler
|
||||
.word UsageFault_Handler //UsageFault_Handler
|
||||
.word IsrEntry
|
||||
.word IsrEntry
|
||||
.word IsrEntry
|
||||
.word IsrEntry
|
||||
.word IsrEntry //SVC_Handler
|
||||
.word IsrEntry //DebugMon_Handler
|
||||
.word IsrEntry
|
||||
.word PendSV_Handler
|
||||
.word IsrEntry //systick
|
||||
.word IsrEntry // GPIO Port A
|
||||
.word IsrEntry // GPIO Port B
|
||||
.word IsrEntry // GPIO Port C
|
||||
.word IsrEntry // GPIO Port D
|
||||
.word IsrEntry // GPIO Port E
|
||||
.word IsrEntry // UART0 Rx and Tx
|
||||
.word IsrEntry // UART1 Rx and Tx
|
||||
.word IsrEntry // SSI Rx and Tx
|
||||
.word IsrEntry // I2C Master and Slave
|
||||
.word IsrEntry // PWM Fault
|
||||
.word IsrEntry // PWM Generator 0
|
||||
.word IsrEntry // PWM Generator 1
|
||||
.word IsrEntry // PWM Generator 2
|
||||
.word IsrEntry // Quadrature Encoder
|
||||
.word IsrEntry // ADC Sequence 0
|
||||
.word IsrEntry // ADC Sequence 1
|
||||
.word IsrEntry // ADC Sequence 2
|
||||
.word IsrEntry // ADC Sequence 3
|
||||
.word IsrEntry // Watchdog timer
|
||||
.word IsrEntry // Timer 0 subtimer A
|
||||
.word IsrEntry // Timer 0 subtimer B
|
||||
.word IsrEntry // Timer 1 subtimer A
|
||||
.word IsrEntry // Timer 1 subtimer B
|
||||
.word IsrEntry // Timer 2 subtimer A
|
||||
.word IsrEntry // Timer 2 subtimer B
|
||||
.word IsrEntry // Analog Comparator 0
|
||||
.word IsrEntry // Analog Comparator 1
|
||||
.word IsrEntry // Analog Comparator 2
|
||||
.word IsrEntry // System Control (PLL, OSC,
|
||||
.word IsrEntry // FLASH Control
|
||||
.word IsrEntry // GPIO Port F
|
||||
.word IsrEntry // GPIO Port G
|
||||
.word IsrEntry // GPIO Port H
|
||||
.word IsrEntry // UART2 Rx and Tx
|
||||
.word IsrEntry // SSI1 Rx and Tx
|
||||
.word IsrEntry // Timer 3 subtimer A
|
||||
.word IsrEntry // Timer 3 subtimer B
|
||||
.word IsrEntry // I2C1 Master and Slave
|
||||
.word IsrEntry // Quadrature Encoder 1
|
||||
.word IsrEntry // CAN0
|
||||
.word IsrEntry // CAN1
|
||||
.word IsrEntry // CAN2
|
||||
.word IsrEntry // Ethernet
|
||||
.word IsrEntry // Hibernate
|
||||
.word IsrEntry // USB0
|
||||
.word IsrEntry // PWM Generator 3
|
||||
.word IsrEntry // uDMA Software Transfer
|
||||
.word IsrEntry // uDMA Error
|
|
@ -14,7 +14,6 @@
|
|||
#include <xs_ktask.h>
|
||||
#include <xs_assign.h>
|
||||
#include "svc_handle.h"
|
||||
#include "stm32f4xx.h"
|
||||
#include <board.h>
|
||||
#include <shell.h>
|
||||
|
||||
|
@ -380,12 +379,6 @@ void MemFaultExceptionPrint(struct ExceptionInfo *ExceptionInfo)
|
|||
if ((ExceptionInfo->ExcReturn & 0x10) == 0)
|
||||
KPrintf("FPU active!\r\n");
|
||||
|
||||
KPrintf("CFSR: 0x%08x \n", (*((volatile unsigned long *)(SCB->CFSR))) );
|
||||
KPrintf("HFSR: 0x%08x \n", (*((volatile unsigned long *)(SCB->HFSR))) );
|
||||
KPrintf("DFSR: 0x%08x \n",(*((volatile unsigned long *)(SCB->DFSR))) );
|
||||
KPrintf("MMFAR: 0x%08x \n",(*((volatile unsigned long *)(SCB->MMFAR))));
|
||||
KPrintf("BFAR: 0x%08x \n",(*((volatile unsigned long *)(SCB->BFAR))));
|
||||
KPrintf("AFSR: 0x%08x \n",(*((volatile unsigned long *)(SCB->AFSR))));
|
||||
|
||||
#ifdef TOOL_SHELL
|
||||
HardFaultTrack();
|
||||
|
|
|
@ -70,13 +70,13 @@ _begin:
|
|||
j Kd233Start
|
||||
|
||||
|
||||
#ifdef ARCH_SMP
|
||||
|
||||
.data
|
||||
.globl cpu2_boot_flag
|
||||
.align 3
|
||||
cpu2_boot_flag:
|
||||
.8byte 0
|
||||
#endif
|
||||
|
||||
|
||||
.section .text.entry
|
||||
.align 2
|
||||
|
|
|
@ -84,14 +84,17 @@ void Kd233Start(uint32_t mhartid)
|
|||
/*kernel start entry*/
|
||||
entry();
|
||||
break;
|
||||
#ifdef ARCH_SMP
|
||||
case CPU1:
|
||||
while(0x2018050420191010 != cpu2_boot_flag) { ///< waiting for boot flag ,then start cpu1 core
|
||||
|
||||
}
|
||||
SecondaryCpuCStart();
|
||||
break;
|
||||
#ifndef ARCH_SMP
|
||||
asm volatile("wfi");
|
||||
#endif
|
||||
}
|
||||
#ifdef ARCH_SMP
|
||||
SecondaryCpuCStart();
|
||||
#endif
|
||||
break;
|
||||
|
||||
default:
|
||||
break;
|
||||
}
|
||||
|
|
|
@ -0,0 +1,248 @@
|
|||
#
|
||||
# Automatically generated file; DO NOT EDIT.
|
||||
# XiUOS Project Configuration
|
||||
#
|
||||
CONFIG_BOARD_CORTEX_M3_EVB=y
|
||||
CONFIG_KERNEL_CONSOLE_DEVICE_NAME="uart0"
|
||||
#CONFIG_LED0=24
|
||||
#CONFIG_LED1=25
|
||||
CONFIG_ARCH_RISCV=y
|
||||
CONFIG_ARCH_RISCV32=y
|
||||
CONFIG_ARCH_CPU_32BIT=y
|
||||
|
||||
#
|
||||
# cortex-m3-emulator feature
|
||||
#
|
||||
# CONFIG_BSP_USING_AUDIO is not set
|
||||
# CONFIG_BSP_USING_CAMERA is not set
|
||||
# CONFIG_BSP_USING_SDIO is not set
|
||||
# CONFIG_BSP_USING_DMA is not set
|
||||
CONFIG_BSP_USING_GPIO=y
|
||||
# CONFIG_BSP_USING_I2C is not set
|
||||
# CONFIG_BSP_USING_I2S is not set
|
||||
# CONFIG_BSP_USING_LCD is not set
|
||||
# CONFIG_BSP_USING_RTC is not set
|
||||
# CONFIG_BSP_USING_SECURITY is not set
|
||||
# CONFIG_BSP_USING_SPI is not set
|
||||
CONFIG_BSP_USING_UART=y
|
||||
# CONFIG_BSP_USING_UART_HS is not set
|
||||
# CONFIG_BSP_USING_VIDEO is not set
|
||||
# CONFIG_BSP_USING_WDT is not set
|
||||
|
||||
#
|
||||
# General Purpose UARTs
|
||||
#
|
||||
|
||||
CONFIG___STACKSIZE__=4096
|
||||
|
||||
#
|
||||
# Hardware feature
|
||||
#
|
||||
CONFIG_RESOURCES_SERIAL=y
|
||||
# CONFIG_SERIAL_USING_DMA=y
|
||||
CONFIG_SERIAL_RB_BUFSZ=64
|
||||
CONFIG_FS_VFS=n
|
||||
# CONFIG_RESOURCES_HWTIMER is not set
|
||||
# CONFIG_RESOURCES_I2C is not set
|
||||
# CONFIG_RESOURCES_LCD is not set
|
||||
# CONFIG_RESOURCES_SDIO is not set
|
||||
# CONFIG_RESOURCES_TOUCH is not set
|
||||
# CONFIG_RESOURCES_PIN=y
|
||||
# CONFIG_RESOURCES_RTC is not set
|
||||
# CONFIG_RESOURCES_SPI is not set
|
||||
#CONFIG_RESOURCES_SPI_SD is not set
|
||||
#CONFIG_RESOURCES_SPI_SFUD is not set
|
||||
# SFUD_USING_SFDP is not set
|
||||
# SFUD_USING_FLASH_INFO_TABLE is not set
|
||||
# SFUD_DEBUG_LOG is not set
|
||||
# CONFIG_RESOURCES_WDT is not set
|
||||
# CONFIG_RESOURCES_USB is not set
|
||||
# CONFIG_RESOURCES_USB_HOST is not set
|
||||
# CONFIG_UDISK_MOUNTPOINT is not set
|
||||
# CONFIG_USBH_MSTORAGE is not set
|
||||
# CONFIG_RESOURCES_USB_DEVICE is not set
|
||||
# CONFIG_USBD_THREAD_STACK_SZ is not set
|
||||
|
||||
#
|
||||
# Kernel feature
|
||||
#
|
||||
|
||||
#
|
||||
# Kernel Device Object
|
||||
#
|
||||
CONFIG_KERNEL_DEVICE=y
|
||||
CONFIG_KERNEL_CONSOLE=y
|
||||
CONFIG_KERNEL_CONSOLEBUF_SIZE=128
|
||||
|
||||
#
|
||||
# Task feature
|
||||
#
|
||||
CONFIG_SCHED_POLICY_RR_REMAINSLICE=y
|
||||
# CONFIG_SCHED_POLICY_RR is not set
|
||||
# CONFIG_SCHED_POLICY_FIFO is not set
|
||||
|
||||
#
|
||||
# Memory Management
|
||||
#
|
||||
# CONFIG_KERNEL_MEMBLOCK is not set
|
||||
CONFIG_MEM_ALIGN_SIZE=4
|
||||
CONFIG_MM_PAGE_SIZE=1024
|
||||
|
||||
#
|
||||
# Using small memory allocator
|
||||
#
|
||||
CONFIG_KERNEL_SMALL_MEM_ALLOC=y
|
||||
CONFIG_SMALL_NUMBER_32B=32
|
||||
CONFIG_SMALL_NUMBER_64B=16
|
||||
|
||||
#
|
||||
# Inter-Task communication
|
||||
#
|
||||
# CONFIG_KERNEL_SEMAPHORE=y
|
||||
# CONFIG_KERNEL_MUTEX=y
|
||||
CONFIG_KERNEL_EVENT=n
|
||||
CONFIG_KERNEL_MESSAGEQUEUE=n
|
||||
CONFIG_KTASK_PRIORITY_8=y
|
||||
CONFIG_KTASK_PRIORITY_MAX=8
|
||||
CONFIG_TICK_PER_SECOND=100
|
||||
# CONFIG_KERNEL_STACK_OVERFLOW_CHECK=y
|
||||
CONFIG_KERNEL_BANNER=y
|
||||
# CONFIG_KERNEL_HOOK is not set
|
||||
# CONFIG_KERNEL_SOFTTIMER=y
|
||||
# CONFIG_KERNEL_IDLE_HOOK=y
|
||||
# CONFIG_IDEL_HOOK_LIST_SIZE=4
|
||||
CONFIG_IDLE_KTASK_STACKSIZE=512
|
||||
CONFIG_ZOMBIE_KTASK_STACKSIZE=512
|
||||
# CONFIG_KERNEL_TASK_ISOLATION is not set
|
||||
|
||||
#
|
||||
# Memory Management
|
||||
#
|
||||
# CONFIG_KERNEL_MEMBLOCK is not set
|
||||
|
||||
#
|
||||
# Command shell
|
||||
#
|
||||
CONFIG_TOOL_SHELL=y
|
||||
CONFIG_SHELL_TASK_PRIORITY=4
|
||||
CONFIG_SHELL_TASK_STACK_SIZE=2048
|
||||
|
||||
#
|
||||
# User Control
|
||||
#
|
||||
CONFIG_SHELL_DEFAULT_USER="letter"
|
||||
CONFIG_SHELL_DEFAULT_USER_PASSWORD=""
|
||||
CONFIG_SHELL_LOCK_TIMEOUT=10000
|
||||
CONFIG_SHELL_ENTER_CR_AND_LF=y
|
||||
# CONFIG_SHELL_ENTER_CRLF is not set
|
||||
CONFIG_SHELL_ENTER_CR=y
|
||||
CONFIG_SHELL_ENTER_LF=y
|
||||
CONFIG_SHELL_MAX_NUMBER=5
|
||||
CONFIG_SHELL_PARAMETER_MAX_NUMBER=8
|
||||
CONFIG_SHELL_HISTORY_MAX_NUMBER=5
|
||||
CONFIG_SHELL_PRINT_BUFFER=128
|
||||
CONFIG_SHELL_USING_CMD_EXPORT=y
|
||||
# CONFIG_SHELL_HELP_LIST_USER is not set
|
||||
CONFIG_SHELL_HELP_SHOW_PERMISSION=y
|
||||
# CONFIG_SHELL_HELP_LIST_VAR is not set
|
||||
# CONFIG_SHELL_HELP_LIST_KEY is not set
|
||||
#CONFIG_KERNEL_QUEUEMANAGE=y
|
||||
# CONFIG_KERNEL_WORKQUEUE is not set
|
||||
CONFIG_WORKQUEUE_KTASK_STACKSIZE=256
|
||||
CONFIG_WORKQUEUE_KTASK_PRIORITY=2
|
||||
CONFIG_QUEUE_MAX=2
|
||||
CONFIG_KERNEL_WAITQUEUE=y
|
||||
CONFIG_KERNEL_DATAQUEUE=y
|
||||
# CONFIG_KERNEL_CIRCULAR_AREA is not set
|
||||
# CONFIG_KERNEL_AVL_TREE is not set
|
||||
CONFIG_NAME_MAX=32
|
||||
CONFIG_ALIGN_SIZE=8
|
||||
CONFIG_KERNEL_COMPONENTS_INIT=n
|
||||
CONFIG_KERNEL_USER_MAIN=y
|
||||
CONFIG_MAIN_KTASK_STACK_SIZE=2048
|
||||
CONFIG_ENV_INIT_KTASK_STACK_SIZE=2048
|
||||
CONFIG_MAIN_KTASK_PRIORITY=3
|
||||
# CONFIG_USER_TEST is not set
|
||||
# CONFIG_TOOL_TEST_SEM is not set
|
||||
# CONFIG_TOOL_TEST_MUTEX is not set
|
||||
# CONFIG_TOOL_TEST_EVENT is not set
|
||||
# CONFIG_TOOL_TEST_MSG is not set
|
||||
# CONFIG_TOOL_TEST_AVLTREE is not set
|
||||
# CONFIG_TEST_CRICULAR_AREA is not set
|
||||
# CONFIG_TOOL_TEST_MEM is not set
|
||||
# CONFIG_TOOL_TEST_TIMER is not set
|
||||
# CONFIG_TOOL_TEST_IWG is not set
|
||||
# CONFIG_TOOL_TEST_REALTIME is not set
|
||||
# CONFIG_TOOL_TEST_DBG is not set
|
||||
# CONFIG_TOOL_TEST_SCHED is not set
|
||||
# CONFIG_KERNEL_DEBUG is not set
|
||||
#CONFIG_DEBUG_INIT_CONFIG=y
|
||||
#CONFIG_DBG_INIT=1
|
||||
#CONFIG_ARCH_SMP=y
|
||||
#CONFIG_CPUS_NR=2
|
||||
|
||||
#
|
||||
# hash table config
|
||||
#
|
||||
CONFIG_ID_HTABLE_SIZE=4
|
||||
CONFIG_ID_NUM_MAX=16
|
||||
|
||||
#
|
||||
# File system
|
||||
#
|
||||
CONFIG_FS_DFS=n
|
||||
#CONFIG_DFS_USING_WORKDIR=y
|
||||
#CONFIG_FS_DFS_DEVFS=y
|
||||
|
||||
#
|
||||
# Fat filesystem
|
||||
#
|
||||
|
||||
#
|
||||
# IOT-Device File system
|
||||
#
|
||||
|
||||
#
|
||||
# Lwext4 filesystem
|
||||
#
|
||||
|
||||
#
|
||||
# APP Framework
|
||||
#
|
||||
|
||||
#
|
||||
# Perception
|
||||
#
|
||||
# CONFIG_PERCEPTION_SENSORDEVICE is not set
|
||||
|
||||
#
|
||||
# connection
|
||||
#
|
||||
# CONFIG_CONNECTION_AT is not set
|
||||
# CONFIG_CONNECTION_MQTT is not set
|
||||
|
||||
#
|
||||
# medium communication
|
||||
#
|
||||
|
||||
|
||||
#
|
||||
# Intelligence
|
||||
#
|
||||
|
||||
#
|
||||
# Control
|
||||
#
|
||||
|
||||
#
|
||||
# Lib
|
||||
#
|
||||
CONFIG_LIB=y
|
||||
CONFIG_LIB_POSIX=y
|
||||
CONFIG_LIB_NEWLIB=y
|
||||
|
||||
# CONFIG_LITTLEVGL2RTT_USING_DEMO=y
|
||||
|
||||
#
|
||||
# Security
|
||||
#
|
|
@ -0,0 +1,56 @@
|
|||
mainmenu "XiUOS Project Configuration"
|
||||
|
||||
config BSP_DIR
|
||||
string
|
||||
option env="BSP_ROOT"
|
||||
default "."
|
||||
|
||||
config KERNEL_DIR
|
||||
string
|
||||
option env="KERNEL_ROOT"
|
||||
default "../.."
|
||||
|
||||
config BOARD_CORTEX_M3_EVB
|
||||
bool
|
||||
select ARCH_ARM
|
||||
default y
|
||||
|
||||
config KERNEL_CONSOLE_DEVICE_NAME
|
||||
string
|
||||
default "uart0"
|
||||
|
||||
|
||||
source "$KERNEL_DIR/arch/Kconfig"
|
||||
|
||||
menu "cortex-m3 emulator feature"
|
||||
source "$BSP_DIR/third_party_driver/Kconfig"
|
||||
|
||||
menu "config default board resources"
|
||||
menu "config board app name"
|
||||
config BOARD_APP_NAME
|
||||
string "config board app name"
|
||||
default "/XiUOS_cortex-m3-emulator_app.bin"
|
||||
endmenu
|
||||
|
||||
menu "config board service table"
|
||||
config SERVICE_TABLE_ADDRESS
|
||||
hex "board service table address"
|
||||
default 0x2007F0000
|
||||
endmenu
|
||||
|
||||
endmenu
|
||||
|
||||
config __STACKSIZE__
|
||||
int "stack size for interrupt"
|
||||
default 4096
|
||||
|
||||
endmenu
|
||||
|
||||
|
||||
menu "Hardware feature"
|
||||
source "$KERNEL_DIR/resources/Kconfig"
|
||||
endmenu
|
||||
|
||||
source "$KERNEL_DIR/Kconfig"
|
||||
|
||||
|
|
@ -0,0 +1,5 @@
|
|||
SRC_DIR := third_party_driver
|
||||
|
||||
SRC_FILES := board.c connect_uart.c
|
||||
|
||||
include $(KERNEL_ROOT)/compiler.mk
|
|
@ -0,0 +1,187 @@
|
|||
# 从零开始构建矽璓工业物联操作系统:使用ARM架构的cortex-m3 emulator
|
||||
|
||||
# cortex-m3 emulator
|
||||
|
||||
[XiUOS](http://xuos.io/) (X Industrial Ubiquitous Operating System) 矽璓XiUOS是一款面向智慧车间的工业物联网操作系统,主要由一个极简的微型实时操作系统内核和其上的工业物联框架构成,通过高效管理工业物联网设备、支撑工业物联应用,在生产车间内实现智能化的“感知环境、联网传输、知悉识别、控制调整”,促进以工业设备和工业控制系统为核心的人、机、物深度互联,帮助提升生产线的数字化和智能化水平。
|
||||
|
||||
## 1. 简介
|
||||
|
||||
QEMU 是一个通用的开源模拟器和虚拟化工具。目前QEMU已经可以较完整的支持ARM cortex-m3架构。XiUOS同样支持运行在QEMU上
|
||||
|
||||
| 硬件 | 描述 |
|
||||
| -- | -- |
|
||||
|芯片型号| lm3s6965evb |
|
||||
|架构| cortex-m3 |
|
||||
|主频| 50MHz |
|
||||
|片内SRAM| 64KB |
|
||||
| 外设支持 | UART |
|
||||
|
||||
XiUOS板级当前支持使用UART。
|
||||
|
||||
## 2. 开发环境搭建
|
||||
|
||||
### 推荐使用:
|
||||
|
||||
**操作系统:** ubuntu18.04 [https://ubuntu.com/download/desktop](https://ubuntu.com/download/desktop)
|
||||
|
||||
更新`ubuntu 18.04`源的方法:(根据自身情况而定,可以不更改)
|
||||
|
||||
第一步:打开sources.list文件
|
||||
|
||||
```c
|
||||
sudo vim /etc/apt/sources.list
|
||||
```
|
||||
|
||||
第二步:将以下内容复制到sources.list文件
|
||||
|
||||
```c
|
||||
deb http://mirrors.aliyun.com/ubuntu/ bionic main restricted universe multiverse
|
||||
deb http://mirrors.aliyun.com/ubuntu/ bionic-security main restricted universe multiverse
|
||||
deb http://mirrors.aliyun.com/ubuntu/ bionic-updates main restricted universe multiverse
|
||||
deb http://mirrors.aliyun.com/ubuntu/ bionic-proposed main restricted universe multiverse
|
||||
deb http://mirrors.aliyun.com/ubuntu/ bionic-backports main restricted universe multiverse
|
||||
deb-src http://mirrors.aliyun.com/ubuntu/ bionic main restricted universe multiverse
|
||||
deb-src http://mirrors.aliyun.com/ubuntu/ bionic-security main restricted universe multiverse
|
||||
deb-src http://mirrors.aliyun.com/ubuntu/ bionic-updates main restricted universe multiverse
|
||||
deb-src http://mirrors.aliyun.com/ubuntu/ bionic-proposed main restricted universe multiverse
|
||||
deb-src http://mirrors.aliyun.com/ubuntu/ bionic-backports main restricted universe multiverse
|
||||
```
|
||||
|
||||
第三步:更新源和系统软件
|
||||
|
||||
```c
|
||||
sudo apt-get update
|
||||
sudo apt-get upgrade
|
||||
```
|
||||
|
||||
**开发工具推荐使用 VSCode ,VScode下载地址为:** VSCode [https://code.visualstudio.com/](https://code.visualstudio.com/),推荐下载地址为 [http://vscode.cdn.azure.cn/stable/3c4e3df9e89829dce27b7b5c24508306b151f30d/code_1.55.2-1618307277_amd64.deb](http://vscode.cdn.azure.cn/stable/3c4e3df9e89829dce27b7b5c24508306b151f30d/code_1.55.2-1618307277_amd64.deb)
|
||||
|
||||
### 依赖包安装:
|
||||
|
||||
```
|
||||
$ sudo apt install build-essential pkg-config git
|
||||
$ sudo apt install gcc make libncurses5-dev openssl libssl-dev bison flex libelf-dev autoconf libtool gperf libc6-dev
|
||||
```
|
||||
|
||||
**XiUOS操作系统源码下载:** XiUOS [https://forgeplus.trustie.net/projects/xuos/xiuos](https://forgeplus.trustie.net/projects/xuos/xiuos)
|
||||
|
||||
新建一个空文件夹并进入文件夹中,并下载源码,具体命令如下:
|
||||
|
||||
```c
|
||||
mkdir test && cd test
|
||||
git clone https://git.trustie.net/xuos/xiuos.git
|
||||
```
|
||||
|
||||
打开源码文件包可以看到以下目录:
|
||||
| 名称 | 说明 |
|
||||
| -- | -- |
|
||||
| application | 应用代码 |
|
||||
| board | 板级支持包 |
|
||||
| framework | 应用框架 |
|
||||
| fs | 文件系统 |
|
||||
| kernel | 内核源码 |
|
||||
| resources | 驱动文件 |
|
||||
| tool | 系统工具 |
|
||||
|
||||
使用VScode打开代码,具体操作步骤为:在源码文件夹下打开系统终端,输入`code .`即可打开VScode开发环境,如下图所示:
|
||||
|
||||
<div align= "center">
|
||||
<img src = img/vscode.jpg width =1000>
|
||||
</div>
|
||||
|
||||
### 裁减配置工具的下载
|
||||
|
||||
裁减配置工具:
|
||||
|
||||
**工具地址:** kconfig-frontends [https://forgeplus.trustie.net/projects/xuos/kconfig-frontends](https://forgeplus.trustie.net/projects/xuos/kconfig-frontends),下载与安装的具体命令如下:
|
||||
|
||||
```c
|
||||
mkdir kfrontends && cd kfrontends
|
||||
git clone https://git.trustie.net/xuos/kconfig-frontends.git
|
||||
```
|
||||
|
||||
下载源码后按以下步骤执行软件安装:
|
||||
|
||||
```c
|
||||
cd kconfig-frontends
|
||||
./xs_build.sh
|
||||
```
|
||||
|
||||
### 编译工具链:
|
||||
|
||||
ARM: arm-none-eabi(`gcc version 6.3.1`),默认安装到Ubuntu的/usr/bin/arm-none-eabi-,使用如下命令行下载和安装。
|
||||
|
||||
```shell
|
||||
$ sudo apt install gcc-arm-none-eabi
|
||||
```
|
||||
|
||||
## 编译说明
|
||||
|
||||
### 编辑环境:`Ubuntu18.04`
|
||||
|
||||
### 编译工具链:`arm-none-eabi-gcc`
|
||||
使用`VScode`打开工程的方法有多种,本文介绍一种快捷键,在项目目录下将`code .`输入linux系统命令终端即可打开目标项目
|
||||
|
||||
|
||||
编译步骤:
|
||||
|
||||
1.在VScode命令终端中执行以下命令,生成配置文件
|
||||
|
||||
```c
|
||||
make BOARD=cortex-m3-emulator menuconfig
|
||||
```
|
||||
|
||||
2.在menuconfig界面配置需要关闭和开启的功能,按回车键进入下级菜单,按Y键选中需要开启的功能,按N键选中需要关闭的功能,配置结束后保存并退出(本例旨在演示简单的输出例程,所以没有需要配置的选项,双击快捷键ESC退出配置)
|
||||
|
||||

|
||||
|
||||
退出时选择`yes`保存上面所配置的内容,如下图所示:
|
||||
|
||||

|
||||
|
||||
3.继续执行以下命令,进行编译
|
||||
|
||||
```
|
||||
make BOARD=cortex-m3-emulator
|
||||
```
|
||||
|
||||
4.如果编译正确无误,会产生XiUOS_cortex-m3-emulator.elf、XiUOS_cortex-m3-emulator.bin文件。
|
||||
|
||||
## 3. 运行
|
||||
|
||||
### 3.1 安装QEMU
|
||||
|
||||
```
|
||||
sudo apt install qemu-system-arm
|
||||
```
|
||||
|
||||
### 3.2 运行结果
|
||||
|
||||
通过以下命令启动QEMU并加载XiUOS ELF文件
|
||||
|
||||
```
|
||||
qemu-system-arm -machine lm3s6965evb -nographic -kernel build/XiUOS_cortex-m3-emulator.elf
|
||||
```
|
||||
|
||||
QEMU运行起来后将会在终端上看到信息打印输出
|
||||
|
||||

|
||||
|
||||
### 3.3 调试
|
||||
|
||||
通过QEMU可以方便的对XiUOS进行调试,首先安装gdb调试工具
|
||||
```
|
||||
sudo apt install gdb-multiarch
|
||||
```
|
||||
|
||||
并通过以下命令启动QEMU
|
||||
|
||||
```
|
||||
qemu-system-arm -machine lm3s6965evb -nographic -kernel build/XiUOS_cortex-m3-emulator.elf -s -S
|
||||
```
|
||||
|
||||
然后要重新开启另一个linux系统终端一个终端,执行`riscv-none-embed-gdb`命令
|
||||
|
||||
```
|
||||
gdb-multiarch build/XiUOS_cortex-m3-emulator.elf -ex "target remote localhost:1234"
|
||||
```
|
|
@ -0,0 +1,40 @@
|
|||
/*
|
||||
* Copyright (c) 2020 AIIT XUOS Lab
|
||||
* XiUOS is licensed under Mulan PSL v2.
|
||||
* You can use this software according to the terms and conditions of the Mulan PSL v2.
|
||||
* You may obtain a copy of Mulan PSL v2 at:
|
||||
* http://license.coscl.org.cn/MulanPSL2
|
||||
* THIS SOFTWARE IS PROVIDED ON AN "AS IS" BASIS, WITHOUT WARRANTIES OF ANY KIND,
|
||||
* EITHER EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO NON-INFRINGEMENT,
|
||||
* MERCHANTABILITY OR FIT FOR A PARTICULAR PURPOSE.
|
||||
* See the Mulan PSL v2 for more details.
|
||||
*/
|
||||
|
||||
/**
|
||||
* @file board.c
|
||||
* @brief support cortex-m3-emulator init configure and start-up
|
||||
* @version 1.0
|
||||
* @author AIIT XUOS Lab
|
||||
* @date 2021-05-13
|
||||
*/
|
||||
|
||||
|
||||
#include <board.h>
|
||||
#include <xiuos.h>
|
||||
#include <device.h>
|
||||
#include <arch_interrupt.h>
|
||||
|
||||
void SysTick_Handler(int irqn, void *arg)
|
||||
{
|
||||
TickAndTaskTimesliceUpdate();
|
||||
}
|
||||
DECLARE_HW_IRQ(SYSTICK_IRQN, SysTick_Handler, NONE);
|
||||
|
||||
void InitBoardHardware()
|
||||
{
|
||||
extern int InitHwUart(void);
|
||||
InitHwUart();
|
||||
InstallConsole(SERIAL_BUS_NAME_1, SERIAL_DRV_NAME_1, SERIAL_DEVICE_NAME_1);
|
||||
InitBoardMemory((void*)LM3S_SRAM_START, (void*)LM3S_SRAM_END);
|
||||
|
||||
}
|
|
@ -0,0 +1,38 @@
|
|||
/*
|
||||
* Copyright (c) 2020 AIIT XUOS Lab
|
||||
* XiUOS is licensed under Mulan PSL v2.
|
||||
* You can use this software according to the terms and conditions of the Mulan PSL v2.
|
||||
* You may obtain a copy of Mulan PSL v2 at:
|
||||
* http://license.coscl.org.cn/MulanPSL2
|
||||
* THIS SOFTWARE IS PROVIDED ON AN "AS IS" BASIS, WITHOUT WARRANTIES OF ANY KIND,
|
||||
* EITHER EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO NON-INFRINGEMENT,
|
||||
* MERCHANTABILITY OR FIT FOR A PARTICULAR PURPOSE.
|
||||
* See the Mulan PSL v2 for more details.
|
||||
*/
|
||||
|
||||
/**
|
||||
* @file board.h
|
||||
* @brief define cortex-m3-emulator init configure and start-up function
|
||||
* @version 1.0
|
||||
* @author AIIT XUOS Lab
|
||||
* @date 2021-05-13
|
||||
*/
|
||||
|
||||
#ifndef __BOARD_H__
|
||||
#define __BOARD_H__
|
||||
|
||||
|
||||
extern void *__bss_end;
|
||||
extern void *_heap_end;
|
||||
#define MEM_OFFSET 0x20002000
|
||||
#define LM3S_SRAM_START ( ( ((unsigned long)(&__bss_end)) > MEM_OFFSET)? (unsigned long)(&__bss_end):(MEM_OFFSET) )
|
||||
#define LM3S_SRAM_END ( &_heap_end )
|
||||
|
||||
#define BSP_USING_UART1
|
||||
#define SERIAL_BUS_NAME_1 "uart0"
|
||||
#define SERIAL_DRV_NAME_1 "uart0_drv"
|
||||
#define SERIAL_DEVICE_NAME_1 "uart0_dev0"
|
||||
|
||||
|
||||
|
||||
#endif
|
|
@ -0,0 +1,14 @@
|
|||
export CROSS_COMPILE ?=/usr/bin/arm-none-eabi-
|
||||
|
||||
export CFLAGS := -mcpu=cortex-m3 -mthumb -ffunction-sections -fdata-sections -Dgcc -O0 -gdwarf-2 -g -fgnu89-inline -Wa,-mimplicit-it=thumb
|
||||
export AFLAGS := -c -mcpu=cortex-m3 -mthumb -ffunction-sections -fdata-sections -x assembler-with-cpp -Wa,-mimplicit-it=thumb -gdwarf-2
|
||||
export LFLAGS := -mcpu=cortex-m3 -mthumb -ffunction-sections -fdata-sections -Wl,--gc-sections,-Map=XiUOS_cortex-m3-emulator.map,-cref,-u,Reset_Handler -T $(BSP_ROOT)/link.lds
|
||||
export CXXFLAGS := -mcpu=cortex-m3 -mthumb -ffunction-sections -fdata-sections -Dgcc -O0 -gdwarf-2 -g
|
||||
|
||||
export APPLFLAGS := -mcpu=cortex-m3 -mthumb -ffunction-sections -fdata-sections -Wl,--gc-sections,-Map=XiUOS_app.map,-cref,-u, -T $(BSP_ROOT)/link_userspace.lds
|
||||
|
||||
|
||||
export DEFINES := -DHAVE_CCONFIG_H
|
||||
|
||||
export ARCH = arm
|
||||
export MCU = cortex-m3
|
|
@ -0,0 +1,351 @@
|
|||
/*
|
||||
* Copyright (c) 2020 AIIT XUOS Lab
|
||||
* XiUOS is licensed under Mulan PSL v2.
|
||||
* You can use this software according to the terms and conditions of the Mulan PSL v2.
|
||||
* You may obtain a copy of Mulan PSL v2 at:
|
||||
* http://license.coscl.org.cn/MulanPSL2
|
||||
* THIS SOFTWARE IS PROVIDED ON AN "AS IS" BASIS, WITHOUT WARRANTIES OF ANY KIND,
|
||||
* EITHER EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO NON-INFRINGEMENT,
|
||||
* MERCHANTABILITY OR FIT FOR A PARTICULAR PURPOSE.
|
||||
* See the Mulan PSL v2 for more details.
|
||||
*/
|
||||
|
||||
/**
|
||||
* @file connect_uart.c
|
||||
* @brief support cortex_m3_emulator board uart function and register to bus framework
|
||||
* @version 1.0
|
||||
* @author AIIT XUOS Lab
|
||||
* @date 2021-05-10
|
||||
*/
|
||||
|
||||
#include <board.h>
|
||||
#include <xiuos.h>
|
||||
#include <device.h>
|
||||
#include <inc/hw_types.h>
|
||||
#include <driverlib/gpio.h>
|
||||
#include <driverlib/interrupt.h>
|
||||
#include <driverlib/sysctl.h>
|
||||
#include <driverlib/uart.h>
|
||||
#include <inc/hw_ints.h>
|
||||
#include <inc/hw_memmap.h>
|
||||
#include <inc/hw_uart.h>
|
||||
|
||||
#ifdef BSP_USING_UART1
|
||||
static struct SerialBus serial_bus_1;
|
||||
static struct SerialDriver serial_driver_1;
|
||||
static struct SerialHardwareDevice serial_device_1;
|
||||
#endif
|
||||
#ifdef BSP_USING_UART2
|
||||
static struct SerialBus serial_bus_2;
|
||||
static struct SerialDriver serial_driver_2;
|
||||
static struct SerialHardwareDevice serial_device_2;
|
||||
#endif
|
||||
|
||||
static void SerialCfgParamCheck(struct SerialCfgParam *serial_cfg_default, struct SerialCfgParam *serial_cfg_new)
|
||||
{
|
||||
struct SerialDataCfg *data_cfg_default = &serial_cfg_default->data_cfg;
|
||||
struct SerialDataCfg *data_cfg_new = &serial_cfg_new->data_cfg;
|
||||
|
||||
if ((data_cfg_default->serial_baud_rate != data_cfg_new->serial_baud_rate) && (data_cfg_new->serial_baud_rate)) {
|
||||
data_cfg_default->serial_baud_rate = data_cfg_new->serial_baud_rate;
|
||||
}
|
||||
|
||||
if ((data_cfg_default->serial_bit_order != data_cfg_new->serial_bit_order) && (data_cfg_new->serial_bit_order)) {
|
||||
data_cfg_default->serial_bit_order = data_cfg_new->serial_bit_order;
|
||||
}
|
||||
|
||||
if ((data_cfg_default->serial_buffer_size != data_cfg_new->serial_buffer_size) && (data_cfg_new->serial_buffer_size)) {
|
||||
data_cfg_default->serial_buffer_size = data_cfg_new->serial_buffer_size;
|
||||
}
|
||||
|
||||
if ((data_cfg_default->serial_data_bits != data_cfg_new->serial_data_bits) && (data_cfg_new->serial_data_bits)) {
|
||||
data_cfg_default->serial_data_bits = data_cfg_new->serial_data_bits;
|
||||
}
|
||||
|
||||
if ((data_cfg_default->serial_invert_mode != data_cfg_new->serial_invert_mode) && (data_cfg_new->serial_invert_mode)) {
|
||||
data_cfg_default->serial_invert_mode = data_cfg_new->serial_invert_mode;
|
||||
}
|
||||
|
||||
if ((data_cfg_default->serial_parity_mode != data_cfg_new->serial_parity_mode) && (data_cfg_new->serial_parity_mode)) {
|
||||
data_cfg_default->serial_parity_mode = data_cfg_new->serial_parity_mode;
|
||||
}
|
||||
|
||||
if ((data_cfg_default->serial_stop_bits != data_cfg_new->serial_stop_bits) && (data_cfg_new->serial_stop_bits)) {
|
||||
data_cfg_default->serial_stop_bits = data_cfg_new->serial_stop_bits;
|
||||
}
|
||||
}
|
||||
|
||||
static void UartHandler(struct SerialBus *serial_bus, struct SerialDriver *serial_drv)
|
||||
{
|
||||
struct SerialHardwareDevice *serial_dev = (struct SerialHardwareDevice *)serial_bus->bus.owner_haldev;
|
||||
struct SerialCfgParam *serial_cfg = (struct SerialCfgParam *)serial_drv->private_data;
|
||||
|
||||
uint32 status;
|
||||
|
||||
status = UARTIntStatus(serial_cfg->hw_cfg.serial_register_base, RET_TRUE);
|
||||
|
||||
/* clear interrupt status */
|
||||
UARTIntClear(serial_cfg->hw_cfg.serial_register_base, status);
|
||||
|
||||
while (UARTCharsAvail(serial_cfg->hw_cfg.serial_register_base)) {
|
||||
SerialSetIsr(serial_dev, SERIAL_EVENT_RX_IND);
|
||||
}
|
||||
}
|
||||
|
||||
#ifdef BSP_USING_UART1
|
||||
void UartIsr1(int vector, void *param)
|
||||
{
|
||||
/* get serial bus 1 */
|
||||
UartHandler(&serial_bus_1, &serial_driver_1);
|
||||
}
|
||||
DECLARE_HW_IRQ(UART1_IRQn, UartIsr1, NONE);
|
||||
#endif
|
||||
|
||||
#ifdef BSP_USING_UART2
|
||||
void UartIsr2(int irqno)
|
||||
{
|
||||
/* get serial bus 2 */
|
||||
UartHandler(&serial_bus_2, &serial_driver_2);
|
||||
}
|
||||
#endif
|
||||
|
||||
static uint32 SerialInit(struct SerialDriver *serial_drv, struct BusConfigureInfo *configure_info)
|
||||
{
|
||||
NULL_PARAM_CHECK(serial_drv);
|
||||
|
||||
return EOK;
|
||||
}
|
||||
|
||||
static uint32 SerialConfigure(struct SerialDriver *serial_drv, int serial_operation_cmd)
|
||||
{
|
||||
NULL_PARAM_CHECK(serial_drv);
|
||||
|
||||
struct SerialCfgParam *serial_cfg = (struct SerialCfgParam *)serial_drv->private_data;
|
||||
struct HardwareDev *dev = serial_drv->driver.owner_bus->owner_haldev;
|
||||
struct SerialHardwareDevice *serial_dev = (struct SerialHardwareDevice *)dev;
|
||||
struct SerialDevParam *serial_dev_param = (struct SerialDevParam *)serial_dev->haldev.private_data;
|
||||
|
||||
if (OPER_CLR_INT == serial_operation_cmd) {
|
||||
if (SIGN_OPER_INT_RX & serial_dev_param->serial_work_mode) {
|
||||
/* disable UART rx interrupt */
|
||||
UARTIntDisable(serial_cfg->hw_cfg.serial_register_base, UART_INT_RX | UART_INT_RT);
|
||||
}
|
||||
} else if (OPER_SET_INT == serial_operation_cmd) {
|
||||
/* enable interrupt */
|
||||
if (UART0_BASE == serial_cfg->hw_cfg.serial_register_base)
|
||||
IntEnable(INT_UART0);
|
||||
else if (UART1_BASE == serial_cfg->hw_cfg.serial_register_base)
|
||||
IntEnable(INT_UART1);
|
||||
|
||||
UARTIntEnable(serial_cfg->hw_cfg.serial_register_base, UART_INT_RX | UART_INT_RT);
|
||||
}
|
||||
|
||||
return EOK;
|
||||
}
|
||||
|
||||
static uint32 SerialDrvConfigure(void *drv, struct BusConfigureInfo *configure_info)
|
||||
{
|
||||
NULL_PARAM_CHECK(drv);
|
||||
NULL_PARAM_CHECK(configure_info);
|
||||
|
||||
x_err_t ret = EOK;
|
||||
int serial_operation_cmd;
|
||||
struct SerialDriver *serial_drv = (struct SerialDriver *)drv;
|
||||
|
||||
switch (configure_info->configure_cmd)
|
||||
{
|
||||
case OPE_INT:
|
||||
ret = SerialInit(serial_drv, configure_info);
|
||||
break;
|
||||
case OPE_CFG:
|
||||
serial_operation_cmd = *(int *)configure_info->private_data;
|
||||
ret = SerialConfigure(serial_drv, serial_operation_cmd);
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
static int SerialPutChar(struct SerialHardwareDevice *serial_dev, char c)
|
||||
{
|
||||
struct SerialCfgParam *serial_cfg = (struct SerialCfgParam *)serial_dev->private_data;
|
||||
while (UARTCharPutNonBlocking(serial_cfg->hw_cfg.serial_register_base, c) == RET_FALSE);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
static int SerialGetChar(struct SerialHardwareDevice *serial_dev)
|
||||
{
|
||||
struct SerialCfgParam *serial_cfg = (struct SerialCfgParam *)serial_dev->private_data;
|
||||
long val = UARTCharGetNonBlocking(serial_cfg->hw_cfg.serial_register_base);
|
||||
if (val > 0)
|
||||
return (int)val;
|
||||
else
|
||||
return -1;
|
||||
}
|
||||
|
||||
static const struct SerialDataCfg data_cfg_init =
|
||||
{
|
||||
.serial_baud_rate = BAUD_RATE_115200,
|
||||
.serial_data_bits = DATA_BITS_8,
|
||||
.serial_stop_bits = STOP_BITS_1,
|
||||
.serial_parity_mode = PARITY_NONE,
|
||||
.serial_bit_order = BIT_ORDER_LSB,
|
||||
.serial_invert_mode = NRZ_NORMAL,
|
||||
.serial_buffer_size = SERIAL_RB_BUFSZ,
|
||||
};
|
||||
|
||||
/*manage the serial device operations*/
|
||||
static const struct SerialDrvDone drv_done =
|
||||
{
|
||||
.init = SerialInit,
|
||||
.configure = SerialConfigure,
|
||||
};
|
||||
|
||||
/*manage the serial device hal operations*/
|
||||
static struct SerialHwDevDone hwdev_done =
|
||||
{
|
||||
.put_char = SerialPutChar,
|
||||
.get_char = SerialGetChar,
|
||||
};
|
||||
|
||||
static int BoardSerialBusInit(struct SerialBus *serial_bus, struct SerialDriver *serial_driver, const char *bus_name, const char *drv_name)
|
||||
{
|
||||
x_err_t ret = EOK;
|
||||
|
||||
/*Init the serial bus */
|
||||
ret = SerialBusInit(serial_bus, bus_name);
|
||||
if (EOK != ret) {
|
||||
KPrintf("InitHwUart SerialBusInit error %d\n", ret);
|
||||
return ERROR;
|
||||
}
|
||||
|
||||
/*Init the serial driver*/
|
||||
ret = SerialDriverInit(serial_driver, drv_name);
|
||||
if (EOK != ret) {
|
||||
KPrintf("InitHwUart SerialDriverInit error %d\n", ret);
|
||||
return ERROR;
|
||||
}
|
||||
|
||||
/*Attach the serial driver to the serial bus*/
|
||||
ret = SerialDriverAttachToBus(drv_name, bus_name);
|
||||
if (EOK != ret) {
|
||||
KPrintf("InitHwUart SerialDriverAttachToBus error %d\n", ret);
|
||||
return ERROR;
|
||||
}
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
/*Attach the serial device to the serial bus*/
|
||||
static int BoardSerialDevBend(struct SerialHardwareDevice *serial_device, void *serial_param, const char *bus_name, const char *dev_name)
|
||||
{
|
||||
x_err_t ret = EOK;
|
||||
|
||||
ret = SerialDeviceRegister(serial_device, serial_param, dev_name);
|
||||
if (EOK != ret) {
|
||||
KPrintf("InitHwUart SerialDeviceInit device %s error %d\n", dev_name, ret);
|
||||
return ERROR;
|
||||
}
|
||||
|
||||
ret = SerialDeviceAttachToBus(dev_name, bus_name);
|
||||
if (EOK != ret) {
|
||||
KPrintf("InitHwUart SerialDeviceAttachToBus device %s error %d\n", dev_name, ret);
|
||||
return ERROR;
|
||||
}
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
int InitHwUart(void)
|
||||
{
|
||||
x_err_t ret = EOK;
|
||||
|
||||
#ifdef BSP_USING_UART1
|
||||
memset(&serial_bus_1, 0, sizeof(struct SerialBus));
|
||||
memset(&serial_driver_1, 0, sizeof(struct SerialDriver));
|
||||
memset(&serial_device_1, 0, sizeof(struct SerialHardwareDevice));
|
||||
|
||||
static struct SerialCfgParam serial_cfg_1;
|
||||
memset(&serial_cfg_1, 0, sizeof(struct SerialCfgParam));
|
||||
|
||||
static struct SerialDevParam serial_dev_param_1;
|
||||
memset(&serial_dev_param_1, 0, sizeof(struct SerialDevParam));
|
||||
|
||||
serial_driver_1.drv_done = &drv_done;
|
||||
serial_driver_1.configure = &SerialDrvConfigure;
|
||||
serial_device_1.hwdev_done = &hwdev_done;
|
||||
|
||||
serial_cfg_1.data_cfg = data_cfg_init;
|
||||
|
||||
serial_cfg_1.hw_cfg.serial_register_base = UART0_BASE;
|
||||
serial_driver_1.private_data = (void *)&serial_cfg_1;
|
||||
|
||||
serial_dev_param_1.serial_work_mode = SIGN_OPER_INT_RX;
|
||||
serial_device_1.haldev.private_data = (void *)&serial_dev_param_1;
|
||||
|
||||
/* enable UART0 clock */
|
||||
SysCtlPeripheralEnable(SYSCTL_PERIPH_UART0);
|
||||
SysCtlPeripheralEnable(SYSCTL_PERIPH_GPIOA);
|
||||
|
||||
/* set UART0 pinmux */
|
||||
GPIOPinTypeUART(GPIO_PORTA_BASE, GPIO_PIN_0 | GPIO_PIN_1);
|
||||
|
||||
/* Configure the UART for 115,200, 8-N-1 operation. */
|
||||
UARTConfigSetExpClk(UART0_BASE, SysCtlClockGet(), serial_cfg_1.data_cfg.serial_baud_rate,
|
||||
(UART_CONFIG_WLEN_8 | UART_CONFIG_STOP_ONE |
|
||||
UART_CONFIG_PAR_NONE));
|
||||
|
||||
ret = BoardSerialBusInit(&serial_bus_1, &serial_driver_1, SERIAL_BUS_NAME_1, SERIAL_DRV_NAME_1);
|
||||
if (EOK != ret) {
|
||||
KPrintf("InitHwUart uarths error ret %u\n", ret);
|
||||
return ERROR;
|
||||
}
|
||||
|
||||
ret = BoardSerialDevBend(&serial_device_1, (void *)&serial_cfg_1, SERIAL_BUS_NAME_1, SERIAL_DEVICE_NAME_1);
|
||||
if (EOK != ret) {
|
||||
KPrintf("InitHwUart uarths error ret %u\n", ret);
|
||||
return ERROR;
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef BSP_USING_UART2
|
||||
memset(&serial_bus_2, 0, sizeof(struct SerialBus));
|
||||
memset(&serial_driver_2, 0, sizeof(struct SerialDriver));
|
||||
memset(&serial_device_2, 0, sizeof(struct SerialHardwareDevice));
|
||||
|
||||
static struct SerialCfgParam serial_cfg_2;
|
||||
memset(&serial_cfg_2, 0, sizeof(struct SerialCfgParam));
|
||||
|
||||
static struct SerialDevParam serial_dev_param_2;
|
||||
memset(&serial_dev_param_2, 0, sizeof(struct SerialDevParam));
|
||||
|
||||
serial_driver_2.drv_done = &drv_done;
|
||||
serial_driver_2.configure = &SerialDrvConfigure;
|
||||
serial_device_2.hwdev_done = &hwdev_done;
|
||||
|
||||
serial_cfg_2.data_cfg = data_cfg_init;
|
||||
|
||||
serial_cfg_2.hw_cfg.serial_register_base = UART1_BASE;
|
||||
serial_driver_2.private_data = (void *)&serial_cfg_2;
|
||||
|
||||
serial_dev_param_2.serial_work_mode = SIGN_OPER_INT_RX;
|
||||
serial_device_2.haldev.private_data = (void *)&serial_dev_param_2;
|
||||
|
||||
ret = BoardSerialBusInit(&serial_bus_2, &serial_driver_2, SERIAL_BUS_NAME_2, SERIAL_DRV_NAME_2);
|
||||
if (EOK != ret) {
|
||||
KPrintf("InitHwUart uarths error ret %u\n", ret);
|
||||
return ERROR;
|
||||
}
|
||||
|
||||
ret = BoardSerialDevBend(&serial_device_2, (void *)&serial_cfg_2, SERIAL_BUS_NAME_2, SERIAL_DEVICE_NAME_2);
|
||||
if (EOK != ret) {
|
||||
KPrintf("InitHwUart uarths error ret %u\n", ret);
|
||||
return ERROR;
|
||||
}
|
||||
#endif
|
||||
|
||||
return ret;
|
||||
}
|
Binary file not shown.
After Width: | Height: | Size: 41 KiB |
Binary file not shown.
After Width: | Height: | Size: 21 KiB |
Binary file not shown.
After Width: | Height: | Size: 451 KiB |
Binary file not shown.
After Width: | Height: | Size: 56 KiB |
|
@ -0,0 +1,97 @@
|
|||
/*
|
||||
* Copyright (c) 2020 AIIT XUOS Lab
|
||||
* XiUOS is licensed under Mulan PSL v2.
|
||||
* You can use this software according to the terms and conditions of the Mulan PSL v2.
|
||||
* You may obtain a copy of Mulan PSL v2 at:
|
||||
* http://license.coscl.org.cn/MulanPSL2
|
||||
* THIS SOFTWARE IS PROVIDED ON AN "AS IS" BASIS, WITHOUT WARRANTIES OF ANY KIND,
|
||||
* EITHER EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO NON-INFRINGEMENT,
|
||||
* MERCHANTABILITY OR FIT FOR A PARTICULAR PURPOSE.
|
||||
* See the Mulan PSL v2 for more details.
|
||||
*/
|
||||
|
||||
MEMORY
|
||||
{
|
||||
flash (rx) : ORIGIN = 0x00000000, LENGTH = 256K
|
||||
sram (rwx) : ORIGIN = 0x20000000, LENGTH = 64K
|
||||
}
|
||||
OUTPUT_ARCH(arm)
|
||||
|
||||
__SYSTEM_STACKSIZE__ = 0x1000;
|
||||
|
||||
ENTRY(Reset_Handler)
|
||||
SECTIONS
|
||||
{
|
||||
.text :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
KEEP(*(.isr_vector)) /* Startup code */
|
||||
. = ALIGN(4);
|
||||
*(.text .text.*)
|
||||
*(.rodata .rodata*) /* read-only data (constants) */
|
||||
*(.glue_7)
|
||||
*(.glue_7t)
|
||||
|
||||
/* section information for shell */
|
||||
. = ALIGN(4);
|
||||
_shell_command_start = .;
|
||||
KEEP (*(shellCommand))
|
||||
_shell_command_end = .;
|
||||
. = ALIGN(4);
|
||||
|
||||
__isrtbl_idx_start = .;
|
||||
KEEP(*(.isrtbl.idx))
|
||||
__isrtbl_start = .;
|
||||
KEEP(*(.isrtbl))
|
||||
__isrtbl_end = .;
|
||||
. = ALIGN(4);
|
||||
|
||||
PROVIDE(g_service_table_start = ABSOLUTE(.));
|
||||
KEEP(*(.g_service_table))
|
||||
PROVIDE(g_service_table_end = ABSOLUTE(.));
|
||||
|
||||
PROVIDE(_etext = ABSOLUTE(.));
|
||||
|
||||
_etext = .;
|
||||
} > flash = 0
|
||||
|
||||
__exidx_start = .;
|
||||
.ARM.exidx :
|
||||
{
|
||||
*(.ARM.exidx* .gnu.linkonce.armexidx.*)
|
||||
_sidata = .;
|
||||
} > flash
|
||||
__exidx_end = .;
|
||||
|
||||
.data : AT (_sidata)
|
||||
{
|
||||
. = ALIGN(4);
|
||||
_sdata = . ;
|
||||
|
||||
*(.data)
|
||||
*(.data.*)
|
||||
. = ALIGN(4);
|
||||
_edata = . ;
|
||||
} >sram
|
||||
|
||||
__bss_start = .;
|
||||
.bss :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
_sbss = .;
|
||||
*(.bss)
|
||||
*(COMMON)
|
||||
. = ALIGN(4);
|
||||
_ebss = . ;
|
||||
} > sram
|
||||
__bss_end = .;
|
||||
_end = .;
|
||||
|
||||
.stack ORIGIN(sram) + LENGTH(sram) - __SYSTEM_STACKSIZE__ :
|
||||
{
|
||||
PROVIDE( _heap_end = . );
|
||||
. = __SYSTEM_STACKSIZE__;
|
||||
PROVIDE( _sp = . );
|
||||
} >sram
|
||||
|
||||
}
|
|
@ -0,0 +1,3 @@
|
|||
SRC_DIR := driverlib
|
||||
|
||||
include $(KERNEL_ROOT)/compiler.mk
|
|
@ -0,0 +1,3 @@
|
|||
SRC_FILES := gpio.c interrupt.c sysctl.c uart.c
|
||||
|
||||
include $(KERNEL_ROOT)/compiler.mk
|
|
@ -0,0 +1,75 @@
|
|||
//*****************************************************************************
|
||||
//
|
||||
// cpu.h - Prototypes for the CPU instruction wrapper functions.
|
||||
//
|
||||
// Copyright (c) 2006-2013 Texas Instruments Incorporated. All rights reserved.
|
||||
// Software License Agreement
|
||||
//
|
||||
// Redistribution and use in source and binary forms, with or without
|
||||
// modification, are permitted provided that the following conditions
|
||||
// are met:
|
||||
//
|
||||
// Redistributions of source code must retain the above copyright
|
||||
// notice, this list of conditions and the following disclaimer.
|
||||
//
|
||||
// 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.
|
||||
//
|
||||
// Neither the name of Texas Instruments Incorporated 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
|
||||
// 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.
|
||||
//
|
||||
// This is part of revision 10636 of the Stellaris Peripheral Driver Library.
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
#ifndef __CPU_H__
|
||||
#define __CPU_H__
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// If building with a C++ compiler, make all of the definitions in this header
|
||||
// have a C binding.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#ifdef __cplusplus
|
||||
extern "C"
|
||||
{
|
||||
#endif
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Prototypes.
|
||||
//
|
||||
//*****************************************************************************
|
||||
extern unsigned long CPUcpsid(void);
|
||||
extern unsigned long CPUcpsie(void);
|
||||
extern unsigned long CPUprimask(void);
|
||||
extern void CPUwfi(void);
|
||||
extern unsigned long CPUbasepriGet(void);
|
||||
extern void CPUbasepriSet(unsigned long ulNewBasepri);
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Mark the end of the C bindings section for C++ compilers.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif // __CPU_H__
|
|
@ -0,0 +1,68 @@
|
|||
//*****************************************************************************
|
||||
//
|
||||
// debug.h - Macros for assisting debug of the driver library.
|
||||
//
|
||||
// Copyright (c) 2006-2013 Texas Instruments Incorporated. All rights reserved.
|
||||
// Software License Agreement
|
||||
//
|
||||
// Redistribution and use in source and binary forms, with or without
|
||||
// modification, are permitted provided that the following conditions
|
||||
// are met:
|
||||
//
|
||||
// Redistributions of source code must retain the above copyright
|
||||
// notice, this list of conditions and the following disclaimer.
|
||||
//
|
||||
// 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.
|
||||
//
|
||||
// Neither the name of Texas Instruments Incorporated 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
|
||||
// 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.
|
||||
//
|
||||
// This is part of revision 10636 of the Stellaris Peripheral Driver Library.
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
#ifndef __DEBUG_H__
|
||||
#define __DEBUG_H__
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Prototype for the function that is called when an invalid argument is passed
|
||||
// to an API. This is only used when doing a DEBUG build.
|
||||
//
|
||||
//*****************************************************************************
|
||||
extern void __error__(char *pcFilename, unsigned long ulLine);
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The ASSERT macro, which does the actual assertion checking. Typically, this
|
||||
// will be for procedure arguments.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#ifdef DEBUG
|
||||
#define ASSERT(expr) { \
|
||||
if(!(expr)) \
|
||||
{ \
|
||||
__error__(__FILE__, __LINE__); \
|
||||
} \
|
||||
}
|
||||
#else
|
||||
#define ASSERT(expr)
|
||||
#endif
|
||||
|
||||
#endif // __DEBUG_H__
|
File diff suppressed because it is too large
Load Diff
|
@ -0,0 +1,197 @@
|
|||
//*****************************************************************************
|
||||
//
|
||||
// gpio.h - Defines and Macros for GPIO API.
|
||||
//
|
||||
// Copyright (c) 2005-2013 Texas Instruments Incorporated. All rights reserved.
|
||||
// Software License Agreement
|
||||
//
|
||||
// Redistribution and use in source and binary forms, with or without
|
||||
// modification, are permitted provided that the following conditions
|
||||
// are met:
|
||||
//
|
||||
// Redistributions of source code must retain the above copyright
|
||||
// notice, this list of conditions and the following disclaimer.
|
||||
//
|
||||
// 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.
|
||||
//
|
||||
// Neither the name of Texas Instruments Incorporated 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
|
||||
// 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.
|
||||
//
|
||||
// This is part of revision 10636 of the Stellaris Peripheral Driver Library.
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
#ifndef __GPIO_H__
|
||||
#define __GPIO_H__
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// If building with a C++ compiler, make all of the definitions in this header
|
||||
// have a C binding.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#ifdef __cplusplus
|
||||
extern "C"
|
||||
{
|
||||
#endif
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following values define the bit field for the ucPins argument to several
|
||||
// of the APIs.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define GPIO_PIN_0 0x00000001 // GPIO pin 0
|
||||
#define GPIO_PIN_1 0x00000002 // GPIO pin 1
|
||||
#define GPIO_PIN_2 0x00000004 // GPIO pin 2
|
||||
#define GPIO_PIN_3 0x00000008 // GPIO pin 3
|
||||
#define GPIO_PIN_4 0x00000010 // GPIO pin 4
|
||||
#define GPIO_PIN_5 0x00000020 // GPIO pin 5
|
||||
#define GPIO_PIN_6 0x00000040 // GPIO pin 6
|
||||
#define GPIO_PIN_7 0x00000080 // GPIO pin 7
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Values that can be passed to GPIODirModeSet as the ulPinIO parameter, and
|
||||
// returned from GPIODirModeGet.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define GPIO_DIR_MODE_IN 0x00000000 // Pin is a GPIO input
|
||||
#define GPIO_DIR_MODE_OUT 0x00000001 // Pin is a GPIO output
|
||||
#define GPIO_DIR_MODE_HW 0x00000002 // Pin is a peripheral function
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Values that can be passed to GPIOIntTypeSet as the ulIntType parameter, and
|
||||
// returned from GPIOIntTypeGet.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define GPIO_FALLING_EDGE 0x00000000 // Interrupt on falling edge
|
||||
#define GPIO_RISING_EDGE 0x00000004 // Interrupt on rising edge
|
||||
#define GPIO_BOTH_EDGES 0x00000001 // Interrupt on both edges
|
||||
#define GPIO_LOW_LEVEL 0x00000002 // Interrupt on low level
|
||||
#define GPIO_HIGH_LEVEL 0x00000006 // Interrupt on high level
|
||||
#define GPIO_DISCRETE_INT 0x00010000 // Interrupt for individual pins
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Values that can be passed to GPIOPadConfigSet as the ulStrength parameter,
|
||||
// and returned by GPIOPadConfigGet in the *pulStrength parameter.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define GPIO_STRENGTH_2MA 0x00000001 // 2mA drive strength
|
||||
#define GPIO_STRENGTH_4MA 0x00000002 // 4mA drive strength
|
||||
#define GPIO_STRENGTH_8MA 0x00000004 // 8mA drive strength
|
||||
#define GPIO_STRENGTH_8MA_SC 0x0000000C // 8mA drive with slew rate control
|
||||
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Values that can be passed to GPIOPadConfigSet as the ulPadType parameter,
|
||||
// and returned by GPIOPadConfigGet in the *pulPadType parameter.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define GPIO_PIN_TYPE_STD 0x00000008 // Push-pull
|
||||
#define GPIO_PIN_TYPE_STD_WPU 0x0000000A // Push-pull with weak pull-up
|
||||
#define GPIO_PIN_TYPE_STD_WPD 0x0000000C // Push-pull with weak pull-down
|
||||
#define GPIO_PIN_TYPE_OD 0x00000009 // Open-drain
|
||||
#define GPIO_PIN_TYPE_ANALOG 0x00000000 // Analog comparator
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Prototypes for the APIs.
|
||||
//
|
||||
//*****************************************************************************
|
||||
extern void GPIODirModeSet(unsigned long ulPort, unsigned char ucPins,
|
||||
unsigned long ulPinIO);
|
||||
extern unsigned long GPIODirModeGet(unsigned long ulPort, unsigned char ucPin);
|
||||
extern void GPIOIntTypeSet(unsigned long ulPort, unsigned char ucPins,
|
||||
unsigned long ulIntType);
|
||||
extern unsigned long GPIOIntTypeGet(unsigned long ulPort, unsigned char ucPin);
|
||||
extern void GPIOPadConfigSet(unsigned long ulPort, unsigned char ucPins,
|
||||
unsigned long ulStrength,
|
||||
unsigned long ulPadType);
|
||||
extern void GPIOPadConfigGet(unsigned long ulPort, unsigned char ucPin,
|
||||
unsigned long *pulStrength,
|
||||
unsigned long *pulPadType);
|
||||
extern void GPIOPinIntEnable(unsigned long ulPort, unsigned char ucPins);
|
||||
extern void GPIOPinIntDisable(unsigned long ulPort, unsigned char ucPins);
|
||||
extern long GPIOPinIntStatus(unsigned long ulPort, tBoolean bMasked);
|
||||
extern void GPIOPinIntClear(unsigned long ulPort, unsigned char ucPins);
|
||||
extern void GPIOPortIntRegister(unsigned long ulPort,
|
||||
void (*pfnIntHandler)(void));
|
||||
extern void GPIOPortIntUnregister(unsigned long ulPort);
|
||||
extern long GPIOPinRead(unsigned long ulPort, unsigned char ucPins);
|
||||
extern void GPIOPinWrite(unsigned long ulPort, unsigned char ucPins,
|
||||
unsigned char ucVal);
|
||||
extern void GPIOPinConfigure(unsigned long ulPinConfig);
|
||||
extern void GPIOPinTypeADC(unsigned long ulPort, unsigned char ucPins);
|
||||
extern void GPIOPinTypeCAN(unsigned long ulPort, unsigned char ucPins);
|
||||
extern void GPIOPinTypeComparator(unsigned long ulPort, unsigned char ucPins);
|
||||
extern void GPIOPinTypeEPI(unsigned long ulPort, unsigned char ucPins);
|
||||
extern void GPIOPinTypeEthernetLED(unsigned long ulPort, unsigned char ucPins);
|
||||
extern void GPIOPinTypeEthernetMII(unsigned long ulPort, unsigned char ucPins);
|
||||
extern void GPIOPinTypeFan(unsigned long ulPort, unsigned char ucPins);
|
||||
extern void GPIOPinTypeGPIOInput(unsigned long ulPort, unsigned char ucPins);
|
||||
extern void GPIOPinTypeGPIOOutput(unsigned long ulPort, unsigned char ucPins);
|
||||
extern void GPIOPinTypeGPIOOutputOD(unsigned long ulPort,
|
||||
unsigned char ucPins);
|
||||
extern void GPIOPinTypeI2C(unsigned long ulPort, unsigned char ucPins);
|
||||
extern void GPIOPinTypeI2CSCL(unsigned long ulPort, unsigned char ucPins);
|
||||
extern void GPIOPinTypeI2S(unsigned long ulPort, unsigned char ucPins);
|
||||
extern void GPIOPinTypeLPC(unsigned long ulPort, unsigned char ucPins);
|
||||
extern void GPIOPinTypePECIRx(unsigned long ulPort, unsigned char ucPins);
|
||||
extern void GPIOPinTypePECITx(unsigned long ulPort, unsigned char ucPins);
|
||||
extern void GPIOPinTypePWM(unsigned long ulPort, unsigned char ucPins);
|
||||
extern void GPIOPinTypeQEI(unsigned long ulPort, unsigned char ucPins);
|
||||
extern void GPIOPinTypeSSI(unsigned long ulPort, unsigned char ucPins);
|
||||
extern void GPIOPinTypeTimer(unsigned long ulPort, unsigned char ucPins);
|
||||
extern void GPIOPinTypeUART(unsigned long ulPort, unsigned char ucPins);
|
||||
extern void GPIOPinTypeUSBAnalog(unsigned long ulPort, unsigned char ucPins);
|
||||
extern void GPIOPinTypeUSBDigital(unsigned long ulPort, unsigned char ucPins);
|
||||
extern void GPIODMATriggerEnable(unsigned long ulPort, unsigned char ucPins);
|
||||
extern void GPIODMATriggerDisable(unsigned long ulPort, unsigned char ucPins);
|
||||
extern void GPIOADCTriggerEnable(unsigned long ulPort, unsigned char ucPins);
|
||||
extern void GPIOADCTriggerDisable(unsigned long ulPort, unsigned char ucPins);
|
||||
|
||||
//****************************************************************************
|
||||
//
|
||||
// The definitions for GPIOPinConfigure previously resided in this file but
|
||||
// have been moved to pin_map.h and made part-specific (in other words, only
|
||||
// those definitions that are valid based on the selected part, as defined by
|
||||
// PART_<partnum>, will be made available). For backwards compatibility,
|
||||
// pin_map.h is included here so that the expected definitions will still be
|
||||
// available (though part-specific now, so some that were previously available
|
||||
// but inappropriate for the given part will not be available).
|
||||
//
|
||||
//*****************************************************************************
|
||||
#ifndef DEPRECATED
|
||||
#include "pin_map.h"
|
||||
#endif
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Mark the end of the C bindings section for C++ compilers.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif // __GPIO_H__
|
|
@ -0,0 +1,837 @@
|
|||
//*****************************************************************************
|
||||
//
|
||||
// interrupt.c - Driver for the NVIC Interrupt Controller.
|
||||
//
|
||||
// Copyright (c) 2005-2013 Texas Instruments Incorporated. All rights reserved.
|
||||
// Software License Agreement
|
||||
//
|
||||
// Redistribution and use in source and binary forms, with or without
|
||||
// modification, are permitted provided that the following conditions
|
||||
// are met:
|
||||
//
|
||||
// Redistributions of source code must retain the above copyright
|
||||
// notice, this list of conditions and the following disclaimer.
|
||||
//
|
||||
// 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.
|
||||
//
|
||||
// Neither the name of Texas Instruments Incorporated 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
|
||||
// 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.
|
||||
//
|
||||
// This is part of revision 10636 of the Stellaris Peripheral Driver Library.
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! \addtogroup interrupt_api
|
||||
//! @{
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
#include "inc/hw_ints.h"
|
||||
#include "inc/hw_nvic.h"
|
||||
#include "inc/hw_types.h"
|
||||
#include "driverlib/cpu.h"
|
||||
#include "driverlib/debug.h"
|
||||
#include "driverlib/interrupt.h"
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// This is a mapping between priority grouping encodings and the number of
|
||||
// preemption priority bits.
|
||||
//
|
||||
//*****************************************************************************
|
||||
static const unsigned long g_pulPriority[] =
|
||||
{
|
||||
NVIC_APINT_PRIGROUP_0_8, NVIC_APINT_PRIGROUP_1_7, NVIC_APINT_PRIGROUP_2_6,
|
||||
NVIC_APINT_PRIGROUP_3_5, NVIC_APINT_PRIGROUP_4_4, NVIC_APINT_PRIGROUP_5_3,
|
||||
NVIC_APINT_PRIGROUP_6_2, NVIC_APINT_PRIGROUP_7_1
|
||||
};
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// This is a mapping between interrupt number and the register that contains
|
||||
// the priority encoding for that interrupt.
|
||||
//
|
||||
//*****************************************************************************
|
||||
static const unsigned long g_pulRegs[] =
|
||||
{
|
||||
0, NVIC_SYS_PRI1, NVIC_SYS_PRI2, NVIC_SYS_PRI3, NVIC_PRI0, NVIC_PRI1,
|
||||
NVIC_PRI2, NVIC_PRI3, NVIC_PRI4, NVIC_PRI5, NVIC_PRI6, NVIC_PRI7,
|
||||
NVIC_PRI8, NVIC_PRI9, NVIC_PRI10, NVIC_PRI11, NVIC_PRI12, NVIC_PRI13,
|
||||
NVIC_PRI14, NVIC_PRI15, NVIC_PRI16, NVIC_PRI17, NVIC_PRI18, NVIC_PRI19,
|
||||
NVIC_PRI20, NVIC_PRI21, NVIC_PRI22, NVIC_PRI23, NVIC_PRI24, NVIC_PRI25,
|
||||
NVIC_PRI26, NVIC_PRI27, NVIC_PRI28, NVIC_PRI29, NVIC_PRI30, NVIC_PRI31,
|
||||
NVIC_PRI32, NVIC_PRI33, NVIC_PRI34
|
||||
};
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// This is a mapping between interrupt number (for the peripheral interrupts
|
||||
// only) and the register that contains the interrupt enable for that
|
||||
// interrupt.
|
||||
//
|
||||
//*****************************************************************************
|
||||
static const unsigned long g_pulEnRegs[] =
|
||||
{
|
||||
NVIC_EN0, NVIC_EN1, NVIC_EN2, NVIC_EN3, NVIC_EN4
|
||||
};
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// This is a mapping between interrupt number (for the peripheral interrupts
|
||||
// only) and the register that contains the interrupt disable for that
|
||||
// interrupt.
|
||||
//
|
||||
//*****************************************************************************
|
||||
static const unsigned long g_pulDisRegs[] =
|
||||
{
|
||||
NVIC_DIS0, NVIC_DIS1, NVIC_DIS2, NVIC_DIS3, NVIC_DIS4
|
||||
};
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// This is a mapping between interrupt number (for the peripheral interrupts
|
||||
// only) and the register that contains the interrupt pend for that interrupt.
|
||||
//
|
||||
//*****************************************************************************
|
||||
static const unsigned long g_pulPendRegs[] =
|
||||
{
|
||||
NVIC_PEND0, NVIC_PEND1, NVIC_PEND2, NVIC_PEND3, NVIC_PEND4
|
||||
};
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// This is a mapping between interrupt number (for the peripheral interrupts
|
||||
// only) and the register that contains the interrupt unpend for that
|
||||
// interrupt.
|
||||
//
|
||||
//*****************************************************************************
|
||||
static const unsigned long g_pulUnpendRegs[] =
|
||||
{
|
||||
NVIC_UNPEND0, NVIC_UNPEND1, NVIC_UNPEND2, NVIC_UNPEND3, NVIC_UNPEND4
|
||||
};
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! \internal
|
||||
//! The default interrupt handler.
|
||||
//!
|
||||
//! This is the default interrupt handler for all interrupts. It simply loops
|
||||
//! forever so that the system state is preserved for observation by a
|
||||
//! debugger. Since interrupts should be disabled before unregistering the
|
||||
//! corresponding handler, this should never be called.
|
||||
//!
|
||||
//! \return None.
|
||||
//
|
||||
//*****************************************************************************
|
||||
static void
|
||||
IntDefaultHandler(void)
|
||||
{
|
||||
//
|
||||
// Go into an infinite loop.
|
||||
//
|
||||
while(1)
|
||||
{
|
||||
}
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The processor vector table.
|
||||
//
|
||||
// This contains a list of the handlers for the various interrupt sources in
|
||||
// the system. The layout of this list is defined by the hardware; assertion
|
||||
// of an interrupt causes the processor to start executing directly at the
|
||||
// address given in the corresponding location in this list.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#if defined(ewarm)
|
||||
#pragma data_alignment=1024
|
||||
static __no_init void (*g_pfnRAMVectors[NUM_INTERRUPTS])(void) @ "VTABLE";
|
||||
#elif defined(sourcerygxx)
|
||||
static __attribute__((section(".cs3.region-head.ram")))
|
||||
void (*g_pfnRAMVectors[NUM_INTERRUPTS])(void) __attribute__ ((aligned(1024)));
|
||||
#elif defined(ccs) || defined(DOXYGEN)
|
||||
#pragma DATA_ALIGN(g_pfnRAMVectors, 1024)
|
||||
#pragma DATA_SECTION(g_pfnRAMVectors, ".vtable")
|
||||
void (*g_pfnRAMVectors[NUM_INTERRUPTS])(void);
|
||||
#else
|
||||
static __attribute__((section("vtable")))
|
||||
void (*g_pfnRAMVectors[NUM_INTERRUPTS])(void) __attribute__ ((aligned(1024)));
|
||||
#endif
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Enables the processor interrupt.
|
||||
//!
|
||||
//! This function allows the processor to respond to interrupts. This function
|
||||
//! does not affect the set of interrupts enabled in the interrupt controller;
|
||||
//! it just gates the single interrupt from the controller to the processor.
|
||||
//!
|
||||
//! \note Previously, this function had no return value. As such, it was
|
||||
//! possible to include <tt>interrupt.h</tt> and call this function without
|
||||
//! having included <tt>hw_types.h</tt>. Now that the return is a
|
||||
//! <tt>tBoolean</tt>, a compiler error occurs in this case. The solution
|
||||
//! is to include <tt>hw_types.h</tt> before including <tt>interrupt.h</tt>.
|
||||
//!
|
||||
//! \return Returns \b true if interrupts were disabled when the function was
|
||||
//! called or \b false if they were initially enabled.
|
||||
//
|
||||
//*****************************************************************************
|
||||
tBoolean
|
||||
IntMasterEnable(void)
|
||||
{
|
||||
//
|
||||
// Enable processor interrupts.
|
||||
//
|
||||
return(CPUcpsie());
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Disables the processor interrupt.
|
||||
//!
|
||||
//! This function prevents the processor from receiving interrupts. This
|
||||
//! function does not affect the set of interrupts enabled in the interrupt
|
||||
//! controller; it just gates the single interrupt from the controller to the
|
||||
//! processor.
|
||||
//!
|
||||
//! \note Previously, this function had no return value. As such, it was
|
||||
//! possible to include <tt>interrupt.h</tt> and call this function without
|
||||
//! having included <tt>hw_types.h</tt>. Now that the return is a
|
||||
//! <tt>tBoolean</tt>, a compiler error occurs in this case. The solution
|
||||
//! is to include <tt>hw_types.h</tt> before including <tt>interrupt.h</tt>.
|
||||
//!
|
||||
//! \return Returns \b true if interrupts were already disabled when the
|
||||
//! function was called or \b false if they were initially enabled.
|
||||
//
|
||||
//*****************************************************************************
|
||||
tBoolean
|
||||
IntMasterDisable(void)
|
||||
{
|
||||
//
|
||||
// Disable processor interrupts.
|
||||
//
|
||||
return(CPUcpsid());
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Registers a function to be called when an interrupt occurs.
|
||||
//!
|
||||
//! \param ulInterrupt specifies the interrupt in question.
|
||||
//! \param pfnHandler is a pointer to the function to be called.
|
||||
//!
|
||||
//! This function is used to specify the handler function to be called when the
|
||||
//! given interrupt is asserted to the processor. When the interrupt occurs,
|
||||
//! if it is enabled (via IntEnable()), the handler function is called in
|
||||
//! interrupt context. Because the handler function can preempt other code,
|
||||
//! care must be taken to protect memory or peripherals that are accessed by
|
||||
//! the handler and other non-handler code.
|
||||
//!
|
||||
//! \note The use of this function (directly or indirectly via a peripheral
|
||||
//! driver interrupt register function) moves the interrupt vector table from
|
||||
//! flash to SRAM. Therefore, care must be taken when linking the application
|
||||
//! to ensure that the SRAM vector table is located at the beginning of SRAM;
|
||||
//! otherwise the NVIC does not look in the correct portion of memory for the
|
||||
//! vector table (it requires the vector table be on a 1 kB memory alignment).
|
||||
//! Normally, the SRAM vector table is so placed via the use of linker scripts.
|
||||
//! See the discussion of compile-time versus run-time interrupt handler
|
||||
//! registration in the introduction to this chapter.
|
||||
//!
|
||||
//! \return None.
|
||||
//
|
||||
//*****************************************************************************
|
||||
void
|
||||
IntRegister(unsigned long ulInterrupt, void (*pfnHandler)(void))
|
||||
{
|
||||
unsigned long ulIdx, ulValue;
|
||||
|
||||
//
|
||||
// Check the arguments.
|
||||
//
|
||||
ASSERT(ulInterrupt < NUM_INTERRUPTS);
|
||||
|
||||
//
|
||||
// Make sure that the RAM vector table is correctly aligned.
|
||||
//
|
||||
ASSERT(((unsigned long)g_pfnRAMVectors & 0x000003ff) == 0);
|
||||
|
||||
//
|
||||
// See if the RAM vector table has been initialized.
|
||||
//
|
||||
if(HWREG(NVIC_VTABLE) != (unsigned long)g_pfnRAMVectors)
|
||||
{
|
||||
//
|
||||
// Copy the vector table from the beginning of FLASH to the RAM vector
|
||||
// table.
|
||||
//
|
||||
ulValue = HWREG(NVIC_VTABLE);
|
||||
for(ulIdx = 0; ulIdx < NUM_INTERRUPTS; ulIdx++)
|
||||
{
|
||||
g_pfnRAMVectors[ulIdx] = (void (*)(void))HWREG((ulIdx * 4) +
|
||||
ulValue);
|
||||
}
|
||||
|
||||
//
|
||||
// Point the NVIC at the RAM vector table.
|
||||
//
|
||||
HWREG(NVIC_VTABLE) = (unsigned long)g_pfnRAMVectors;
|
||||
}
|
||||
|
||||
//
|
||||
// Save the interrupt handler.
|
||||
//
|
||||
g_pfnRAMVectors[ulInterrupt] = pfnHandler;
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Unregisters the function to be called when an interrupt occurs.
|
||||
//!
|
||||
//! \param ulInterrupt specifies the interrupt in question.
|
||||
//!
|
||||
//! This function is used to indicate that no handler should be called when the
|
||||
//! given interrupt is asserted to the processor. The interrupt source is
|
||||
//! automatically disabled (via IntDisable()) if necessary.
|
||||
//!
|
||||
//! \sa IntRegister() for important information about registering interrupt
|
||||
//! handlers.
|
||||
//!
|
||||
//! \return None.
|
||||
//
|
||||
//*****************************************************************************
|
||||
void
|
||||
IntUnregister(unsigned long ulInterrupt)
|
||||
{
|
||||
//
|
||||
// Check the arguments.
|
||||
//
|
||||
ASSERT(ulInterrupt < NUM_INTERRUPTS);
|
||||
|
||||
//
|
||||
// Reset the interrupt handler.
|
||||
//
|
||||
g_pfnRAMVectors[ulInterrupt] = IntDefaultHandler;
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Sets the priority grouping of the interrupt controller.
|
||||
//!
|
||||
//! \param ulBits specifies the number of bits of preemptable priority.
|
||||
//!
|
||||
//! This function specifies the split between preemptable priority levels and
|
||||
//! sub-priority levels in the interrupt priority specification. The range of
|
||||
//! the grouping values are dependent upon the hardware implementation; on
|
||||
//! the Stellaris family, three bits are available for hardware interrupt
|
||||
//! prioritization and therefore priority grouping values of three through
|
||||
//! seven have the same effect.
|
||||
//!
|
||||
//! \return None.
|
||||
//
|
||||
//*****************************************************************************
|
||||
void
|
||||
IntPriorityGroupingSet(unsigned long ulBits)
|
||||
{
|
||||
//
|
||||
// Check the arguments.
|
||||
//
|
||||
ASSERT(ulBits < NUM_PRIORITY);
|
||||
|
||||
//
|
||||
// Set the priority grouping.
|
||||
//
|
||||
HWREG(NVIC_APINT) = NVIC_APINT_VECTKEY | g_pulPriority[ulBits];
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Gets the priority grouping of the interrupt controller.
|
||||
//!
|
||||
//! This function returns the split between preemptable priority levels and
|
||||
//! sub-priority levels in the interrupt priority specification.
|
||||
//!
|
||||
//! \return The number of bits of preemptable priority.
|
||||
//
|
||||
//*****************************************************************************
|
||||
unsigned long
|
||||
IntPriorityGroupingGet(void)
|
||||
{
|
||||
unsigned long ulLoop, ulValue;
|
||||
|
||||
//
|
||||
// Read the priority grouping.
|
||||
//
|
||||
ulValue = HWREG(NVIC_APINT) & NVIC_APINT_PRIGROUP_M;
|
||||
|
||||
//
|
||||
// Loop through the priority grouping values.
|
||||
//
|
||||
for(ulLoop = 0; ulLoop < NUM_PRIORITY; ulLoop++)
|
||||
{
|
||||
//
|
||||
// Stop looping if this value matches.
|
||||
//
|
||||
if(ulValue == g_pulPriority[ulLoop])
|
||||
{
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
//
|
||||
// Return the number of priority bits.
|
||||
//
|
||||
return(ulLoop);
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Sets the priority of an interrupt.
|
||||
//!
|
||||
//! \param ulInterrupt specifies the interrupt in question.
|
||||
//! \param ucPriority specifies the priority of the interrupt.
|
||||
//!
|
||||
//! This function is used to set the priority of an interrupt. When multiple
|
||||
//! interrupts are asserted simultaneously, the ones with the highest priority
|
||||
//! are processed before the lower priority interrupts. Smaller numbers
|
||||
//! correspond to higher interrupt priorities; priority 0 is the highest
|
||||
//! interrupt priority.
|
||||
//!
|
||||
//! The hardware priority mechanism only looks at the upper N bits of the
|
||||
//! priority level (where N is 3 for the Stellaris family), so any
|
||||
//! prioritization must be performed in those bits. The remaining bits can be
|
||||
//! used to sub-prioritize the interrupt sources, and may be used by the
|
||||
//! hardware priority mechanism on a future part. This arrangement allows
|
||||
//! priorities to migrate to different NVIC implementations without changing
|
||||
//! the gross prioritization of the interrupts.
|
||||
//!
|
||||
//! \return None.
|
||||
//
|
||||
//*****************************************************************************
|
||||
void
|
||||
IntPrioritySet(unsigned long ulInterrupt, unsigned char ucPriority)
|
||||
{
|
||||
unsigned long ulTemp;
|
||||
|
||||
//
|
||||
// Check the arguments.
|
||||
//
|
||||
ASSERT((ulInterrupt >= 4) && (ulInterrupt < NUM_INTERRUPTS));
|
||||
|
||||
//
|
||||
// Set the interrupt priority.
|
||||
//
|
||||
ulTemp = HWREG(g_pulRegs[ulInterrupt >> 2]);
|
||||
ulTemp &= ~(0xFF << (8 * (ulInterrupt & 3)));
|
||||
ulTemp |= ucPriority << (8 * (ulInterrupt & 3));
|
||||
HWREG(g_pulRegs[ulInterrupt >> 2]) = ulTemp;
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Gets the priority of an interrupt.
|
||||
//!
|
||||
//! \param ulInterrupt specifies the interrupt in question.
|
||||
//!
|
||||
//! This function gets the priority of an interrupt. See IntPrioritySet() for
|
||||
//! a definition of the priority value.
|
||||
//!
|
||||
//! \return Returns the interrupt priority, or -1 if an invalid interrupt was
|
||||
//! specified.
|
||||
//
|
||||
//*****************************************************************************
|
||||
long
|
||||
IntPriorityGet(unsigned long ulInterrupt)
|
||||
{
|
||||
//
|
||||
// Check the arguments.
|
||||
//
|
||||
ASSERT((ulInterrupt >= 4) && (ulInterrupt < NUM_INTERRUPTS));
|
||||
|
||||
//
|
||||
// Return the interrupt priority.
|
||||
//
|
||||
return((HWREG(g_pulRegs[ulInterrupt >> 2]) >> (8 * (ulInterrupt & 3))) &
|
||||
0xFF);
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Enables an interrupt.
|
||||
//!
|
||||
//! \param ulInterrupt specifies the interrupt to be enabled.
|
||||
//!
|
||||
//! The specified interrupt is enabled in the interrupt controller. Other
|
||||
//! enables for the interrupt (such as at the peripheral level) are unaffected
|
||||
//! by this function.
|
||||
//!
|
||||
//! \return None.
|
||||
//
|
||||
//*****************************************************************************
|
||||
void
|
||||
IntEnable(unsigned long ulInterrupt)
|
||||
{
|
||||
//
|
||||
// Check the arguments.
|
||||
//
|
||||
ASSERT(ulInterrupt < NUM_INTERRUPTS);
|
||||
|
||||
//
|
||||
// Determine the interrupt to enable.
|
||||
//
|
||||
if(ulInterrupt == FAULT_MPU)
|
||||
{
|
||||
//
|
||||
// Enable the MemManage interrupt.
|
||||
//
|
||||
HWREG(NVIC_SYS_HND_CTRL) |= NVIC_SYS_HND_CTRL_MEM;
|
||||
}
|
||||
else if(ulInterrupt == FAULT_BUS)
|
||||
{
|
||||
//
|
||||
// Enable the bus fault interrupt.
|
||||
//
|
||||
HWREG(NVIC_SYS_HND_CTRL) |= NVIC_SYS_HND_CTRL_BUS;
|
||||
}
|
||||
else if(ulInterrupt == FAULT_USAGE)
|
||||
{
|
||||
//
|
||||
// Enable the usage fault interrupt.
|
||||
//
|
||||
HWREG(NVIC_SYS_HND_CTRL) |= NVIC_SYS_HND_CTRL_USAGE;
|
||||
}
|
||||
else if(ulInterrupt == FAULT_SYSTICK)
|
||||
{
|
||||
//
|
||||
// Enable the System Tick interrupt.
|
||||
//
|
||||
HWREG(NVIC_ST_CTRL) |= NVIC_ST_CTRL_INTEN;
|
||||
}
|
||||
else if(ulInterrupt >= 16)
|
||||
{
|
||||
//
|
||||
// Enable the general interrupt.
|
||||
//
|
||||
HWREG(g_pulEnRegs[(ulInterrupt - 16) / 32]) =
|
||||
1 << ((ulInterrupt - 16) & 31);
|
||||
}
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Disables an interrupt.
|
||||
//!
|
||||
//! \param ulInterrupt specifies the interrupt to be disabled.
|
||||
//!
|
||||
//! The specified interrupt is disabled in the interrupt controller. Other
|
||||
//! enables for the interrupt (such as at the peripheral level) are unaffected
|
||||
//! by this function.
|
||||
//!
|
||||
//! \return None.
|
||||
//
|
||||
//*****************************************************************************
|
||||
void
|
||||
IntDisable(unsigned long ulInterrupt)
|
||||
{
|
||||
//
|
||||
// Check the arguments.
|
||||
//
|
||||
ASSERT(ulInterrupt < NUM_INTERRUPTS);
|
||||
|
||||
//
|
||||
// Determine the interrupt to disable.
|
||||
//
|
||||
if(ulInterrupt == FAULT_MPU)
|
||||
{
|
||||
//
|
||||
// Disable the MemManage interrupt.
|
||||
//
|
||||
HWREG(NVIC_SYS_HND_CTRL) &= ~(NVIC_SYS_HND_CTRL_MEM);
|
||||
}
|
||||
else if(ulInterrupt == FAULT_BUS)
|
||||
{
|
||||
//
|
||||
// Disable the bus fault interrupt.
|
||||
//
|
||||
HWREG(NVIC_SYS_HND_CTRL) &= ~(NVIC_SYS_HND_CTRL_BUS);
|
||||
}
|
||||
else if(ulInterrupt == FAULT_USAGE)
|
||||
{
|
||||
//
|
||||
// Disable the usage fault interrupt.
|
||||
//
|
||||
HWREG(NVIC_SYS_HND_CTRL) &= ~(NVIC_SYS_HND_CTRL_USAGE);
|
||||
}
|
||||
else if(ulInterrupt == FAULT_SYSTICK)
|
||||
{
|
||||
//
|
||||
// Disable the System Tick interrupt.
|
||||
//
|
||||
HWREG(NVIC_ST_CTRL) &= ~(NVIC_ST_CTRL_INTEN);
|
||||
}
|
||||
else if(ulInterrupt >= 16)
|
||||
{
|
||||
//
|
||||
// Disable the general interrupt.
|
||||
//
|
||||
HWREG(g_pulDisRegs[(ulInterrupt - 16) / 32]) =
|
||||
1 << ((ulInterrupt - 16) & 31);
|
||||
}
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Returns if a peripheral interrupt is enabled.
|
||||
//!
|
||||
//! \param ulInterrupt specifies the interrupt to check.
|
||||
//!
|
||||
//! This function checks if the specified interrupt is enabled in the interrupt
|
||||
//! controller.
|
||||
//!
|
||||
//! \return A non-zero value if the interrupt is enabled.
|
||||
//
|
||||
//*****************************************************************************
|
||||
unsigned long
|
||||
IntIsEnabled(unsigned long ulInterrupt)
|
||||
{
|
||||
unsigned long ulRet;
|
||||
|
||||
//
|
||||
// Check the arguments.
|
||||
//
|
||||
ASSERT(ulInterrupt < NUM_INTERRUPTS);
|
||||
|
||||
//
|
||||
// Initialize the return value.
|
||||
//
|
||||
ulRet = 0;
|
||||
|
||||
//
|
||||
// Determine the interrupt to disable.
|
||||
//
|
||||
if(ulInterrupt == FAULT_MPU)
|
||||
{
|
||||
//
|
||||
// Check the MemManage interrupt.
|
||||
//
|
||||
ulRet = HWREG(NVIC_SYS_HND_CTRL) & NVIC_SYS_HND_CTRL_MEM;
|
||||
}
|
||||
else if(ulInterrupt == FAULT_BUS)
|
||||
{
|
||||
//
|
||||
// Check the bus fault interrupt.
|
||||
//
|
||||
ulRet = HWREG(NVIC_SYS_HND_CTRL) & NVIC_SYS_HND_CTRL_BUS;
|
||||
}
|
||||
else if(ulInterrupt == FAULT_USAGE)
|
||||
{
|
||||
//
|
||||
// Check the usage fault interrupt.
|
||||
//
|
||||
ulRet = HWREG(NVIC_SYS_HND_CTRL) & NVIC_SYS_HND_CTRL_USAGE;
|
||||
}
|
||||
else if(ulInterrupt == FAULT_SYSTICK)
|
||||
{
|
||||
//
|
||||
// Check the System Tick interrupt.
|
||||
//
|
||||
ulRet = HWREG(NVIC_ST_CTRL) & NVIC_ST_CTRL_INTEN;
|
||||
}
|
||||
else if(ulInterrupt >= 16)
|
||||
{
|
||||
//
|
||||
// Check the general interrupt.
|
||||
//
|
||||
ulRet = HWREG(g_pulEnRegs[(ulInterrupt - 16) / 32]) &
|
||||
(1 << ((ulInterrupt - 16) & 31));
|
||||
}
|
||||
return(ulRet);
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Pends an interrupt.
|
||||
//!
|
||||
//! \param ulInterrupt specifies the interrupt to be pended.
|
||||
//!
|
||||
//! The specified interrupt is pended in the interrupt controller. Pending an
|
||||
//! interrupt causes the interrupt controller to execute the corresponding
|
||||
//! interrupt handler at the next available time, based on the current
|
||||
//! interrupt state priorities. For example, if called by a higher priority
|
||||
//! interrupt handler, the specified interrupt handler is not called until
|
||||
//! after the current interrupt handler has completed execution. The interrupt
|
||||
//! must have been enabled for it to be called.
|
||||
//!
|
||||
//! \return None.
|
||||
//
|
||||
//*****************************************************************************
|
||||
void
|
||||
IntPendSet(unsigned long ulInterrupt)
|
||||
{
|
||||
//
|
||||
// Check the arguments.
|
||||
//
|
||||
ASSERT(ulInterrupt < NUM_INTERRUPTS);
|
||||
|
||||
//
|
||||
// Determine the interrupt to pend.
|
||||
//
|
||||
if(ulInterrupt == FAULT_NMI)
|
||||
{
|
||||
//
|
||||
// Pend the NMI interrupt.
|
||||
//
|
||||
HWREG(NVIC_INT_CTRL) |= NVIC_INT_CTRL_NMI_SET;
|
||||
}
|
||||
else if(ulInterrupt == FAULT_PENDSV)
|
||||
{
|
||||
//
|
||||
// Pend the PendSV interrupt.
|
||||
//
|
||||
HWREG(NVIC_INT_CTRL) |= NVIC_INT_CTRL_PEND_SV;
|
||||
}
|
||||
else if(ulInterrupt == FAULT_SYSTICK)
|
||||
{
|
||||
//
|
||||
// Pend the SysTick interrupt.
|
||||
//
|
||||
HWREG(NVIC_INT_CTRL) |= NVIC_INT_CTRL_PENDSTSET;
|
||||
}
|
||||
else if(ulInterrupt >= 16)
|
||||
{
|
||||
//
|
||||
// Pend the general interrupt.
|
||||
//
|
||||
HWREG(g_pulPendRegs[(ulInterrupt - 16) / 32]) =
|
||||
1 << ((ulInterrupt - 16) & 31);
|
||||
}
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Un-pends an interrupt.
|
||||
//!
|
||||
//! \param ulInterrupt specifies the interrupt to be un-pended.
|
||||
//!
|
||||
//! The specified interrupt is un-pended in the interrupt controller. This
|
||||
//! will cause any previously generated interrupts that have not been handled
|
||||
//! yet (due to higher priority interrupts or the interrupt no having been
|
||||
//! enabled yet) to be discarded.
|
||||
//!
|
||||
//! \return None.
|
||||
//
|
||||
//*****************************************************************************
|
||||
void
|
||||
IntPendClear(unsigned long ulInterrupt)
|
||||
{
|
||||
//
|
||||
// Check the arguments.
|
||||
//
|
||||
ASSERT(ulInterrupt < NUM_INTERRUPTS);
|
||||
|
||||
//
|
||||
// Determine the interrupt to unpend.
|
||||
//
|
||||
if(ulInterrupt == FAULT_PENDSV)
|
||||
{
|
||||
//
|
||||
// Unpend the PendSV interrupt.
|
||||
//
|
||||
HWREG(NVIC_INT_CTRL) |= NVIC_INT_CTRL_UNPEND_SV;
|
||||
}
|
||||
else if(ulInterrupt == FAULT_SYSTICK)
|
||||
{
|
||||
//
|
||||
// Unpend the SysTick interrupt.
|
||||
//
|
||||
HWREG(NVIC_INT_CTRL) |= NVIC_INT_CTRL_PENDSTCLR;
|
||||
}
|
||||
else if(ulInterrupt >= 16)
|
||||
{
|
||||
//
|
||||
// Unpend the general interrupt.
|
||||
//
|
||||
HWREG(g_pulUnpendRegs[(ulInterrupt - 16) / 32]) =
|
||||
1 << ((ulInterrupt - 16) & 31);
|
||||
}
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Sets the priority masking level
|
||||
//!
|
||||
//! \param ulPriorityMask is the priority level that is masked.
|
||||
//!
|
||||
//! This function sets the interrupt priority masking level so that all
|
||||
//! interrupts at the specified or lesser priority level are masked. Masking
|
||||
//! interrupts can be used to globally disable a set of interrupts with
|
||||
//! priority below a predetermined threshold. A value of 0 disables priority
|
||||
//! masking.
|
||||
//!
|
||||
//! Smaller numbers correspond to higher interrupt priorities. So for example
|
||||
//! a priority level mask of 4 allows interrupts of priority level 0-3,
|
||||
//! and interrupts with a numerical priority of 4 and greater are blocked.
|
||||
//!
|
||||
//! The hardware priority mechanism only looks at the upper N bits of the
|
||||
//! priority level (where N is 3 for the Stellaris family), so any
|
||||
//! prioritization must be performed in those bits.
|
||||
//!
|
||||
//! \return None.
|
||||
//
|
||||
//*****************************************************************************
|
||||
void
|
||||
IntPriorityMaskSet(unsigned long ulPriorityMask)
|
||||
{
|
||||
CPUbasepriSet(ulPriorityMask);
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
//! Gets the priority masking level
|
||||
//!
|
||||
//! This function gets the current setting of the interrupt priority masking
|
||||
//! level. The value returned is the priority level such that all interrupts
|
||||
//! of that and lesser priority are masked. A value of 0 means that priority
|
||||
//! masking is disabled.
|
||||
//!
|
||||
//! Smaller numbers correspond to higher interrupt priorities. So for example
|
||||
//! a priority level mask of 4 allows interrupts of priority level 0-3,
|
||||
//! and interrupts with a numerical priority of 4 and greater are blocked.
|
||||
//!
|
||||
//! The hardware priority mechanism only looks at the upper N bits of the
|
||||
//! priority level (where N is 3 for the Stellaris family), so any
|
||||
//! prioritization must be performed in those bits.
|
||||
//!
|
||||
//! \return Returns the value of the interrupt priority level mask.
|
||||
//
|
||||
//*****************************************************************************
|
||||
unsigned long
|
||||
IntPriorityMaskGet(void)
|
||||
{
|
||||
return(CPUbasepriGet());
|
||||
}
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Close the Doxygen group.
|
||||
//! @}
|
||||
//
|
||||
//*****************************************************************************
|
|
@ -0,0 +1,93 @@
|
|||
//*****************************************************************************
|
||||
//
|
||||
// interrupt.h - Prototypes for the NVIC Interrupt Controller Driver.
|
||||
//
|
||||
// Copyright (c) 2005-2013 Texas Instruments Incorporated. All rights reserved.
|
||||
// Software License Agreement
|
||||
//
|
||||
// Redistribution and use in source and binary forms, with or without
|
||||
// modification, are permitted provided that the following conditions
|
||||
// are met:
|
||||
//
|
||||
// Redistributions of source code must retain the above copyright
|
||||
// notice, this list of conditions and the following disclaimer.
|
||||
//
|
||||
// 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.
|
||||
//
|
||||
// Neither the name of Texas Instruments Incorporated 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
|
||||
// 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.
|
||||
//
|
||||
// This is part of revision 10636 of the Stellaris Peripheral Driver Library.
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
#ifndef __INTERRUPT_H__
|
||||
#define __INTERRUPT_H__
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// If building with a C++ compiler, make all of the definitions in this header
|
||||
// have a C binding.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#ifdef __cplusplus
|
||||
extern "C"
|
||||
{
|
||||
#endif
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Macro to generate an interrupt priority mask based on the number of bits
|
||||
// of priority supported by the hardware.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define INT_PRIORITY_MASK ((0xFF << (8 - NUM_PRIORITY_BITS)) & 0xFF)
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Prototypes for the APIs.
|
||||
//
|
||||
//*****************************************************************************
|
||||
extern tBoolean IntMasterEnable(void);
|
||||
extern tBoolean IntMasterDisable(void);
|
||||
extern void IntRegister(unsigned long ulInterrupt, void (*pfnHandler)(void));
|
||||
extern void IntUnregister(unsigned long ulInterrupt);
|
||||
extern void IntPriorityGroupingSet(unsigned long ulBits);
|
||||
extern unsigned long IntPriorityGroupingGet(void);
|
||||
extern void IntPrioritySet(unsigned long ulInterrupt,
|
||||
unsigned char ucPriority);
|
||||
extern long IntPriorityGet(unsigned long ulInterrupt);
|
||||
extern void IntEnable(unsigned long ulInterrupt);
|
||||
extern void IntDisable(unsigned long ulInterrupt);
|
||||
extern unsigned long IntIsEnabled(unsigned long ulInterrupt);
|
||||
extern void IntPendSet(unsigned long ulInterrupt);
|
||||
extern void IntPendClear(unsigned long ulInterrupt);
|
||||
extern void IntPriorityMaskSet(unsigned long ulPriorityMask);
|
||||
extern unsigned long IntPriorityMaskGet(void);
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Mark the end of the C bindings section for C++ compilers.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif // __INTERRUPT_H__
|
File diff suppressed because it is too large
Load Diff
File diff suppressed because it is too large
Load Diff
|
@ -0,0 +1,642 @@
|
|||
//*****************************************************************************
|
||||
//
|
||||
// sysctl.h - Prototypes for the system control driver.
|
||||
//
|
||||
// Copyright (c) 2005-2013 Texas Instruments Incorporated. All rights reserved.
|
||||
// Software License Agreement
|
||||
//
|
||||
// Redistribution and use in source and binary forms, with or without
|
||||
// modification, are permitted provided that the following conditions
|
||||
// are met:
|
||||
//
|
||||
// Redistributions of source code must retain the above copyright
|
||||
// notice, this list of conditions and the following disclaimer.
|
||||
//
|
||||
// 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.
|
||||
//
|
||||
// Neither the name of Texas Instruments Incorporated 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
|
||||
// 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.
|
||||
//
|
||||
// This is part of revision 10636 of the Stellaris Peripheral Driver Library.
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
#ifndef __SYSCTL_H__
|
||||
#define __SYSCTL_H__
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// If building with a C++ compiler, make all of the definitions in this header
|
||||
// have a C binding.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#ifdef __cplusplus
|
||||
extern "C"
|
||||
{
|
||||
#endif
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are values that can be passed to the
|
||||
// SysCtlPeripheralPresent(), SysCtlPeripheralEnable(),
|
||||
// SysCtlPeripheralDisable(), and SysCtlPeripheralReset() APIs as the
|
||||
// ulPeripheral parameter. The peripherals in the fourth group (upper nibble
|
||||
// is 3) can only be used with the SysCtlPeripheralPresent() API.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#ifndef DEPRECATED
|
||||
#define SYSCTL_PERIPH_WDOG 0x00000008 // Watchdog
|
||||
#endif
|
||||
#define SYSCTL_PERIPH_WDOG0 0x00000008 // Watchdog 0
|
||||
#define SYSCTL_PERIPH_HIBERNATE 0x00000040 // Hibernation module
|
||||
#ifndef DEPRECATED
|
||||
#define SYSCTL_PERIPH_ADC 0x00100001 // ADC
|
||||
#endif
|
||||
#define SYSCTL_PERIPH_ADC0 0x00100001 // ADC0
|
||||
#define SYSCTL_PERIPH_ADC1 0x00100002 // ADC1
|
||||
#ifndef DEPRECATED
|
||||
#define SYSCTL_PERIPH_PWM 0x00100010 // PWM
|
||||
#endif
|
||||
#define SYSCTL_PERIPH_PWM0 0x00100010 // PWM
|
||||
#define SYSCTL_PERIPH_CAN0 0x00100100 // CAN 0
|
||||
#define SYSCTL_PERIPH_CAN1 0x00100200 // CAN 1
|
||||
#define SYSCTL_PERIPH_CAN2 0x00100400 // CAN 2
|
||||
#define SYSCTL_PERIPH_WDOG1 0x00101000 // Watchdog 1
|
||||
#define SYSCTL_PERIPH_UART0 0x10000001 // UART 0
|
||||
#define SYSCTL_PERIPH_UART1 0x10000002 // UART 1
|
||||
#define SYSCTL_PERIPH_UART2 0x10000004 // UART 2
|
||||
#ifndef DEPRECATED
|
||||
#define SYSCTL_PERIPH_SSI 0x10000010 // SSI
|
||||
#endif
|
||||
#define SYSCTL_PERIPH_SSI0 0x10000010 // SSI 0
|
||||
#define SYSCTL_PERIPH_SSI1 0x10000020 // SSI 1
|
||||
#ifndef DEPRECATED
|
||||
#define SYSCTL_PERIPH_QEI 0x10000100 // QEI
|
||||
#endif
|
||||
#define SYSCTL_PERIPH_QEI0 0x10000100 // QEI 0
|
||||
#define SYSCTL_PERIPH_QEI1 0x10000200 // QEI 1
|
||||
#ifndef DEPRECATED
|
||||
#define SYSCTL_PERIPH_I2C 0x10001000 // I2C
|
||||
#endif
|
||||
#define SYSCTL_PERIPH_I2C0 0x10001000 // I2C 0
|
||||
#define SYSCTL_PERIPH_I2C1 0x10004000 // I2C 1
|
||||
#define SYSCTL_PERIPH_TIMER0 0x10100001 // Timer 0
|
||||
#define SYSCTL_PERIPH_TIMER1 0x10100002 // Timer 1
|
||||
#define SYSCTL_PERIPH_TIMER2 0x10100004 // Timer 2
|
||||
#define SYSCTL_PERIPH_TIMER3 0x10100008 // Timer 3
|
||||
#define SYSCTL_PERIPH_COMP0 0x10100100 // Analog comparator 0
|
||||
#define SYSCTL_PERIPH_COMP1 0x10100200 // Analog comparator 1
|
||||
#define SYSCTL_PERIPH_COMP2 0x10100400 // Analog comparator 2
|
||||
#define SYSCTL_PERIPH_I2S0 0x10101000 // I2S0
|
||||
#define SYSCTL_PERIPH_EPI0 0x10104000 // EPI0
|
||||
#define SYSCTL_PERIPH_GPIOA 0x20000001 // GPIO A
|
||||
#define SYSCTL_PERIPH_GPIOB 0x20000002 // GPIO B
|
||||
#define SYSCTL_PERIPH_GPIOC 0x20000004 // GPIO C
|
||||
#define SYSCTL_PERIPH_GPIOD 0x20000008 // GPIO D
|
||||
#define SYSCTL_PERIPH_GPIOE 0x20000010 // GPIO E
|
||||
#define SYSCTL_PERIPH_GPIOF 0x20000020 // GPIO F
|
||||
#define SYSCTL_PERIPH_GPIOG 0x20000040 // GPIO G
|
||||
#define SYSCTL_PERIPH_GPIOH 0x20000080 // GPIO H
|
||||
#define SYSCTL_PERIPH_GPIOJ 0x20000100 // GPIO J
|
||||
#define SYSCTL_PERIPH_UDMA 0x20002000 // uDMA
|
||||
#define SYSCTL_PERIPH_USB0 0x20100001 // USB0
|
||||
#define SYSCTL_PERIPH_ETH 0x20105000 // Ethernet
|
||||
#define SYSCTL_PERIPH_IEEE1588 0x20100100 // IEEE1588
|
||||
#define SYSCTL_PERIPH_PLL 0x30000010 // PLL
|
||||
#define SYSCTL_PERIPH_TEMP 0x30000020 // Temperature sensor
|
||||
#define SYSCTL_PERIPH_MPU 0x30000080 // Cortex M3 MPU
|
||||
#define SYSCTL_PERIPH2_ADC0 0xf0003800 // ADC 0
|
||||
#define SYSCTL_PERIPH2_ADC1 0xf0003801 // ADC 1
|
||||
#define SYSCTL_PERIPH2_CAN0 0xf0003400 // CAN 0
|
||||
#define SYSCTL_PERIPH2_CAN1 0xf0003401 // CAN 1
|
||||
#define SYSCTL_PERIPH2_CAN2 0xf0003402 // CAN 2
|
||||
#define SYSCTL_PERIPH2_COMP0 0xf0003c00 // Analog comparator 0
|
||||
#define SYSCTL_PERIPH_EEPROM0 0xf0005800 // EEPROM 0
|
||||
#define SYSCTL_PERIPH2_EPI0 0xf0001000 // EPI0
|
||||
#define SYSCTL_PERIPH2_ETH 0xf0002c00 // ETH
|
||||
#define SYSCTL_PERIPH_FAN0 0xf0005400 // FAN 0
|
||||
#define SYSCTL_PERIPH2_GPIOA 0xf0000800 // GPIO A
|
||||
#define SYSCTL_PERIPH2_GPIOB 0xf0000801 // GPIO B
|
||||
#define SYSCTL_PERIPH2_GPIOC 0xf0000802 // GPIO C
|
||||
#define SYSCTL_PERIPH2_GPIOD 0xf0000803 // GPIO D
|
||||
#define SYSCTL_PERIPH2_GPIOE 0xf0000804 // GPIO E
|
||||
#define SYSCTL_PERIPH2_GPIOF 0xf0000805 // GPIO F
|
||||
#define SYSCTL_PERIPH2_GPIOG 0xf0000806 // GPIO G
|
||||
#define SYSCTL_PERIPH2_GPIOH 0xf0000807 // GPIO H
|
||||
#define SYSCTL_PERIPH2_GPIOJ 0xf0000808 // GPIO J
|
||||
#define SYSCTL_PERIPH_GPIOK 0xf0000809 // GPIO K
|
||||
#define SYSCTL_PERIPH_GPIOL 0xf000080a // GPIO L
|
||||
#define SYSCTL_PERIPH_GPIOM 0xf000080b // GPIO M
|
||||
#define SYSCTL_PERIPH_GPION 0xf000080c // GPIO N
|
||||
#define SYSCTL_PERIPH_GPIOP 0xf000080d // GPIO P
|
||||
#define SYSCTL_PERIPH_GPIOQ 0xf000080e // GPIO Q
|
||||
#define SYSCTL_PERIPH_GPIOR 0xf000080f // GPIO R
|
||||
#define SYSCTL_PERIPH_GPIOS 0xf0000810 // GPIO S
|
||||
#define SYSCTL_PERIPH2_HIB 0xf0001400 // Hibernation module
|
||||
#define SYSCTL_PERIPH2_I2C0 0xf0002000 // I2C 0
|
||||
#define SYSCTL_PERIPH2_I2C1 0xf0002001 // I2C 1
|
||||
#define SYSCTL_PERIPH_I2C2 0xf0002002 // I2C 2
|
||||
#define SYSCTL_PERIPH_I2C3 0xf0002003 // I2C 3
|
||||
#define SYSCTL_PERIPH_I2C4 0xf0002004 // I2C 4
|
||||
#define SYSCTL_PERIPH_I2C5 0xf0002005 // I2C 5
|
||||
#define SYSCTL_PERIPH2_I2S0 0xf0002400 // I2S0
|
||||
#define SYSCTL_PERIPH_LPC0 0xf0004800 // LPC 0
|
||||
#define SYSCTL_PERIPH_PECI0 0xf0005000 // PECI 0
|
||||
#define SYSCTL_PERIPH2_PWM0 0xf0004000 // PWM 0
|
||||
#define SYSCTL_PERIPH_PWM1 0xf0004001 // PWM 1
|
||||
#define SYSCTL_PERIPH2_QEI0 0xf0004400 // QEI 0
|
||||
#define SYSCTL_PERIPH2_QEI1 0xf0004401 // QEI 1
|
||||
#define SYSCTL_PERIPH2_SSI0 0xf0001c00 // SSI 0
|
||||
#define SYSCTL_PERIPH2_SSI1 0xf0001c01 // SSI 1
|
||||
#define SYSCTL_PERIPH_SSI2 0xf0001c02 // SSI 2
|
||||
#define SYSCTL_PERIPH_SSI3 0xf0001c03 // SSI 3
|
||||
#define SYSCTL_PERIPH2_TIMER0 0xf0000400 // Timer 0
|
||||
#define SYSCTL_PERIPH2_TIMER1 0xf0000401 // Timer 1
|
||||
#define SYSCTL_PERIPH2_TIMER2 0xf0000402 // Timer 2
|
||||
#define SYSCTL_PERIPH2_TIMER3 0xf0000403 // Timer 3
|
||||
#define SYSCTL_PERIPH_TIMER4 0xf0000404 // Timer 4
|
||||
#define SYSCTL_PERIPH_TIMER5 0xf0000405 // Timer 5
|
||||
#define SYSCTL_PERIPH_WTIMER0 0xf0005c00 // Wide Timer 0
|
||||
#define SYSCTL_PERIPH_WTIMER1 0xf0005c01 // Wide Timer 1
|
||||
#define SYSCTL_PERIPH_WTIMER2 0xf0005c02 // Wide Timer 2
|
||||
#define SYSCTL_PERIPH_WTIMER3 0xf0005c03 // Wide Timer 3
|
||||
#define SYSCTL_PERIPH_WTIMER4 0xf0005c04 // Wide Timer 4
|
||||
#define SYSCTL_PERIPH_WTIMER5 0xf0005c05 // Wide Timer 5
|
||||
#define SYSCTL_PERIPH2_UART0 0xf0001800 // UART 0
|
||||
#define SYSCTL_PERIPH2_UART1 0xf0001801 // UART 1
|
||||
#define SYSCTL_PERIPH2_UART2 0xf0001802 // UART 2
|
||||
#define SYSCTL_PERIPH_UART3 0xf0001803 // UART 3
|
||||
#define SYSCTL_PERIPH_UART4 0xf0001804 // UART 4
|
||||
#define SYSCTL_PERIPH_UART5 0xf0001805 // UART 5
|
||||
#define SYSCTL_PERIPH_UART6 0xf0001806 // UART 6
|
||||
#define SYSCTL_PERIPH_UART7 0xf0001807 // UART 7
|
||||
#define SYSCTL_PERIPH2_UDMA 0xf0000c00 // uDMA
|
||||
#define SYSCTL_PERIPH2_USB0 0xf0002800 // USB 0
|
||||
#define SYSCTL_PERIPH2_WDOG0 0xf0000000 // Watchdog 0
|
||||
#define SYSCTL_PERIPH2_WDOG1 0xf0000001 // Watchdog 1
|
||||
#define SYSCTL_PERIPH2_HIBERNATE \
|
||||
0xf0001400 // Hibernate
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are values that can be passed to the SysCtlPinPresent() API
|
||||
// as the ulPin parameter.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define SYSCTL_PIN_PWM0 0x00000001 // PWM0 pin
|
||||
#define SYSCTL_PIN_PWM1 0x00000002 // PWM1 pin
|
||||
#define SYSCTL_PIN_PWM2 0x00000004 // PWM2 pin
|
||||
#define SYSCTL_PIN_PWM3 0x00000008 // PWM3 pin
|
||||
#define SYSCTL_PIN_PWM4 0x00000010 // PWM4 pin
|
||||
#define SYSCTL_PIN_PWM5 0x00000020 // PWM5 pin
|
||||
#define SYSCTL_PIN_PWM6 0x00000040 // PWM6 pin
|
||||
#define SYSCTL_PIN_PWM7 0x00000080 // PWM7 pin
|
||||
#define SYSCTL_PIN_C0MINUS 0x00000040 // C0- pin
|
||||
#define SYSCTL_PIN_C0PLUS 0x00000080 // C0+ pin
|
||||
#define SYSCTL_PIN_C0O 0x00000100 // C0o pin
|
||||
#define SYSCTL_PIN_C1MINUS 0x00000200 // C1- pin
|
||||
#define SYSCTL_PIN_C1PLUS 0x00000400 // C1+ pin
|
||||
#define SYSCTL_PIN_C1O 0x00000800 // C1o pin
|
||||
#define SYSCTL_PIN_C2MINUS 0x00001000 // C2- pin
|
||||
#define SYSCTL_PIN_C2PLUS 0x00002000 // C2+ pin
|
||||
#define SYSCTL_PIN_C2O 0x00004000 // C2o pin
|
||||
#define SYSCTL_PIN_MC_FAULT0 0x00008000 // MC0 Fault pin
|
||||
#define SYSCTL_PIN_ADC0 0x00010000 // ADC0 pin
|
||||
#define SYSCTL_PIN_ADC1 0x00020000 // ADC1 pin
|
||||
#define SYSCTL_PIN_ADC2 0x00040000 // ADC2 pin
|
||||
#define SYSCTL_PIN_ADC3 0x00080000 // ADC3 pin
|
||||
#define SYSCTL_PIN_ADC4 0x00100000 // ADC4 pin
|
||||
#define SYSCTL_PIN_ADC5 0x00200000 // ADC5 pin
|
||||
#define SYSCTL_PIN_ADC6 0x00400000 // ADC6 pin
|
||||
#define SYSCTL_PIN_ADC7 0x00800000 // ADC7 pin
|
||||
#define SYSCTL_PIN_CCP0 0x01000000 // CCP0 pin
|
||||
#define SYSCTL_PIN_CCP1 0x02000000 // CCP1 pin
|
||||
#define SYSCTL_PIN_CCP2 0x04000000 // CCP2 pin
|
||||
#define SYSCTL_PIN_CCP3 0x08000000 // CCP3 pin
|
||||
#define SYSCTL_PIN_CCP4 0x10000000 // CCP4 pin
|
||||
#define SYSCTL_PIN_CCP5 0x20000000 // CCP5 pin
|
||||
#define SYSCTL_PIN_32KHZ 0x80000000 // 32kHz pin
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are values that can be passed to the SysCtlLDOSet() API as
|
||||
// the ulVoltage value, or returned by the SysCtlLDOGet() API.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define SYSCTL_LDO_2_25V 0x00000005 // LDO output of 2.25V
|
||||
#define SYSCTL_LDO_2_30V 0x00000004 // LDO output of 2.30V
|
||||
#define SYSCTL_LDO_2_35V 0x00000003 // LDO output of 2.35V
|
||||
#define SYSCTL_LDO_2_40V 0x00000002 // LDO output of 2.40V
|
||||
#define SYSCTL_LDO_2_45V 0x00000001 // LDO output of 2.45V
|
||||
#define SYSCTL_LDO_2_50V 0x00000000 // LDO output of 2.50V
|
||||
#define SYSCTL_LDO_2_55V 0x0000001f // LDO output of 2.55V
|
||||
#define SYSCTL_LDO_2_60V 0x0000001e // LDO output of 2.60V
|
||||
#define SYSCTL_LDO_2_65V 0x0000001d // LDO output of 2.65V
|
||||
#define SYSCTL_LDO_2_70V 0x0000001c // LDO output of 2.70V
|
||||
#define SYSCTL_LDO_2_75V 0x0000001b // LDO output of 2.75V
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are values that can be passed to the SysCtlLDOConfigSet() API.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define SYSCTL_LDOCFG_ARST 0x00000001 // Allow LDO failure to reset
|
||||
#define SYSCTL_LDOCFG_NORST 0x00000000 // Do not reset on LDO failure
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are values that can be passed to the SysCtlIntEnable(),
|
||||
// SysCtlIntDisable(), and SysCtlIntClear() APIs, or returned in the bit mask
|
||||
// by the SysCtlIntStatus() API.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define SYSCTL_INT_MOSC_PUP 0x00000100 // MOSC power-up interrupt
|
||||
#define SYSCTL_INT_USBPLL_LOCK 0x00000080 // USB PLL lock interrupt
|
||||
#define SYSCTL_INT_PLL_LOCK 0x00000040 // PLL lock interrupt
|
||||
#define SYSCTL_INT_CUR_LIMIT 0x00000020 // Current limit interrupt
|
||||
#define SYSCTL_INT_IOSC_FAIL 0x00000010 // Internal oscillator failure int
|
||||
#define SYSCTL_INT_MOSC_FAIL 0x00000008 // Main oscillator failure int
|
||||
#define SYSCTL_INT_POR 0x00000004 // Power on reset interrupt
|
||||
#define SYSCTL_INT_BOR 0x00000002 // Brown out interrupt
|
||||
#define SYSCTL_INT_PLL_FAIL 0x00000001 // PLL failure interrupt
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are values that can be passed to the SysCtlResetCauseClear()
|
||||
// API or returned by the SysCtlResetCauseGet() API.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define SYSCTL_CAUSE_LDO 0x00000020 // LDO power not OK reset
|
||||
#define SYSCTL_CAUSE_WDOG1 0x00000020 // Watchdog 1 reset
|
||||
#define SYSCTL_CAUSE_SW 0x00000010 // Software reset
|
||||
#define SYSCTL_CAUSE_WDOG0 0x00000008 // Watchdog 0 reset
|
||||
#define SYSCTL_CAUSE_WDOG 0x00000008 // Watchdog reset
|
||||
#define SYSCTL_CAUSE_BOR 0x00000004 // Brown-out reset
|
||||
#define SYSCTL_CAUSE_POR 0x00000002 // Power on reset
|
||||
#define SYSCTL_CAUSE_EXT 0x00000001 // External reset
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are values that can be passed to the SysCtlBrownOutConfigSet()
|
||||
// API as the ulConfig parameter.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define SYSCTL_BOR_RESET 0x00000002 // Reset instead of interrupting
|
||||
#define SYSCTL_BOR_RESAMPLE 0x00000001 // Resample BOR before asserting
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are values that can be passed to the SysCtlPWMClockSet() API
|
||||
// as the ulConfig parameter, and can be returned by the SysCtlPWMClockGet()
|
||||
// API.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define SYSCTL_PWMDIV_1 0x00000000 // PWM clock is processor clock /1
|
||||
#define SYSCTL_PWMDIV_2 0x00100000 // PWM clock is processor clock /2
|
||||
#define SYSCTL_PWMDIV_4 0x00120000 // PWM clock is processor clock /4
|
||||
#define SYSCTL_PWMDIV_8 0x00140000 // PWM clock is processor clock /8
|
||||
#define SYSCTL_PWMDIV_16 0x00160000 // PWM clock is processor clock /16
|
||||
#define SYSCTL_PWMDIV_32 0x00180000 // PWM clock is processor clock /32
|
||||
#define SYSCTL_PWMDIV_64 0x001A0000 // PWM clock is processor clock /64
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are values that can be passed to the SysCtlADCSpeedSet() API
|
||||
// as the ulSpeed parameter, and can be returned by the SyCtlADCSpeedGet()
|
||||
// API.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define SYSCTL_ADCSPEED_1MSPS 0x00000F00 // 1,000,000 samples per second
|
||||
#define SYSCTL_ADCSPEED_500KSPS 0x00000A00 // 500,000 samples per second
|
||||
#define SYSCTL_ADCSPEED_250KSPS 0x00000500 // 250,000 samples per second
|
||||
#define SYSCTL_ADCSPEED_125KSPS 0x00000000 // 125,000 samples per second
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are values that can be passed to the SysCtlClockSet() API as
|
||||
// the ulConfig parameter.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define SYSCTL_SYSDIV_1 0x07800000 // Processor clock is osc/pll /1
|
||||
#define SYSCTL_SYSDIV_2 0x00C00000 // Processor clock is osc/pll /2
|
||||
#define SYSCTL_SYSDIV_3 0x01400000 // Processor clock is osc/pll /3
|
||||
#define SYSCTL_SYSDIV_4 0x01C00000 // Processor clock is osc/pll /4
|
||||
#define SYSCTL_SYSDIV_5 0x02400000 // Processor clock is osc/pll /5
|
||||
#define SYSCTL_SYSDIV_6 0x02C00000 // Processor clock is osc/pll /6
|
||||
#define SYSCTL_SYSDIV_7 0x03400000 // Processor clock is osc/pll /7
|
||||
#define SYSCTL_SYSDIV_8 0x03C00000 // Processor clock is osc/pll /8
|
||||
#define SYSCTL_SYSDIV_9 0x04400000 // Processor clock is osc/pll /9
|
||||
#define SYSCTL_SYSDIV_10 0x04C00000 // Processor clock is osc/pll /10
|
||||
#define SYSCTL_SYSDIV_11 0x05400000 // Processor clock is osc/pll /11
|
||||
#define SYSCTL_SYSDIV_12 0x05C00000 // Processor clock is osc/pll /12
|
||||
#define SYSCTL_SYSDIV_13 0x06400000 // Processor clock is osc/pll /13
|
||||
#define SYSCTL_SYSDIV_14 0x06C00000 // Processor clock is osc/pll /14
|
||||
#define SYSCTL_SYSDIV_15 0x07400000 // Processor clock is osc/pll /15
|
||||
#define SYSCTL_SYSDIV_16 0x07C00000 // Processor clock is osc/pll /16
|
||||
#define SYSCTL_SYSDIV_17 0x88400000 // Processor clock is osc/pll /17
|
||||
#define SYSCTL_SYSDIV_18 0x88C00000 // Processor clock is osc/pll /18
|
||||
#define SYSCTL_SYSDIV_19 0x89400000 // Processor clock is osc/pll /19
|
||||
#define SYSCTL_SYSDIV_20 0x89C00000 // Processor clock is osc/pll /20
|
||||
#define SYSCTL_SYSDIV_21 0x8A400000 // Processor clock is osc/pll /21
|
||||
#define SYSCTL_SYSDIV_22 0x8AC00000 // Processor clock is osc/pll /22
|
||||
#define SYSCTL_SYSDIV_23 0x8B400000 // Processor clock is osc/pll /23
|
||||
#define SYSCTL_SYSDIV_24 0x8BC00000 // Processor clock is osc/pll /24
|
||||
#define SYSCTL_SYSDIV_25 0x8C400000 // Processor clock is osc/pll /25
|
||||
#define SYSCTL_SYSDIV_26 0x8CC00000 // Processor clock is osc/pll /26
|
||||
#define SYSCTL_SYSDIV_27 0x8D400000 // Processor clock is osc/pll /27
|
||||
#define SYSCTL_SYSDIV_28 0x8DC00000 // Processor clock is osc/pll /28
|
||||
#define SYSCTL_SYSDIV_29 0x8E400000 // Processor clock is osc/pll /29
|
||||
#define SYSCTL_SYSDIV_30 0x8EC00000 // Processor clock is osc/pll /30
|
||||
#define SYSCTL_SYSDIV_31 0x8F400000 // Processor clock is osc/pll /31
|
||||
#define SYSCTL_SYSDIV_32 0x8FC00000 // Processor clock is osc/pll /32
|
||||
#define SYSCTL_SYSDIV_33 0x90400000 // Processor clock is osc/pll /33
|
||||
#define SYSCTL_SYSDIV_34 0x90C00000 // Processor clock is osc/pll /34
|
||||
#define SYSCTL_SYSDIV_35 0x91400000 // Processor clock is osc/pll /35
|
||||
#define SYSCTL_SYSDIV_36 0x91C00000 // Processor clock is osc/pll /36
|
||||
#define SYSCTL_SYSDIV_37 0x92400000 // Processor clock is osc/pll /37
|
||||
#define SYSCTL_SYSDIV_38 0x92C00000 // Processor clock is osc/pll /38
|
||||
#define SYSCTL_SYSDIV_39 0x93400000 // Processor clock is osc/pll /39
|
||||
#define SYSCTL_SYSDIV_40 0x93C00000 // Processor clock is osc/pll /40
|
||||
#define SYSCTL_SYSDIV_41 0x94400000 // Processor clock is osc/pll /41
|
||||
#define SYSCTL_SYSDIV_42 0x94C00000 // Processor clock is osc/pll /42
|
||||
#define SYSCTL_SYSDIV_43 0x95400000 // Processor clock is osc/pll /43
|
||||
#define SYSCTL_SYSDIV_44 0x95C00000 // Processor clock is osc/pll /44
|
||||
#define SYSCTL_SYSDIV_45 0x96400000 // Processor clock is osc/pll /45
|
||||
#define SYSCTL_SYSDIV_46 0x96C00000 // Processor clock is osc/pll /46
|
||||
#define SYSCTL_SYSDIV_47 0x97400000 // Processor clock is osc/pll /47
|
||||
#define SYSCTL_SYSDIV_48 0x97C00000 // Processor clock is osc/pll /48
|
||||
#define SYSCTL_SYSDIV_49 0x98400000 // Processor clock is osc/pll /49
|
||||
#define SYSCTL_SYSDIV_50 0x98C00000 // Processor clock is osc/pll /50
|
||||
#define SYSCTL_SYSDIV_51 0x99400000 // Processor clock is osc/pll /51
|
||||
#define SYSCTL_SYSDIV_52 0x99C00000 // Processor clock is osc/pll /52
|
||||
#define SYSCTL_SYSDIV_53 0x9A400000 // Processor clock is osc/pll /53
|
||||
#define SYSCTL_SYSDIV_54 0x9AC00000 // Processor clock is osc/pll /54
|
||||
#define SYSCTL_SYSDIV_55 0x9B400000 // Processor clock is osc/pll /55
|
||||
#define SYSCTL_SYSDIV_56 0x9BC00000 // Processor clock is osc/pll /56
|
||||
#define SYSCTL_SYSDIV_57 0x9C400000 // Processor clock is osc/pll /57
|
||||
#define SYSCTL_SYSDIV_58 0x9CC00000 // Processor clock is osc/pll /58
|
||||
#define SYSCTL_SYSDIV_59 0x9D400000 // Processor clock is osc/pll /59
|
||||
#define SYSCTL_SYSDIV_60 0x9DC00000 // Processor clock is osc/pll /60
|
||||
#define SYSCTL_SYSDIV_61 0x9E400000 // Processor clock is osc/pll /61
|
||||
#define SYSCTL_SYSDIV_62 0x9EC00000 // Processor clock is osc/pll /62
|
||||
#define SYSCTL_SYSDIV_63 0x9F400000 // Processor clock is osc/pll /63
|
||||
#define SYSCTL_SYSDIV_64 0x9FC00000 // Processor clock is osc/pll /64
|
||||
#define SYSCTL_SYSDIV_2_5 0xC1000000 // Processor clock is pll / 2.5
|
||||
#define SYSCTL_SYSDIV_3_5 0xC1800000 // Processor clock is pll / 3.5
|
||||
#define SYSCTL_SYSDIV_4_5 0xC2000000 // Processor clock is pll / 4.5
|
||||
#define SYSCTL_SYSDIV_5_5 0xC2800000 // Processor clock is pll / 5.5
|
||||
#define SYSCTL_SYSDIV_6_5 0xC3000000 // Processor clock is pll / 6.5
|
||||
#define SYSCTL_SYSDIV_7_5 0xC3800000 // Processor clock is pll / 7.5
|
||||
#define SYSCTL_SYSDIV_8_5 0xC4000000 // Processor clock is pll / 8.5
|
||||
#define SYSCTL_SYSDIV_9_5 0xC4800000 // Processor clock is pll / 9.5
|
||||
#define SYSCTL_SYSDIV_10_5 0xC5000000 // Processor clock is pll / 10.5
|
||||
#define SYSCTL_SYSDIV_11_5 0xC5800000 // Processor clock is pll / 11.5
|
||||
#define SYSCTL_SYSDIV_12_5 0xC6000000 // Processor clock is pll / 12.5
|
||||
#define SYSCTL_SYSDIV_13_5 0xC6800000 // Processor clock is pll / 13.5
|
||||
#define SYSCTL_SYSDIV_14_5 0xC7000000 // Processor clock is pll / 14.5
|
||||
#define SYSCTL_SYSDIV_15_5 0xC7800000 // Processor clock is pll / 15.5
|
||||
#define SYSCTL_SYSDIV_16_5 0xC8000000 // Processor clock is pll / 16.5
|
||||
#define SYSCTL_SYSDIV_17_5 0xC8800000 // Processor clock is pll / 17.5
|
||||
#define SYSCTL_SYSDIV_18_5 0xC9000000 // Processor clock is pll / 18.5
|
||||
#define SYSCTL_SYSDIV_19_5 0xC9800000 // Processor clock is pll / 19.5
|
||||
#define SYSCTL_SYSDIV_20_5 0xCA000000 // Processor clock is pll / 20.5
|
||||
#define SYSCTL_SYSDIV_21_5 0xCA800000 // Processor clock is pll / 21.5
|
||||
#define SYSCTL_SYSDIV_22_5 0xCB000000 // Processor clock is pll / 22.5
|
||||
#define SYSCTL_SYSDIV_23_5 0xCB800000 // Processor clock is pll / 23.5
|
||||
#define SYSCTL_SYSDIV_24_5 0xCC000000 // Processor clock is pll / 24.5
|
||||
#define SYSCTL_SYSDIV_25_5 0xCC800000 // Processor clock is pll / 25.5
|
||||
#define SYSCTL_SYSDIV_26_5 0xCD000000 // Processor clock is pll / 26.5
|
||||
#define SYSCTL_SYSDIV_27_5 0xCD800000 // Processor clock is pll / 27.5
|
||||
#define SYSCTL_SYSDIV_28_5 0xCE000000 // Processor clock is pll / 28.5
|
||||
#define SYSCTL_SYSDIV_29_5 0xCE800000 // Processor clock is pll / 29.5
|
||||
#define SYSCTL_SYSDIV_30_5 0xCF000000 // Processor clock is pll / 30.5
|
||||
#define SYSCTL_SYSDIV_31_5 0xCF800000 // Processor clock is pll / 31.5
|
||||
#define SYSCTL_SYSDIV_32_5 0xD0000000 // Processor clock is pll / 32.5
|
||||
#define SYSCTL_SYSDIV_33_5 0xD0800000 // Processor clock is pll / 33.5
|
||||
#define SYSCTL_SYSDIV_34_5 0xD1000000 // Processor clock is pll / 34.5
|
||||
#define SYSCTL_SYSDIV_35_5 0xD1800000 // Processor clock is pll / 35.5
|
||||
#define SYSCTL_SYSDIV_36_5 0xD2000000 // Processor clock is pll / 36.5
|
||||
#define SYSCTL_SYSDIV_37_5 0xD2800000 // Processor clock is pll / 37.5
|
||||
#define SYSCTL_SYSDIV_38_5 0xD3000000 // Processor clock is pll / 38.5
|
||||
#define SYSCTL_SYSDIV_39_5 0xD3800000 // Processor clock is pll / 39.5
|
||||
#define SYSCTL_SYSDIV_40_5 0xD4000000 // Processor clock is pll / 40.5
|
||||
#define SYSCTL_SYSDIV_41_5 0xD4800000 // Processor clock is pll / 41.5
|
||||
#define SYSCTL_SYSDIV_42_5 0xD5000000 // Processor clock is pll / 42.5
|
||||
#define SYSCTL_SYSDIV_43_5 0xD5800000 // Processor clock is pll / 43.5
|
||||
#define SYSCTL_SYSDIV_44_5 0xD6000000 // Processor clock is pll / 44.5
|
||||
#define SYSCTL_SYSDIV_45_5 0xD6800000 // Processor clock is pll / 45.5
|
||||
#define SYSCTL_SYSDIV_46_5 0xD7000000 // Processor clock is pll / 46.5
|
||||
#define SYSCTL_SYSDIV_47_5 0xD7800000 // Processor clock is pll / 47.5
|
||||
#define SYSCTL_SYSDIV_48_5 0xD8000000 // Processor clock is pll / 48.5
|
||||
#define SYSCTL_SYSDIV_49_5 0xD8800000 // Processor clock is pll / 49.5
|
||||
#define SYSCTL_SYSDIV_50_5 0xD9000000 // Processor clock is pll / 50.5
|
||||
#define SYSCTL_SYSDIV_51_5 0xD9800000 // Processor clock is pll / 51.5
|
||||
#define SYSCTL_SYSDIV_52_5 0xDA000000 // Processor clock is pll / 52.5
|
||||
#define SYSCTL_SYSDIV_53_5 0xDA800000 // Processor clock is pll / 53.5
|
||||
#define SYSCTL_SYSDIV_54_5 0xDB000000 // Processor clock is pll / 54.5
|
||||
#define SYSCTL_SYSDIV_55_5 0xDB800000 // Processor clock is pll / 55.5
|
||||
#define SYSCTL_SYSDIV_56_5 0xDC000000 // Processor clock is pll / 56.5
|
||||
#define SYSCTL_SYSDIV_57_5 0xDC800000 // Processor clock is pll / 57.5
|
||||
#define SYSCTL_SYSDIV_58_5 0xDD000000 // Processor clock is pll / 58.5
|
||||
#define SYSCTL_SYSDIV_59_5 0xDD800000 // Processor clock is pll / 59.5
|
||||
#define SYSCTL_SYSDIV_60_5 0xDE000000 // Processor clock is pll / 60.5
|
||||
#define SYSCTL_SYSDIV_61_5 0xDE800000 // Processor clock is pll / 61.5
|
||||
#define SYSCTL_SYSDIV_62_5 0xDF000000 // Processor clock is pll / 62.5
|
||||
#define SYSCTL_SYSDIV_63_5 0xDF800000 // Processor clock is pll / 63.5
|
||||
#define SYSCTL_USE_PLL 0x00000000 // System clock is the PLL clock
|
||||
#define SYSCTL_USE_OSC 0x00003800 // System clock is the osc clock
|
||||
#define SYSCTL_XTAL_1MHZ 0x00000000 // External crystal is 1MHz
|
||||
#define SYSCTL_XTAL_1_84MHZ 0x00000040 // External crystal is 1.8432MHz
|
||||
#define SYSCTL_XTAL_2MHZ 0x00000080 // External crystal is 2MHz
|
||||
#define SYSCTL_XTAL_2_45MHZ 0x000000C0 // External crystal is 2.4576MHz
|
||||
#define SYSCTL_XTAL_3_57MHZ 0x00000100 // External crystal is 3.579545MHz
|
||||
#define SYSCTL_XTAL_3_68MHZ 0x00000140 // External crystal is 3.6864MHz
|
||||
#define SYSCTL_XTAL_4MHZ 0x00000180 // External crystal is 4MHz
|
||||
#define SYSCTL_XTAL_4_09MHZ 0x000001C0 // External crystal is 4.096MHz
|
||||
#define SYSCTL_XTAL_4_91MHZ 0x00000200 // External crystal is 4.9152MHz
|
||||
#define SYSCTL_XTAL_5MHZ 0x00000240 // External crystal is 5MHz
|
||||
#define SYSCTL_XTAL_5_12MHZ 0x00000280 // External crystal is 5.12MHz
|
||||
#define SYSCTL_XTAL_6MHZ 0x000002C0 // External crystal is 6MHz
|
||||
#define SYSCTL_XTAL_6_14MHZ 0x00000300 // External crystal is 6.144MHz
|
||||
#define SYSCTL_XTAL_7_37MHZ 0x00000340 // External crystal is 7.3728MHz
|
||||
#define SYSCTL_XTAL_8MHZ 0x00000380 // External crystal is 8MHz
|
||||
#define SYSCTL_XTAL_8_19MHZ 0x000003C0 // External crystal is 8.192MHz
|
||||
#define SYSCTL_XTAL_10MHZ 0x00000400 // External crystal is 10 MHz
|
||||
#define SYSCTL_XTAL_12MHZ 0x00000440 // External crystal is 12 MHz
|
||||
#define SYSCTL_XTAL_12_2MHZ 0x00000480 // External crystal is 12.288 MHz
|
||||
#define SYSCTL_XTAL_13_5MHZ 0x000004C0 // External crystal is 13.56 MHz
|
||||
#define SYSCTL_XTAL_14_3MHZ 0x00000500 // External crystal is 14.31818 MHz
|
||||
#define SYSCTL_XTAL_16MHZ 0x00000540 // External crystal is 16 MHz
|
||||
#define SYSCTL_XTAL_16_3MHZ 0x00000580 // External crystal is 16.384 MHz
|
||||
#define SYSCTL_XTAL_18MHZ 0x000005C0 // External crystal is 18.0 MHz
|
||||
#define SYSCTL_XTAL_20MHZ 0x00000600 // External crystal is 20.0 MHz
|
||||
#define SYSCTL_XTAL_24MHZ 0x00000640 // External crystal is 24.0 MHz
|
||||
#define SYSCTL_XTAL_25MHZ 0x00000680 // External crystal is 25.0 MHz
|
||||
#define SYSCTL_OSC_MAIN 0x00000000 // Osc source is main osc
|
||||
#define SYSCTL_OSC_INT 0x00000010 // Osc source is int. osc
|
||||
#define SYSCTL_OSC_INT4 0x00000020 // Osc source is int. osc /4
|
||||
#define SYSCTL_OSC_INT30 0x00000030 // Osc source is int. 30 KHz
|
||||
#define SYSCTL_OSC_EXT4_19 0x80000028 // Osc source is ext. 4.19 MHz
|
||||
#define SYSCTL_OSC_EXT32 0x80000038 // Osc source is ext. 32 KHz
|
||||
#define SYSCTL_INT_OSC_DIS 0x00000002 // Disable internal oscillator
|
||||
#define SYSCTL_MAIN_OSC_DIS 0x00000001 // Disable main oscillator
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are values that can be passed to the SysCtlDeepSleepClockSet()
|
||||
// API as the ulConfig parameter.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define SYSCTL_DSLP_DIV_1 0x00000000 // Deep-sleep clock is osc /1
|
||||
#define SYSCTL_DSLP_DIV_2 0x00800000 // Deep-sleep clock is osc /2
|
||||
#define SYSCTL_DSLP_DIV_3 0x01000000 // Deep-sleep clock is osc /3
|
||||
#define SYSCTL_DSLP_DIV_4 0x01800000 // Deep-sleep clock is osc /4
|
||||
#define SYSCTL_DSLP_DIV_5 0x02000000 // Deep-sleep clock is osc /5
|
||||
#define SYSCTL_DSLP_DIV_6 0x02800000 // Deep-sleep clock is osc /6
|
||||
#define SYSCTL_DSLP_DIV_7 0x03000000 // Deep-sleep clock is osc /7
|
||||
#define SYSCTL_DSLP_DIV_8 0x03800000 // Deep-sleep clock is osc /8
|
||||
#define SYSCTL_DSLP_DIV_9 0x04000000 // Deep-sleep clock is osc /9
|
||||
#define SYSCTL_DSLP_DIV_10 0x04800000 // Deep-sleep clock is osc /10
|
||||
#define SYSCTL_DSLP_DIV_11 0x05000000 // Deep-sleep clock is osc /11
|
||||
#define SYSCTL_DSLP_DIV_12 0x05800000 // Deep-sleep clock is osc /12
|
||||
#define SYSCTL_DSLP_DIV_13 0x06000000 // Deep-sleep clock is osc /13
|
||||
#define SYSCTL_DSLP_DIV_14 0x06800000 // Deep-sleep clock is osc /14
|
||||
#define SYSCTL_DSLP_DIV_15 0x07000000 // Deep-sleep clock is osc /15
|
||||
#define SYSCTL_DSLP_DIV_16 0x07800000 // Deep-sleep clock is osc /16
|
||||
#define SYSCTL_DSLP_DIV_17 0x08000000 // Deep-sleep clock is osc /17
|
||||
#define SYSCTL_DSLP_DIV_18 0x08800000 // Deep-sleep clock is osc /18
|
||||
#define SYSCTL_DSLP_DIV_19 0x09000000 // Deep-sleep clock is osc /19
|
||||
#define SYSCTL_DSLP_DIV_20 0x09800000 // Deep-sleep clock is osc /20
|
||||
#define SYSCTL_DSLP_DIV_21 0x0A000000 // Deep-sleep clock is osc /21
|
||||
#define SYSCTL_DSLP_DIV_22 0x0A800000 // Deep-sleep clock is osc /22
|
||||
#define SYSCTL_DSLP_DIV_23 0x0B000000 // Deep-sleep clock is osc /23
|
||||
#define SYSCTL_DSLP_DIV_24 0x0B800000 // Deep-sleep clock is osc /24
|
||||
#define SYSCTL_DSLP_DIV_25 0x0C000000 // Deep-sleep clock is osc /25
|
||||
#define SYSCTL_DSLP_DIV_26 0x0C800000 // Deep-sleep clock is osc /26
|
||||
#define SYSCTL_DSLP_DIV_27 0x0D000000 // Deep-sleep clock is osc /27
|
||||
#define SYSCTL_DSLP_DIV_28 0x0D800000 // Deep-sleep clock is osc /28
|
||||
#define SYSCTL_DSLP_DIV_29 0x0E000000 // Deep-sleep clock is osc /29
|
||||
#define SYSCTL_DSLP_DIV_30 0x0E800000 // Deep-sleep clock is osc /30
|
||||
#define SYSCTL_DSLP_DIV_31 0x0F000000 // Deep-sleep clock is osc /31
|
||||
#define SYSCTL_DSLP_DIV_32 0x0F800000 // Deep-sleep clock is osc /32
|
||||
#define SYSCTL_DSLP_DIV_33 0x10000000 // Deep-sleep clock is osc /33
|
||||
#define SYSCTL_DSLP_DIV_34 0x10800000 // Deep-sleep clock is osc /34
|
||||
#define SYSCTL_DSLP_DIV_35 0x11000000 // Deep-sleep clock is osc /35
|
||||
#define SYSCTL_DSLP_DIV_36 0x11800000 // Deep-sleep clock is osc /36
|
||||
#define SYSCTL_DSLP_DIV_37 0x12000000 // Deep-sleep clock is osc /37
|
||||
#define SYSCTL_DSLP_DIV_38 0x12800000 // Deep-sleep clock is osc /38
|
||||
#define SYSCTL_DSLP_DIV_39 0x13000000 // Deep-sleep clock is osc /39
|
||||
#define SYSCTL_DSLP_DIV_40 0x13800000 // Deep-sleep clock is osc /40
|
||||
#define SYSCTL_DSLP_DIV_41 0x14000000 // Deep-sleep clock is osc /41
|
||||
#define SYSCTL_DSLP_DIV_42 0x14800000 // Deep-sleep clock is osc /42
|
||||
#define SYSCTL_DSLP_DIV_43 0x15000000 // Deep-sleep clock is osc /43
|
||||
#define SYSCTL_DSLP_DIV_44 0x15800000 // Deep-sleep clock is osc /44
|
||||
#define SYSCTL_DSLP_DIV_45 0x16000000 // Deep-sleep clock is osc /45
|
||||
#define SYSCTL_DSLP_DIV_46 0x16800000 // Deep-sleep clock is osc /46
|
||||
#define SYSCTL_DSLP_DIV_47 0x17000000 // Deep-sleep clock is osc /47
|
||||
#define SYSCTL_DSLP_DIV_48 0x17800000 // Deep-sleep clock is osc /48
|
||||
#define SYSCTL_DSLP_DIV_49 0x18000000 // Deep-sleep clock is osc /49
|
||||
#define SYSCTL_DSLP_DIV_50 0x18800000 // Deep-sleep clock is osc /50
|
||||
#define SYSCTL_DSLP_DIV_51 0x19000000 // Deep-sleep clock is osc /51
|
||||
#define SYSCTL_DSLP_DIV_52 0x19800000 // Deep-sleep clock is osc /52
|
||||
#define SYSCTL_DSLP_DIV_53 0x1A000000 // Deep-sleep clock is osc /53
|
||||
#define SYSCTL_DSLP_DIV_54 0x1A800000 // Deep-sleep clock is osc /54
|
||||
#define SYSCTL_DSLP_DIV_55 0x1B000000 // Deep-sleep clock is osc /55
|
||||
#define SYSCTL_DSLP_DIV_56 0x1B800000 // Deep-sleep clock is osc /56
|
||||
#define SYSCTL_DSLP_DIV_57 0x1C000000 // Deep-sleep clock is osc /57
|
||||
#define SYSCTL_DSLP_DIV_58 0x1C800000 // Deep-sleep clock is osc /58
|
||||
#define SYSCTL_DSLP_DIV_59 0x1D000000 // Deep-sleep clock is osc /59
|
||||
#define SYSCTL_DSLP_DIV_60 0x1D800000 // Deep-sleep clock is osc /60
|
||||
#define SYSCTL_DSLP_DIV_61 0x1E000000 // Deep-sleep clock is osc /61
|
||||
#define SYSCTL_DSLP_DIV_62 0x1E800000 // Deep-sleep clock is osc /62
|
||||
#define SYSCTL_DSLP_DIV_63 0x1F000000 // Deep-sleep clock is osc /63
|
||||
#define SYSCTL_DSLP_DIV_64 0x1F800000 // Deep-sleep clock is osc /64
|
||||
#define SYSCTL_DSLP_OSC_MAIN 0x00000000 // Osc source is main osc
|
||||
#define SYSCTL_DSLP_OSC_INT 0x00000010 // Osc source is int. osc
|
||||
#define SYSCTL_DSLP_OSC_INT30 0x00000030 // Osc source is int. 30 KHz
|
||||
#define SYSCTL_DSLP_OSC_EXT32 0x00000070 // Osc source is ext. 32 KHz
|
||||
#define SYSCTL_DSLP_PIOSC_PD 0x00000002 // Power down PIOSC in deep-sleep
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Prototypes for the APIs.
|
||||
//
|
||||
//*****************************************************************************
|
||||
extern unsigned long SysCtlSRAMSizeGet(void);
|
||||
extern unsigned long SysCtlFlashSizeGet(void);
|
||||
extern tBoolean SysCtlPinPresent(unsigned long ulPin);
|
||||
extern tBoolean SysCtlPeripheralPresent(unsigned long ulPeripheral);
|
||||
extern tBoolean SysCtlPeripheralReady(unsigned long ulPeripheral);
|
||||
extern void SysCtlPeripheralPowerOn(unsigned long ulPeripheral);
|
||||
extern void SysCtlPeripheralPowerOff(unsigned long ulPeripheral);
|
||||
extern void SysCtlPeripheralReset(unsigned long ulPeripheral);
|
||||
extern void SysCtlPeripheralEnable(unsigned long ulPeripheral);
|
||||
extern void SysCtlPeripheralDisable(unsigned long ulPeripheral);
|
||||
extern void SysCtlPeripheralSleepEnable(unsigned long ulPeripheral);
|
||||
extern void SysCtlPeripheralSleepDisable(unsigned long ulPeripheral);
|
||||
extern void SysCtlPeripheralDeepSleepEnable(unsigned long ulPeripheral);
|
||||
extern void SysCtlPeripheralDeepSleepDisable(unsigned long ulPeripheral);
|
||||
extern void SysCtlPeripheralClockGating(tBoolean bEnable);
|
||||
extern void SysCtlIntRegister(void (*pfnHandler)(void));
|
||||
extern void SysCtlIntUnregister(void);
|
||||
extern void SysCtlIntEnable(unsigned long ulInts);
|
||||
extern void SysCtlIntDisable(unsigned long ulInts);
|
||||
extern void SysCtlIntClear(unsigned long ulInts);
|
||||
extern unsigned long SysCtlIntStatus(tBoolean bMasked);
|
||||
extern void SysCtlLDOSet(unsigned long ulVoltage);
|
||||
extern unsigned long SysCtlLDOGet(void);
|
||||
extern void SysCtlLDOConfigSet(unsigned long ulConfig);
|
||||
extern void SysCtlReset(void);
|
||||
extern void SysCtlSleep(void);
|
||||
extern void SysCtlDeepSleep(void);
|
||||
extern unsigned long SysCtlResetCauseGet(void);
|
||||
extern void SysCtlResetCauseClear(unsigned long ulCauses);
|
||||
extern void SysCtlBrownOutConfigSet(unsigned long ulConfig,
|
||||
unsigned long ulDelay);
|
||||
extern void SysCtlDelay(unsigned long ulCount);
|
||||
extern void SysCtlMOSCConfigSet(unsigned long ulConfig);
|
||||
extern unsigned long SysCtlPIOSCCalibrate(unsigned long ulType);
|
||||
extern void SysCtlClockSet(unsigned long ulConfig);
|
||||
extern unsigned long SysCtlClockGet(void);
|
||||
extern void SysCtlDeepSleepClockSet(unsigned long ulConfig);
|
||||
extern void SysCtlPWMClockSet(unsigned long ulConfig);
|
||||
extern unsigned long SysCtlPWMClockGet(void);
|
||||
extern void SysCtlADCSpeedSet(unsigned long ulSpeed);
|
||||
extern unsigned long SysCtlADCSpeedGet(void);
|
||||
extern void SysCtlIOSCVerificationSet(tBoolean bEnable);
|
||||
extern void SysCtlMOSCVerificationSet(tBoolean bEnable);
|
||||
extern void SysCtlPLLVerificationSet(tBoolean bEnable);
|
||||
extern void SysCtlClkVerificationClear(void);
|
||||
extern void SysCtlGPIOAHBEnable(unsigned long ulGPIOPeripheral);
|
||||
extern void SysCtlGPIOAHBDisable(unsigned long ulGPIOPeripheral);
|
||||
extern void SysCtlUSBPLLEnable(void);
|
||||
extern void SysCtlUSBPLLDisable(void);
|
||||
extern unsigned long SysCtlI2SMClkSet(unsigned long ulInputClock,
|
||||
unsigned long ulMClk);
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Mark the end of the C bindings section for C++ compilers.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif // __SYSCTL_H__
|
File diff suppressed because it is too large
Load Diff
|
@ -0,0 +1,275 @@
|
|||
//*****************************************************************************
|
||||
//
|
||||
// uart.h - Defines and Macros for the UART.
|
||||
//
|
||||
// Copyright (c) 2005-2013 Texas Instruments Incorporated. All rights reserved.
|
||||
// Software License Agreement
|
||||
//
|
||||
// Redistribution and use in source and binary forms, with or without
|
||||
// modification, are permitted provided that the following conditions
|
||||
// are met:
|
||||
//
|
||||
// Redistributions of source code must retain the above copyright
|
||||
// notice, this list of conditions and the following disclaimer.
|
||||
//
|
||||
// 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.
|
||||
//
|
||||
// Neither the name of Texas Instruments Incorporated 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
|
||||
// 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.
|
||||
//
|
||||
// This is part of revision 10636 of the Stellaris Peripheral Driver Library.
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
#ifndef __UART_H__
|
||||
#define __UART_H__
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// If building with a C++ compiler, make all of the definitions in this header
|
||||
// have a C binding.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#ifdef __cplusplus
|
||||
extern "C"
|
||||
{
|
||||
#endif
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Values that can be passed to UARTIntEnable, UARTIntDisable, and UARTIntClear
|
||||
// as the ulIntFlags parameter, and returned from UARTIntStatus.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define UART_INT_9BIT 0x1000 // 9-bit address match interrupt
|
||||
#define UART_INT_OE 0x400 // Overrun Error Interrupt Mask
|
||||
#define UART_INT_BE 0x200 // Break Error Interrupt Mask
|
||||
#define UART_INT_PE 0x100 // Parity Error Interrupt Mask
|
||||
#define UART_INT_FE 0x080 // Framing Error Interrupt Mask
|
||||
#define UART_INT_RT 0x040 // Receive Timeout Interrupt Mask
|
||||
#define UART_INT_TX 0x020 // Transmit Interrupt Mask
|
||||
#define UART_INT_RX 0x010 // Receive Interrupt Mask
|
||||
#define UART_INT_DSR 0x008 // DSR Modem Interrupt Mask
|
||||
#define UART_INT_DCD 0x004 // DCD Modem Interrupt Mask
|
||||
#define UART_INT_CTS 0x002 // CTS Modem Interrupt Mask
|
||||
#define UART_INT_RI 0x001 // RI Modem Interrupt Mask
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Values that can be passed to UARTConfigSetExpClk as the ulConfig parameter
|
||||
// and returned by UARTConfigGetExpClk in the pulConfig parameter.
|
||||
// Additionally, the UART_CONFIG_PAR_* subset can be passed to
|
||||
// UARTParityModeSet as the ulParity parameter, and are returned by
|
||||
// UARTParityModeGet.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define UART_CONFIG_WLEN_MASK 0x00000060 // Mask for extracting word length
|
||||
#define UART_CONFIG_WLEN_8 0x00000060 // 8 bit data
|
||||
#define UART_CONFIG_WLEN_7 0x00000040 // 7 bit data
|
||||
#define UART_CONFIG_WLEN_6 0x00000020 // 6 bit data
|
||||
#define UART_CONFIG_WLEN_5 0x00000000 // 5 bit data
|
||||
#define UART_CONFIG_STOP_MASK 0x00000008 // Mask for extracting stop bits
|
||||
#define UART_CONFIG_STOP_ONE 0x00000000 // One stop bit
|
||||
#define UART_CONFIG_STOP_TWO 0x00000008 // Two stop bits
|
||||
#define UART_CONFIG_PAR_MASK 0x00000086 // Mask for extracting parity
|
||||
#define UART_CONFIG_PAR_NONE 0x00000000 // No parity
|
||||
#define UART_CONFIG_PAR_EVEN 0x00000006 // Even parity
|
||||
#define UART_CONFIG_PAR_ODD 0x00000002 // Odd parity
|
||||
#define UART_CONFIG_PAR_ONE 0x00000082 // Parity bit is one
|
||||
#define UART_CONFIG_PAR_ZERO 0x00000086 // Parity bit is zero
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Values that can be passed to UARTFIFOLevelSet as the ulTxLevel parameter and
|
||||
// returned by UARTFIFOLevelGet in the pulTxLevel.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define UART_FIFO_TX1_8 0x00000000 // Transmit interrupt at 1/8 Full
|
||||
#define UART_FIFO_TX2_8 0x00000001 // Transmit interrupt at 1/4 Full
|
||||
#define UART_FIFO_TX4_8 0x00000002 // Transmit interrupt at 1/2 Full
|
||||
#define UART_FIFO_TX6_8 0x00000003 // Transmit interrupt at 3/4 Full
|
||||
#define UART_FIFO_TX7_8 0x00000004 // Transmit interrupt at 7/8 Full
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Values that can be passed to UARTFIFOLevelSet as the ulRxLevel parameter and
|
||||
// returned by UARTFIFOLevelGet in the pulRxLevel.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define UART_FIFO_RX1_8 0x00000000 // Receive interrupt at 1/8 Full
|
||||
#define UART_FIFO_RX2_8 0x00000008 // Receive interrupt at 1/4 Full
|
||||
#define UART_FIFO_RX4_8 0x00000010 // Receive interrupt at 1/2 Full
|
||||
#define UART_FIFO_RX6_8 0x00000018 // Receive interrupt at 3/4 Full
|
||||
#define UART_FIFO_RX7_8 0x00000020 // Receive interrupt at 7/8 Full
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Values that can be passed to UARTDMAEnable() and UARTDMADisable().
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define UART_DMA_ERR_RXSTOP 0x00000004 // Stop DMA receive if UART error
|
||||
#define UART_DMA_TX 0x00000002 // Enable DMA for transmit
|
||||
#define UART_DMA_RX 0x00000001 // Enable DMA for receive
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Values returned from UARTRxErrorGet().
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define UART_RXERROR_OVERRUN 0x00000008
|
||||
#define UART_RXERROR_BREAK 0x00000004
|
||||
#define UART_RXERROR_PARITY 0x00000002
|
||||
#define UART_RXERROR_FRAMING 0x00000001
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Values that can be passed to UARTHandshakeOutputsSet() or returned from
|
||||
// UARTHandshakeOutputGet().
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define UART_OUTPUT_RTS 0x00000800
|
||||
#define UART_OUTPUT_DTR 0x00000400
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Values that can be returned from UARTHandshakeInputsGet().
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define UART_INPUT_RI 0x00000100
|
||||
#define UART_INPUT_DCD 0x00000004
|
||||
#define UART_INPUT_DSR 0x00000002
|
||||
#define UART_INPUT_CTS 0x00000001
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Values that can be passed to UARTFlowControl() or returned from
|
||||
// UARTFlowControlGet().
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define UART_FLOWCONTROL_TX 0x00008000
|
||||
#define UART_FLOWCONTROL_RX 0x00004000
|
||||
#define UART_FLOWCONTROL_NONE 0x00000000
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Values that can be passed to UARTTxIntModeSet() or returned from
|
||||
// UARTTxIntModeGet().
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define UART_TXINT_MODE_FIFO 0x00000000
|
||||
#define UART_TXINT_MODE_EOT 0x00000010
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Values that can be passed to UARTClockSourceSet() or returned from
|
||||
// UARTClockSourceGet().
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define UART_CLOCK_SYSTEM 0x00000000
|
||||
#define UART_CLOCK_PIOSC 0x00000005
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// API Function prototypes
|
||||
//
|
||||
//*****************************************************************************
|
||||
extern void UARTParityModeSet(unsigned long ulBase, unsigned long ulParity);
|
||||
extern unsigned long UARTParityModeGet(unsigned long ulBase);
|
||||
extern void UARTFIFOLevelSet(unsigned long ulBase, unsigned long ulTxLevel,
|
||||
unsigned long ulRxLevel);
|
||||
extern void UARTFIFOLevelGet(unsigned long ulBase, unsigned long *pulTxLevel,
|
||||
unsigned long *pulRxLevel);
|
||||
extern void UARTConfigSetExpClk(unsigned long ulBase, unsigned long ulUARTClk,
|
||||
unsigned long ulBaud, unsigned long ulConfig);
|
||||
extern void UARTConfigGetExpClk(unsigned long ulBase, unsigned long ulUARTClk,
|
||||
unsigned long *pulBaud,
|
||||
unsigned long *pulConfig);
|
||||
extern void UARTEnable(unsigned long ulBase);
|
||||
extern void UARTDisable(unsigned long ulBase);
|
||||
extern void UARTFIFOEnable(unsigned long ulBase);
|
||||
extern void UARTFIFODisable(unsigned long ulBase);
|
||||
extern void UARTEnableSIR(unsigned long ulBase, tBoolean bLowPower);
|
||||
extern void UARTDisableSIR(unsigned long ulBase);
|
||||
extern tBoolean UARTCharsAvail(unsigned long ulBase);
|
||||
extern tBoolean UARTSpaceAvail(unsigned long ulBase);
|
||||
extern long UARTCharGetNonBlocking(unsigned long ulBase);
|
||||
extern long UARTCharGet(unsigned long ulBase);
|
||||
extern tBoolean UARTCharPutNonBlocking(unsigned long ulBase,
|
||||
unsigned char ucData);
|
||||
extern void UARTCharPut(unsigned long ulBase, unsigned char ucData);
|
||||
extern void UARTBreakCtl(unsigned long ulBase, tBoolean bBreakState);
|
||||
extern tBoolean UARTBusy(unsigned long ulBase);
|
||||
extern void UARTIntRegister(unsigned long ulBase, void(*pfnHandler)(void));
|
||||
extern void UARTIntUnregister(unsigned long ulBase);
|
||||
extern void UARTIntEnable(unsigned long ulBase, unsigned long ulIntFlags);
|
||||
extern void UARTIntDisable(unsigned long ulBase, unsigned long ulIntFlags);
|
||||
extern unsigned long UARTIntStatus(unsigned long ulBase, tBoolean bMasked);
|
||||
extern void UARTIntClear(unsigned long ulBase, unsigned long ulIntFlags);
|
||||
extern void UARTDMAEnable(unsigned long ulBase, unsigned long ulDMAFlags);
|
||||
extern void UARTDMADisable(unsigned long ulBase, unsigned long ulDMAFlags);
|
||||
extern unsigned long UARTRxErrorGet(unsigned long ulBase);
|
||||
extern void UARTRxErrorClear(unsigned long ulBase);
|
||||
extern void UARTSmartCardEnable(unsigned long ulBase);
|
||||
extern void UARTSmartCardDisable(unsigned long ulBase);
|
||||
extern void UARTModemControlSet(unsigned long ulBase,
|
||||
unsigned long ulControl);
|
||||
extern void UARTModemControlClear(unsigned long ulBase,
|
||||
unsigned long ulControl);
|
||||
extern unsigned long UARTModemControlGet(unsigned long ulBase);
|
||||
extern unsigned long UARTModemStatusGet(unsigned long ulBase);
|
||||
extern void UARTFlowControlSet(unsigned long ulBase, unsigned long ulMode);
|
||||
extern unsigned long UARTFlowControlGet(unsigned long ulBase);
|
||||
extern void UARTTxIntModeSet(unsigned long ulBase, unsigned long ulMode);
|
||||
extern unsigned long UARTTxIntModeGet(unsigned long ulBase);
|
||||
extern void UARTClockSourceSet(unsigned long ulBase, unsigned long ulSource);
|
||||
extern unsigned long UARTClockSourceGet(unsigned long ulBase);
|
||||
extern void UART9BitEnable(unsigned long ulBase);
|
||||
extern void UART9BitDisable(unsigned long ulBase);
|
||||
extern void UART9BitAddrSet(unsigned long ulBase, unsigned char ucAddr,
|
||||
unsigned char ucMask);
|
||||
extern void UART9BitAddrSend(unsigned long ulBase, unsigned char ucAddr);
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Several UART APIs have been renamed, with the original function name being
|
||||
// deprecated. These defines provide backward compatibility.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#ifndef DEPRECATED
|
||||
#include "driverlib/sysctl.h"
|
||||
#define UARTConfigSet(a, b, c) \
|
||||
UARTConfigSetExpClk(a, SysCtlClockGet(), b, c)
|
||||
#define UARTConfigGet(a, b, c) \
|
||||
UARTConfigGetExpClk(a, SysCtlClockGet(), b, c)
|
||||
#define UARTCharNonBlockingGet(a) \
|
||||
UARTCharGetNonBlocking(a)
|
||||
#define UARTCharNonBlockingPut(a, b) \
|
||||
UARTCharPutNonBlocking(a, b)
|
||||
#endif
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Mark the end of the C bindings section for C++ compilers.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif // __UART_H__
|
|
@ -0,0 +1,192 @@
|
|||
//*****************************************************************************
|
||||
//
|
||||
// hw_gpio.h - Defines and Macros for GPIO hardware.
|
||||
//
|
||||
// Copyright (c) 2005-2013 Texas Instruments Incorporated. All rights reserved.
|
||||
// Software License Agreement
|
||||
//
|
||||
// Redistribution and use in source and binary forms, with or without
|
||||
// modification, are permitted provided that the following conditions
|
||||
// are met:
|
||||
//
|
||||
// Redistributions of source code must retain the above copyright
|
||||
// notice, this list of conditions and the following disclaimer.
|
||||
//
|
||||
// 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.
|
||||
//
|
||||
// Neither the name of Texas Instruments Incorporated 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
|
||||
// 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.
|
||||
//
|
||||
// This is part of revision 10636 of the Stellaris Firmware Development Package.
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
#ifndef __HW_GPIO_H__
|
||||
#define __HW_GPIO_H__
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the GPIO register offsets.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define GPIO_O_DATA 0x00000000 // GPIO Data
|
||||
#define GPIO_O_DIR 0x00000400 // GPIO Direction
|
||||
#define GPIO_O_IS 0x00000404 // GPIO Interrupt Sense
|
||||
#define GPIO_O_IBE 0x00000408 // GPIO Interrupt Both Edges
|
||||
#define GPIO_O_IEV 0x0000040C // GPIO Interrupt Event
|
||||
#define GPIO_O_IM 0x00000410 // GPIO Interrupt Mask
|
||||
#define GPIO_O_RIS 0x00000414 // GPIO Raw Interrupt Status
|
||||
#define GPIO_O_MIS 0x00000418 // GPIO Masked Interrupt Status
|
||||
#define GPIO_O_ICR 0x0000041C // GPIO Interrupt Clear
|
||||
#define GPIO_O_AFSEL 0x00000420 // GPIO Alternate Function Select
|
||||
#define GPIO_O_DR2R 0x00000500 // GPIO 2-mA Drive Select
|
||||
#define GPIO_O_DR4R 0x00000504 // GPIO 4-mA Drive Select
|
||||
#define GPIO_O_DR8R 0x00000508 // GPIO 8-mA Drive Select
|
||||
#define GPIO_O_ODR 0x0000050C // GPIO Open Drain Select
|
||||
#define GPIO_O_PUR 0x00000510 // GPIO Pull-Up Select
|
||||
#define GPIO_O_PDR 0x00000514 // GPIO Pull-Down Select
|
||||
#define GPIO_O_SLR 0x00000518 // GPIO Slew Rate Control Select
|
||||
#define GPIO_O_DEN 0x0000051C // GPIO Digital Enable
|
||||
#define GPIO_O_LOCK 0x00000520 // GPIO Lock
|
||||
#define GPIO_O_CR 0x00000524 // GPIO Commit
|
||||
#define GPIO_O_AMSEL 0x00000528 // GPIO Analog Mode Select
|
||||
#define GPIO_O_PCTL 0x0000052C // GPIO Port Control
|
||||
#define GPIO_O_ADCCTL 0x00000530 // GPIO ADC Control
|
||||
#define GPIO_O_DMACTL 0x00000534 // GPIO DMA Control
|
||||
#define GPIO_O_SI 0x00000538 // GPIO Select Interrupt
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the GPIO_O_IM register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define GPIO_IM_GPIO_M 0x000000FF // GPIO Interrupt Mask Enable
|
||||
#define GPIO_IM_GPIO_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the GPIO_O_RIS register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define GPIO_RIS_GPIO_M 0x000000FF // GPIO Interrupt Raw Status
|
||||
#define GPIO_RIS_GPIO_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the GPIO_O_MIS register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define GPIO_MIS_GPIO_M 0x000000FF // GPIO Masked Interrupt Status
|
||||
#define GPIO_MIS_GPIO_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the GPIO_O_ICR register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define GPIO_ICR_GPIO_M 0x000000FF // GPIO Interrupt Clear
|
||||
#define GPIO_ICR_GPIO_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the GPIO_O_LOCK register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define GPIO_LOCK_M 0xFFFFFFFF // GPIO Lock
|
||||
#define GPIO_LOCK_UNLOCKED 0x00000000 // The GPIOCR register is unlocked
|
||||
// and may be modified
|
||||
#define GPIO_LOCK_LOCKED 0x00000001 // The GPIOCR register is locked
|
||||
// and may not be modified
|
||||
#define GPIO_LOCK_KEY 0x1ACCE551 // Unlocks the GPIO_CR register
|
||||
#define GPIO_LOCK_KEY_DD 0x4C4F434B // Unlocks the GPIO_CR register on
|
||||
// DustDevil-class devices and
|
||||
// later
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the GPIO_O_SI register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define GPIO_SI_SUM 0x00000001 // Summary Interrupt
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following definitions are deprecated.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#ifndef DEPRECATED
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are deprecated defines for the GPIO register offsets.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define GPIO_O_PeriphID4 0x00000FD0
|
||||
#define GPIO_O_PeriphID5 0x00000FD4
|
||||
#define GPIO_O_PeriphID6 0x00000FD8
|
||||
#define GPIO_O_PeriphID7 0x00000FDC
|
||||
#define GPIO_O_PeriphID0 0x00000FE0
|
||||
#define GPIO_O_PeriphID1 0x00000FE4
|
||||
#define GPIO_O_PeriphID2 0x00000FE8
|
||||
#define GPIO_O_PeriphID3 0x00000FEC
|
||||
#define GPIO_O_PCellID0 0x00000FF0
|
||||
#define GPIO_O_PCellID1 0x00000FF4
|
||||
#define GPIO_O_PCellID2 0x00000FF8
|
||||
#define GPIO_O_PCellID3 0x00000FFC
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are deprecated defines for the GPIO Register reset values.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define GPIO_RV_DEN 0x000000FF // Digital input enable reg RV
|
||||
#define GPIO_RV_PUR 0x000000FF // Pull up select reg RV
|
||||
#define GPIO_RV_DR2R 0x000000FF // 2ma drive select reg RV
|
||||
#define GPIO_RV_PCellID1 0x000000F0
|
||||
#define GPIO_RV_PCellID3 0x000000B1
|
||||
#define GPIO_RV_PeriphID0 0x00000061
|
||||
#define GPIO_RV_PeriphID1 0x00000010
|
||||
#define GPIO_RV_PCellID0 0x0000000D
|
||||
#define GPIO_RV_PCellID2 0x00000005
|
||||
#define GPIO_RV_PeriphID2 0x00000004
|
||||
#define GPIO_RV_LOCK 0x00000001 // Lock register RV
|
||||
#define GPIO_RV_PeriphID7 0x00000000
|
||||
#define GPIO_RV_PDR 0x00000000 // Pull down select reg RV
|
||||
#define GPIO_RV_IC 0x00000000 // Interrupt clear reg RV
|
||||
#define GPIO_RV_SLR 0x00000000 // Slew rate control enable reg RV
|
||||
#define GPIO_RV_ODR 0x00000000 // Open drain select reg RV
|
||||
#define GPIO_RV_IBE 0x00000000 // Interrupt both edges reg RV
|
||||
#define GPIO_RV_AFSEL 0x00000000 // Mode control select reg RV
|
||||
#define GPIO_RV_IS 0x00000000 // Interrupt sense reg RV
|
||||
#define GPIO_RV_IM 0x00000000 // Interrupt mask reg RV
|
||||
#define GPIO_RV_PeriphID4 0x00000000
|
||||
#define GPIO_RV_PeriphID5 0x00000000
|
||||
#define GPIO_RV_DR8R 0x00000000 // 8ma drive select reg RV
|
||||
#define GPIO_RV_RIS 0x00000000 // Raw interrupt status reg RV
|
||||
#define GPIO_RV_DR4R 0x00000000 // 4ma drive select reg RV
|
||||
#define GPIO_RV_IEV 0x00000000 // Intterupt event reg RV
|
||||
#define GPIO_RV_DIR 0x00000000 // Data direction reg RV
|
||||
#define GPIO_RV_PeriphID6 0x00000000
|
||||
#define GPIO_RV_PeriphID3 0x00000000
|
||||
#define GPIO_RV_DATA 0x00000000 // Data register reset value
|
||||
#define GPIO_RV_MIS 0x00000000 // Masked interrupt status reg RV
|
||||
|
||||
#endif
|
||||
|
||||
#endif // __HW_GPIO_H__
|
|
@ -0,0 +1,217 @@
|
|||
//*****************************************************************************
|
||||
//
|
||||
// hw_ints.h - Macros that define the interrupt assignment on Stellaris.
|
||||
//
|
||||
// Copyright (c) 2005-2013 Texas Instruments Incorporated. All rights reserved.
|
||||
// Software License Agreement
|
||||
//
|
||||
// Redistribution and use in source and binary forms, with or without
|
||||
// modification, are permitted provided that the following conditions
|
||||
// are met:
|
||||
//
|
||||
// Redistributions of source code must retain the above copyright
|
||||
// notice, this list of conditions and the following disclaimer.
|
||||
//
|
||||
// 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.
|
||||
//
|
||||
// Neither the name of Texas Instruments Incorporated 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
|
||||
// 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.
|
||||
//
|
||||
// This is part of revision 10636 of the Stellaris Firmware Development Package.
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
#ifndef __HW_INTS_H__
|
||||
#define __HW_INTS_H__
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the fault assignments.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define FAULT_NMI 2 // NMI fault
|
||||
#define FAULT_HARD 3 // Hard fault
|
||||
#define FAULT_MPU 4 // MPU fault
|
||||
#define FAULT_BUS 5 // Bus fault
|
||||
#define FAULT_USAGE 6 // Usage fault
|
||||
#define FAULT_SVCALL 11 // SVCall
|
||||
#define FAULT_DEBUG 12 // Debug monitor
|
||||
#define FAULT_PENDSV 14 // PendSV
|
||||
#define FAULT_SYSTICK 15 // System Tick
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the interrupt assignments.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define INT_GPIOA 16 // GPIO Port A
|
||||
#define INT_GPIOB 17 // GPIO Port B
|
||||
#define INT_GPIOC 18 // GPIO Port C
|
||||
#define INT_GPIOD 19 // GPIO Port D
|
||||
#define INT_GPIOE 20 // GPIO Port E
|
||||
#define INT_UART0 21 // UART0 Rx and Tx
|
||||
#define INT_UART1 22 // UART1 Rx and Tx
|
||||
#define INT_SSI0 23 // SSI0 Rx and Tx
|
||||
#define INT_I2C0 24 // I2C0 Master and Slave
|
||||
#define INT_PWM0_FAULT 25 // PWM0 Fault
|
||||
#define INT_PWM0_0 26 // PWM0 Generator 0
|
||||
#define INT_PWM0_1 27 // PWM0 Generator 1
|
||||
#define INT_PWM0_2 28 // PWM0 Generator 2
|
||||
#define INT_QEI0 29 // Quadrature Encoder 0
|
||||
#define INT_ADC0SS0 30 // ADC0 Sequence 0
|
||||
#define INT_ADC0SS1 31 // ADC0 Sequence 1
|
||||
#define INT_ADC0SS2 32 // ADC0 Sequence 2
|
||||
#define INT_ADC0SS3 33 // ADC0 Sequence 3
|
||||
#define INT_WATCHDOG 34 // Watchdog timer
|
||||
#define INT_TIMER0A 35 // Timer 0 subtimer A
|
||||
#define INT_TIMER0B 36 // Timer 0 subtimer B
|
||||
#define INT_TIMER1A 37 // Timer 1 subtimer A
|
||||
#define INT_TIMER1B 38 // Timer 1 subtimer B
|
||||
#define INT_TIMER2A 39 // Timer 2 subtimer A
|
||||
#define INT_TIMER2B 40 // Timer 2 subtimer B
|
||||
#define INT_COMP0 41 // Analog Comparator 0
|
||||
#define INT_COMP1 42 // Analog Comparator 1
|
||||
#define INT_COMP2 43 // Analog Comparator 2
|
||||
#define INT_SYSCTL 44 // System Control (PLL, OSC, BO)
|
||||
#define INT_FLASH 45 // FLASH Control
|
||||
#define INT_GPIOF 46 // GPIO Port F
|
||||
#define INT_GPIOG 47 // GPIO Port G
|
||||
#define INT_GPIOH 48 // GPIO Port H
|
||||
#define INT_UART2 49 // UART2 Rx and Tx
|
||||
#define INT_SSI1 50 // SSI1 Rx and Tx
|
||||
#define INT_TIMER3A 51 // Timer 3 subtimer A
|
||||
#define INT_TIMER3B 52 // Timer 3 subtimer B
|
||||
#define INT_I2C1 53 // I2C1 Master and Slave
|
||||
#define INT_QEI1 54 // Quadrature Encoder 1
|
||||
#define INT_CAN0 55 // CAN0
|
||||
#define INT_CAN1 56 // CAN1
|
||||
#define INT_CAN2 57 // CAN2
|
||||
#define INT_ETH 58 // Ethernet
|
||||
#define INT_HIBERNATE 59 // Hibernation module
|
||||
#define INT_USB0 60 // USB 0 Controller
|
||||
#define INT_PWM0_3 61 // PWM0 Generator 3
|
||||
#define INT_UDMA 62 // uDMA controller
|
||||
#define INT_UDMAERR 63 // uDMA Error
|
||||
#define INT_ADC1SS0 64 // ADC1 Sequence 0
|
||||
#define INT_ADC1SS1 65 // ADC1 Sequence 1
|
||||
#define INT_ADC1SS2 66 // ADC1 Sequence 2
|
||||
#define INT_ADC1SS3 67 // ADC1 Sequence 3
|
||||
#define INT_I2S0 68 // I2S0
|
||||
#define INT_EPI0 69 // EPI0
|
||||
#define INT_GPIOJ 70 // GPIO Port J
|
||||
#define INT_GPIOK 71 // GPIO Port K
|
||||
#define INT_GPIOL 72 // GPIO Port L
|
||||
#define INT_SSI2 73 // SSI2
|
||||
#define INT_SSI3 74 // SSI3
|
||||
#define INT_UART3 75 // UART3
|
||||
#define INT_UART4 76 // UART4
|
||||
#define INT_UART5 77 // UART5
|
||||
#define INT_UART6 78 // UART6
|
||||
#define INT_UART7 79 // UART7
|
||||
#define INT_I2C2 84 // I2C2
|
||||
#define INT_I2C3 85 // I2C3
|
||||
#define INT_TIMER4A 86 // Timer 4A
|
||||
#define INT_TIMER4B 87 // Timer 4B
|
||||
#define INT_TIMER5A 108 // Timer 5A
|
||||
#define INT_TIMER5B 109 // Timer 5B
|
||||
#define INT_WTIMER0A 110 // Wide Timer 0A
|
||||
#define INT_WTIMER0B 111 // Wide Timer 0B
|
||||
#define INT_WTIMER1A 112 // Wide Timer 1A
|
||||
#define INT_WTIMER1B 113 // Wide Timer 1B
|
||||
#define INT_WTIMER2A 114 // Wide Timer 2A
|
||||
#define INT_WTIMER2B 115 // Wide Timer 2B
|
||||
#define INT_WTIMER3A 116 // Wide Timer 3A
|
||||
#define INT_WTIMER3B 117 // Wide Timer 3B
|
||||
#define INT_WTIMER4A 118 // Wide Timer 4A
|
||||
#define INT_WTIMER4B 119 // Wide Timer 4B
|
||||
#define INT_WTIMER5A 120 // Wide Timer 5A
|
||||
#define INT_WTIMER5B 121 // Wide Timer 5B
|
||||
#define INT_SYSEXC 122 // System Exception (imprecise)
|
||||
#define INT_PECI0 123 // PECI 0
|
||||
#define INT_LPC0 124 // LPC 0
|
||||
#define INT_I2C4 125 // I2C4
|
||||
#define INT_I2C5 126 // I2C5
|
||||
#define INT_GPIOM 127 // GPIO Port M
|
||||
#define INT_GPION 128 // GPIO Port N
|
||||
#define INT_FAN0 130 // FAN 0
|
||||
#define INT_GPIOP0 132 // GPIO Port P (Summary or P0)
|
||||
#define INT_GPIOP1 133 // GPIO Port P1
|
||||
#define INT_GPIOP2 134 // GPIO Port P2
|
||||
#define INT_GPIOP3 135 // GPIO Port P3
|
||||
#define INT_GPIOP4 136 // GPIO Port P4
|
||||
#define INT_GPIOP5 137 // GPIO Port P5
|
||||
#define INT_GPIOP6 138 // GPIO Port P6
|
||||
#define INT_GPIOP7 139 // GPIO Port P7
|
||||
#define INT_GPIOQ0 140 // GPIO Port Q (Summary or Q0)
|
||||
#define INT_GPIOQ1 141 // GPIO Port Q1
|
||||
#define INT_GPIOQ2 142 // GPIO Port Q2
|
||||
#define INT_GPIOQ3 143 // GPIO Port Q3
|
||||
#define INT_GPIOQ4 144 // GPIO Port Q4
|
||||
#define INT_GPIOQ5 145 // GPIO Port Q5
|
||||
#define INT_GPIOQ6 146 // GPIO Port Q6
|
||||
#define INT_GPIOQ7 147 // GPIO Port Q7
|
||||
#define INT_PWM1_0 150 // PWM1 Generator 0
|
||||
#define INT_PWM1_1 151 // PWM1 Generator 1
|
||||
#define INT_PWM1_2 152 // PWM1 Generator 2
|
||||
#define INT_PWM1_3 153 // PWM1 Generator 3
|
||||
#define INT_PWM1_FAULT 154 // PWM1 Fault
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the total number of interrupts.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define NUM_INTERRUPTS 155
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the total number of priority levels.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define NUM_PRIORITY 8
|
||||
#define NUM_PRIORITY_BITS 3
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following definitions are deprecated.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#ifndef DEPRECATED
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are deprecated defines for the interrupt assignments.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define INT_SSI 23 // SSI Rx and Tx
|
||||
#define INT_I2C 24 // I2C Master and Slave
|
||||
#define INT_PWM_FAULT 25 // PWM Fault
|
||||
#define INT_PWM0 26 // PWM Generator 0
|
||||
#define INT_PWM1 27 // PWM Generator 1
|
||||
#define INT_PWM2 28 // PWM Generator 2
|
||||
#define INT_QEI 29 // Quadrature Encoder
|
||||
#define INT_ADC0 30 // ADC Sequence 0
|
||||
#define INT_ADC1 31 // ADC Sequence 1
|
||||
#define INT_ADC2 32 // ADC Sequence 2
|
||||
#define INT_ADC3 33 // ADC Sequence 3
|
||||
#define INT_PWM3 61 // PWM Generator 3
|
||||
|
||||
#endif
|
||||
|
||||
#endif // __HW_INTS_H__
|
|
@ -0,0 +1,167 @@
|
|||
//*****************************************************************************
|
||||
//
|
||||
// hw_memmap.h - Macros defining the memory map of Stellaris.
|
||||
//
|
||||
// Copyright (c) 2005-2013 Texas Instruments Incorporated. All rights reserved.
|
||||
// Software License Agreement
|
||||
//
|
||||
// Redistribution and use in source and binary forms, with or without
|
||||
// modification, are permitted provided that the following conditions
|
||||
// are met:
|
||||
//
|
||||
// Redistributions of source code must retain the above copyright
|
||||
// notice, this list of conditions and the following disclaimer.
|
||||
//
|
||||
// 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.
|
||||
//
|
||||
// Neither the name of Texas Instruments Incorporated 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
|
||||
// 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.
|
||||
//
|
||||
// This is part of revision 10636 of the Stellaris Firmware Development Package.
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
#ifndef __HW_MEMMAP_H__
|
||||
#define __HW_MEMMAP_H__
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the base address of the memories and
|
||||
// peripherals.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define FLASH_BASE 0x00000000 // FLASH memory
|
||||
#define SRAM_BASE 0x20000000 // SRAM memory
|
||||
#define WATCHDOG0_BASE 0x40000000 // Watchdog0
|
||||
#define WATCHDOG1_BASE 0x40001000 // Watchdog1
|
||||
#define GPIO_PORTA_BASE 0x40004000 // GPIO Port A
|
||||
#define GPIO_PORTB_BASE 0x40005000 // GPIO Port B
|
||||
#define GPIO_PORTC_BASE 0x40006000 // GPIO Port C
|
||||
#define GPIO_PORTD_BASE 0x40007000 // GPIO Port D
|
||||
#define SSI0_BASE 0x40008000 // SSI0
|
||||
#define SSI1_BASE 0x40009000 // SSI1
|
||||
#define SSI2_BASE 0x4000A000 // SSI2
|
||||
#define SSI3_BASE 0x4000B000 // SSI3
|
||||
#define UART0_BASE 0x4000C000 // UART0
|
||||
#define UART1_BASE 0x4000D000 // UART1
|
||||
#define UART2_BASE 0x4000E000 // UART2
|
||||
#define UART3_BASE 0x4000F000 // UART3
|
||||
#define UART4_BASE 0x40010000 // UART4
|
||||
#define UART5_BASE 0x40011000 // UART5
|
||||
#define UART6_BASE 0x40012000 // UART6
|
||||
#define UART7_BASE 0x40013000 // UART7
|
||||
#define I2C0_MASTER_BASE 0x40020000 // I2C0 Master
|
||||
#define I2C0_SLAVE_BASE 0x40020800 // I2C0 Slave
|
||||
#define I2C1_MASTER_BASE 0x40021000 // I2C1 Master
|
||||
#define I2C1_SLAVE_BASE 0x40021800 // I2C1 Slave
|
||||
#define I2C2_MASTER_BASE 0x40022000 // I2C2 Master
|
||||
#define I2C2_SLAVE_BASE 0x40022800 // I2C2 Slave
|
||||
#define I2C3_MASTER_BASE 0x40023000 // I2C3 Master
|
||||
#define I2C3_SLAVE_BASE 0x40023800 // I2C3 Slave
|
||||
#define GPIO_PORTE_BASE 0x40024000 // GPIO Port E
|
||||
#define GPIO_PORTF_BASE 0x40025000 // GPIO Port F
|
||||
#define GPIO_PORTG_BASE 0x40026000 // GPIO Port G
|
||||
#define GPIO_PORTH_BASE 0x40027000 // GPIO Port H
|
||||
#define PWM0_BASE 0x40028000 // Pulse Width Modulator (PWM)
|
||||
#define PWM1_BASE 0x40029000 // Pulse Width Modulator (PWM)
|
||||
#define QEI0_BASE 0x4002C000 // QEI0
|
||||
#define QEI1_BASE 0x4002D000 // QEI1
|
||||
#define TIMER0_BASE 0x40030000 // Timer0
|
||||
#define TIMER1_BASE 0x40031000 // Timer1
|
||||
#define TIMER2_BASE 0x40032000 // Timer2
|
||||
#define TIMER3_BASE 0x40033000 // Timer3
|
||||
#define TIMER4_BASE 0x40034000 // Timer4
|
||||
#define TIMER5_BASE 0x40035000 // Timer5
|
||||
#define WTIMER0_BASE 0x40036000 // Wide Timer0
|
||||
#define WTIMER1_BASE 0x40037000 // Wide Timer1
|
||||
#define ADC0_BASE 0x40038000 // ADC0
|
||||
#define ADC1_BASE 0x40039000 // ADC1
|
||||
#define COMP_BASE 0x4003C000 // Analog comparators
|
||||
#define GPIO_PORTJ_BASE 0x4003D000 // GPIO Port J
|
||||
#define CAN0_BASE 0x40040000 // CAN0
|
||||
#define CAN1_BASE 0x40041000 // CAN1
|
||||
#define CAN2_BASE 0x40042000 // CAN2
|
||||
#define ETH_BASE 0x40048000 // Ethernet
|
||||
#define MAC_BASE 0x40048000 // Ethernet
|
||||
#define WTIMER2_BASE 0x4004C000 // Wide Timer2
|
||||
#define WTIMER3_BASE 0x4004D000 // Wide Timer3
|
||||
#define WTIMER4_BASE 0x4004E000 // Wide Timer4
|
||||
#define WTIMER5_BASE 0x4004F000 // Wide Timer5
|
||||
#define USB0_BASE 0x40050000 // USB 0 Controller
|
||||
#define I2S0_BASE 0x40054000 // I2S0
|
||||
#define GPIO_PORTA_AHB_BASE 0x40058000 // GPIO Port A (high speed)
|
||||
#define GPIO_PORTB_AHB_BASE 0x40059000 // GPIO Port B (high speed)
|
||||
#define GPIO_PORTC_AHB_BASE 0x4005A000 // GPIO Port C (high speed)
|
||||
#define GPIO_PORTD_AHB_BASE 0x4005B000 // GPIO Port D (high speed)
|
||||
#define GPIO_PORTE_AHB_BASE 0x4005C000 // GPIO Port E (high speed)
|
||||
#define GPIO_PORTF_AHB_BASE 0x4005D000 // GPIO Port F (high speed)
|
||||
#define GPIO_PORTG_AHB_BASE 0x4005E000 // GPIO Port G (high speed)
|
||||
#define GPIO_PORTH_AHB_BASE 0x4005F000 // GPIO Port H (high speed)
|
||||
#define GPIO_PORTJ_AHB_BASE 0x40060000 // GPIO Port J (high speed)
|
||||
#define GPIO_PORTK_BASE 0x40061000 // GPIO Port K
|
||||
#define GPIO_PORTL_BASE 0x40062000 // GPIO Port L
|
||||
#define GPIO_PORTM_BASE 0x40063000 // GPIO Port M
|
||||
#define GPIO_PORTN_BASE 0x40064000 // GPIO Port N
|
||||
#define GPIO_PORTP_BASE 0x40065000 // GPIO Port P
|
||||
#define GPIO_PORTQ_BASE 0x40066000 // GPIO Port Q
|
||||
#define LPC0_BASE 0x40080000 // Low Pin Count Interface (LPC)
|
||||
#define FAN0_BASE 0x40084000 // Fan Control (FAN)
|
||||
#define EEPROM_BASE 0x400AF000 // EEPROM memory
|
||||
#define PECI0_BASE 0x400B0000 // Platform Environment Control
|
||||
// Interface (PECI)
|
||||
#define I2C4_MASTER_BASE 0x400C0000 // I2C4 Master
|
||||
#define I2C4_SLAVE_BASE 0x400C0800 // I2C4 Slave
|
||||
#define I2C5_MASTER_BASE 0x400C1000 // I2C5 Master
|
||||
#define I2C5_SLAVE_BASE 0x400C1800 // I2C5 Slave
|
||||
#define EPI0_BASE 0x400D0000 // EPI0
|
||||
#define SYSEXC_BASE 0x400F9000 // System Exception Module
|
||||
#define HIB_BASE 0x400FC000 // Hibernation Module
|
||||
#define FLASH_CTRL_BASE 0x400FD000 // FLASH Controller
|
||||
#define SYSCTL_BASE 0x400FE000 // System Control
|
||||
#define UDMA_BASE 0x400FF000 // uDMA Controller
|
||||
#define ITM_BASE 0xE0000000 // Instrumentation Trace Macrocell
|
||||
#define DWT_BASE 0xE0001000 // Data Watchpoint and Trace
|
||||
#define FPB_BASE 0xE0002000 // FLASH Patch and Breakpoint
|
||||
#define NVIC_BASE 0xE000E000 // Nested Vectored Interrupt Ctrl
|
||||
#define TPIU_BASE 0xE0040000 // Trace Port Interface Unit
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following definitions are deprecated.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#ifndef DEPRECATED
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are deprecated defines for the base address of the memories
|
||||
// and peripherals.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define WATCHDOG_BASE 0x40000000 // Watchdog
|
||||
#define SSI_BASE 0x40008000 // SSI
|
||||
#define I2C_MASTER_BASE 0x40020000 // I2C Master
|
||||
#define I2C_SLAVE_BASE 0x40020800 // I2C Slave
|
||||
#define PWM_BASE 0x40028000 // PWM
|
||||
#define QEI_BASE 0x4002C000 // QEI
|
||||
#define ADC_BASE 0x40038000 // ADC
|
||||
|
||||
#endif
|
||||
|
||||
#endif // __HW_MEMMAP_H__
|
File diff suppressed because it is too large
Load Diff
File diff suppressed because it is too large
Load Diff
|
@ -0,0 +1,212 @@
|
|||
//*****************************************************************************
|
||||
//
|
||||
// hw_types.h - Common types and macros.
|
||||
//
|
||||
// Copyright (c) 2005-2013 Texas Instruments Incorporated. All rights reserved.
|
||||
// Software License Agreement
|
||||
//
|
||||
// Redistribution and use in source and binary forms, with or without
|
||||
// modification, are permitted provided that the following conditions
|
||||
// are met:
|
||||
//
|
||||
// Redistributions of source code must retain the above copyright
|
||||
// notice, this list of conditions and the following disclaimer.
|
||||
//
|
||||
// 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.
|
||||
//
|
||||
// Neither the name of Texas Instruments Incorporated 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
|
||||
// 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.
|
||||
//
|
||||
// This is part of revision 10636 of the Stellaris Firmware Development Package.
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
#ifndef __HW_TYPES_H__
|
||||
#define __HW_TYPES_H__
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Define a boolean type, and values for true and false.
|
||||
//
|
||||
//*****************************************************************************
|
||||
typedef unsigned char tBoolean;
|
||||
|
||||
#ifndef true
|
||||
#define true 1
|
||||
#endif
|
||||
|
||||
#ifndef false
|
||||
#define false 0
|
||||
#endif
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Macros for hardware access, both direct and via the bit-band region.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define HWREG(x) \
|
||||
(*((volatile unsigned long *)(x)))
|
||||
#define HWREGH(x) \
|
||||
(*((volatile unsigned short *)(x)))
|
||||
#define HWREGB(x) \
|
||||
(*((volatile unsigned char *)(x)))
|
||||
#define HWREGBITW(x, b) \
|
||||
HWREG(((unsigned long)(x) & 0xF0000000) | 0x02000000 | \
|
||||
(((unsigned long)(x) & 0x000FFFFF) << 5) | ((b) << 2))
|
||||
#define HWREGBITH(x, b) \
|
||||
HWREGH(((unsigned long)(x) & 0xF0000000) | 0x02000000 | \
|
||||
(((unsigned long)(x) & 0x000FFFFF) << 5) | ((b) << 2))
|
||||
#define HWREGBITB(x, b) \
|
||||
HWREGB(((unsigned long)(x) & 0xF0000000) | 0x02000000 | \
|
||||
(((unsigned long)(x) & 0x000FFFFF) << 5) | ((b) << 2))
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Helper Macros for determining silicon revisions, etc.
|
||||
//
|
||||
// These macros will be used by Driverlib at "run-time" to create necessary
|
||||
// conditional code blocks that will allow a single version of the Driverlib
|
||||
// "binary" code to support multiple(all) Stellaris silicon revisions.
|
||||
//
|
||||
// It is expected that these macros will be used inside of a standard 'C'
|
||||
// conditional block of code, e.g.
|
||||
//
|
||||
// if(CLASS_IS_SANDSTORM)
|
||||
// {
|
||||
// do some Sandstorm-class specific code here.
|
||||
// }
|
||||
//
|
||||
// By default, these macros will be defined as run-time checks of the
|
||||
// appropriate register(s) to allow creation of run-time conditional code
|
||||
// blocks for a common DriverLib across the entire Stellaris family.
|
||||
//
|
||||
// However, if code-space optimization is required, these macros can be "hard-
|
||||
// coded" for a specific version of Stellaris silicon. Many compilers will
|
||||
// then detect the "hard-coded" conditionals, and appropriately optimize the
|
||||
// code blocks, eliminating any "unreachable" code. This would result in
|
||||
// a smaller Driverlib, thus producing a smaller final application size, but
|
||||
// at the cost of limiting the Driverlib binary to a specific Stellaris
|
||||
// silicon revision.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#ifndef CLASS_IS_SANDSTORM
|
||||
#define CLASS_IS_SANDSTORM \
|
||||
(((HWREG(SYSCTL_DID0) & SYSCTL_DID0_VER_M) == SYSCTL_DID0_VER_0) || \
|
||||
((HWREG(SYSCTL_DID0) & (SYSCTL_DID0_VER_M | SYSCTL_DID0_CLASS_M)) == \
|
||||
(SYSCTL_DID0_VER_1 | SYSCTL_DID0_CLASS_SANDSTORM)))
|
||||
#endif
|
||||
|
||||
#ifndef CLASS_IS_FURY
|
||||
#define CLASS_IS_FURY \
|
||||
((HWREG(SYSCTL_DID0) & (SYSCTL_DID0_VER_M | SYSCTL_DID0_CLASS_M)) == \
|
||||
(SYSCTL_DID0_VER_1 | SYSCTL_DID0_CLASS_FURY))
|
||||
#endif
|
||||
|
||||
#ifndef CLASS_IS_DUSTDEVIL
|
||||
#define CLASS_IS_DUSTDEVIL \
|
||||
((HWREG(SYSCTL_DID0) & (SYSCTL_DID0_VER_M | SYSCTL_DID0_CLASS_M)) == \
|
||||
(SYSCTL_DID0_VER_1 | SYSCTL_DID0_CLASS_DUSTDEVIL))
|
||||
#endif
|
||||
|
||||
#ifndef CLASS_IS_TEMPEST
|
||||
#define CLASS_IS_TEMPEST \
|
||||
((HWREG(SYSCTL_DID0) & (SYSCTL_DID0_VER_M | SYSCTL_DID0_CLASS_M)) == \
|
||||
(SYSCTL_DID0_VER_1 | SYSCTL_DID0_CLASS_TEMPEST))
|
||||
#endif
|
||||
|
||||
#ifndef CLASS_IS_FIRESTORM
|
||||
#define CLASS_IS_FIRESTORM \
|
||||
((HWREG(SYSCTL_DID0) & (SYSCTL_DID0_VER_M | SYSCTL_DID0_CLASS_M)) == \
|
||||
(SYSCTL_DID0_VER_1 | SYSCTL_DID0_CLASS_FIRESTORM))
|
||||
#endif
|
||||
|
||||
#ifndef REVISION_IS_A0
|
||||
#define REVISION_IS_A0 \
|
||||
((HWREG(SYSCTL_DID0) & (SYSCTL_DID0_MAJ_M | SYSCTL_DID0_MIN_M)) == \
|
||||
(SYSCTL_DID0_MAJ_REVA | SYSCTL_DID0_MIN_0))
|
||||
#endif
|
||||
|
||||
#ifndef REVISION_IS_A1
|
||||
#define REVISION_IS_A1 \
|
||||
((HWREG(SYSCTL_DID0) & (SYSCTL_DID0_MAJ_M | SYSCTL_DID0_MIN_M)) == \
|
||||
(SYSCTL_DID0_MAJ_REVA | SYSCTL_DID0_MIN_0))
|
||||
#endif
|
||||
|
||||
#ifndef REVISION_IS_A2
|
||||
#define REVISION_IS_A2 \
|
||||
((HWREG(SYSCTL_DID0) & (SYSCTL_DID0_MAJ_M | SYSCTL_DID0_MIN_M)) == \
|
||||
(SYSCTL_DID0_MAJ_REVA | SYSCTL_DID0_MIN_2))
|
||||
#endif
|
||||
|
||||
#ifndef REVISION_IS_B0
|
||||
#define REVISION_IS_B0 \
|
||||
((HWREG(SYSCTL_DID0) & (SYSCTL_DID0_MAJ_M | SYSCTL_DID0_MIN_M)) == \
|
||||
(SYSCTL_DID0_MAJ_REVB | SYSCTL_DID0_MIN_0))
|
||||
#endif
|
||||
|
||||
#ifndef REVISION_IS_B1
|
||||
#define REVISION_IS_B1 \
|
||||
((HWREG(SYSCTL_DID0) & (SYSCTL_DID0_MAJ_M | SYSCTL_DID0_MIN_M)) == \
|
||||
(SYSCTL_DID0_MAJ_REVB | SYSCTL_DID0_MIN_1))
|
||||
#endif
|
||||
|
||||
#ifndef REVISION_IS_C0
|
||||
#define REVISION_IS_C0 \
|
||||
((HWREG(SYSCTL_DID0) & (SYSCTL_DID0_MAJ_M | SYSCTL_DID0_MIN_M)) == \
|
||||
(SYSCTL_DID0_MAJ_REVC | SYSCTL_DID0_MIN_0))
|
||||
#endif
|
||||
|
||||
#ifndef REVISION_IS_C1
|
||||
#define REVISION_IS_C1 \
|
||||
((HWREG(SYSCTL_DID0) & (SYSCTL_DID0_MAJ_M | SYSCTL_DID0_MIN_M)) == \
|
||||
(SYSCTL_DID0_MAJ_REVC | SYSCTL_DID0_MIN_1))
|
||||
#endif
|
||||
|
||||
#ifndef REVISION_IS_C2
|
||||
#define REVISION_IS_C2 \
|
||||
((HWREG(SYSCTL_DID0) & (SYSCTL_DID0_MAJ_M | SYSCTL_DID0_MIN_M)) == \
|
||||
(SYSCTL_DID0_MAJ_REVC | SYSCTL_DID0_MIN_2))
|
||||
#endif
|
||||
|
||||
#ifndef REVISION_IS_C3
|
||||
#define REVISION_IS_C3 \
|
||||
((HWREG(SYSCTL_DID0) & (SYSCTL_DID0_MAJ_M | SYSCTL_DID0_MIN_M)) == \
|
||||
(SYSCTL_DID0_MAJ_REVC | SYSCTL_DID0_MIN_3))
|
||||
#endif
|
||||
|
||||
#ifndef REVISION_IS_C5
|
||||
#define REVISION_IS_C5 \
|
||||
((HWREG(SYSCTL_DID0) & (SYSCTL_DID0_MAJ_M | SYSCTL_DID0_MIN_M)) == \
|
||||
(SYSCTL_DID0_MAJ_REVC | SYSCTL_DID0_MIN_5))
|
||||
#endif
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// Deprecated silicon class and revision detection macros.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#ifndef DEPRECATED
|
||||
#define DEVICE_IS_SANDSTORM CLASS_IS_SANDSTORM
|
||||
#define DEVICE_IS_FURY CLASS_IS_FURY
|
||||
#define DEVICE_IS_REVA2 REVISION_IS_A2
|
||||
#define DEVICE_IS_REVC1 REVISION_IS_C1
|
||||
#define DEVICE_IS_REVC2 REVISION_IS_C2
|
||||
#endif
|
||||
|
||||
#endif // __HW_TYPES_H__
|
|
@ -0,0 +1,522 @@
|
|||
//*****************************************************************************
|
||||
//
|
||||
// hw_uart.h - Macros and defines used when accessing the UART hardware.
|
||||
//
|
||||
// Copyright (c) 2005-2013 Texas Instruments Incorporated. All rights reserved.
|
||||
// Software License Agreement
|
||||
//
|
||||
// Redistribution and use in source and binary forms, with or without
|
||||
// modification, are permitted provided that the following conditions
|
||||
// are met:
|
||||
//
|
||||
// Redistributions of source code must retain the above copyright
|
||||
// notice, this list of conditions and the following disclaimer.
|
||||
//
|
||||
// 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.
|
||||
//
|
||||
// Neither the name of Texas Instruments Incorporated 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
|
||||
// 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.
|
||||
//
|
||||
// This is part of revision 10636 of the Stellaris Firmware Development Package.
|
||||
//
|
||||
//*****************************************************************************
|
||||
|
||||
#ifndef __HW_UART_H__
|
||||
#define __HW_UART_H__
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the UART register offsets.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define UART_O_DR 0x00000000 // UART Data
|
||||
#define UART_O_RSR 0x00000004 // UART Receive Status/Error Clear
|
||||
#define UART_O_ECR 0x00000004 // UART Receive Status/Error Clear
|
||||
#define UART_O_FR 0x00000018 // UART Flag
|
||||
#define UART_O_ILPR 0x00000020 // UART IrDA Low-Power Register
|
||||
#define UART_O_IBRD 0x00000024 // UART Integer Baud-Rate Divisor
|
||||
#define UART_O_FBRD 0x00000028 // UART Fractional Baud-Rate
|
||||
// Divisor
|
||||
#define UART_O_LCRH 0x0000002C // UART Line Control
|
||||
#define UART_O_CTL 0x00000030 // UART Control
|
||||
#define UART_O_IFLS 0x00000034 // UART Interrupt FIFO Level Select
|
||||
#define UART_O_IM 0x00000038 // UART Interrupt Mask
|
||||
#define UART_O_RIS 0x0000003C // UART Raw Interrupt Status
|
||||
#define UART_O_MIS 0x00000040 // UART Masked Interrupt Status
|
||||
#define UART_O_ICR 0x00000044 // UART Interrupt Clear
|
||||
#define UART_O_DMACTL 0x00000048 // UART DMA Control
|
||||
#define UART_O_LCTL 0x00000090 // UART LIN Control
|
||||
#define UART_O_LSS 0x00000094 // UART LIN Snap Shot
|
||||
#define UART_O_LTIM 0x00000098 // UART LIN Timer
|
||||
#define UART_O_9BITADDR 0x000000A4 // UART 9-Bit Self Address
|
||||
#define UART_O_9BITAMASK 0x000000A8 // UART 9-Bit Self Address Mask
|
||||
#define UART_O_PP 0x00000FC0 // UART Peripheral Properties
|
||||
#define UART_O_CC 0x00000FC8 // UART Clock Configuration
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the UART_O_DR register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define UART_DR_OE 0x00000800 // UART Overrun Error
|
||||
#define UART_DR_BE 0x00000400 // UART Break Error
|
||||
#define UART_DR_PE 0x00000200 // UART Parity Error
|
||||
#define UART_DR_FE 0x00000100 // UART Framing Error
|
||||
#define UART_DR_DATA_M 0x000000FF // Data Transmitted or Received
|
||||
#define UART_DR_DATA_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the UART_O_RSR register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define UART_RSR_OE 0x00000008 // UART Overrun Error
|
||||
#define UART_RSR_BE 0x00000004 // UART Break Error
|
||||
#define UART_RSR_PE 0x00000002 // UART Parity Error
|
||||
#define UART_RSR_FE 0x00000001 // UART Framing Error
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the UART_O_ECR register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define UART_ECR_DATA_M 0x000000FF // Error Clear
|
||||
#define UART_ECR_DATA_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the UART_O_FR register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define UART_FR_RI 0x00000100 // Ring Indicator
|
||||
#define UART_FR_TXFE 0x00000080 // UART Transmit FIFO Empty
|
||||
#define UART_FR_RXFF 0x00000040 // UART Receive FIFO Full
|
||||
#define UART_FR_TXFF 0x00000020 // UART Transmit FIFO Full
|
||||
#define UART_FR_RXFE 0x00000010 // UART Receive FIFO Empty
|
||||
#define UART_FR_BUSY 0x00000008 // UART Busy
|
||||
#define UART_FR_DCD 0x00000004 // Data Carrier Detect
|
||||
#define UART_FR_DSR 0x00000002 // Data Set Ready
|
||||
#define UART_FR_CTS 0x00000001 // Clear To Send
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the UART_O_ILPR register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define UART_ILPR_ILPDVSR_M 0x000000FF // IrDA Low-Power Divisor
|
||||
#define UART_ILPR_ILPDVSR_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the UART_O_IBRD register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define UART_IBRD_DIVINT_M 0x0000FFFF // Integer Baud-Rate Divisor
|
||||
#define UART_IBRD_DIVINT_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the UART_O_FBRD register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define UART_FBRD_DIVFRAC_M 0x0000003F // Fractional Baud-Rate Divisor
|
||||
#define UART_FBRD_DIVFRAC_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the UART_O_LCRH register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define UART_LCRH_SPS 0x00000080 // UART Stick Parity Select
|
||||
#define UART_LCRH_WLEN_M 0x00000060 // UART Word Length
|
||||
#define UART_LCRH_WLEN_5 0x00000000 // 5 bits (default)
|
||||
#define UART_LCRH_WLEN_6 0x00000020 // 6 bits
|
||||
#define UART_LCRH_WLEN_7 0x00000040 // 7 bits
|
||||
#define UART_LCRH_WLEN_8 0x00000060 // 8 bits
|
||||
#define UART_LCRH_FEN 0x00000010 // UART Enable FIFOs
|
||||
#define UART_LCRH_STP2 0x00000008 // UART Two Stop Bits Select
|
||||
#define UART_LCRH_EPS 0x00000004 // UART Even Parity Select
|
||||
#define UART_LCRH_PEN 0x00000002 // UART Parity Enable
|
||||
#define UART_LCRH_BRK 0x00000001 // UART Send Break
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the UART_O_CTL register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define UART_CTL_CTSEN 0x00008000 // Enable Clear To Send
|
||||
#define UART_CTL_RTSEN 0x00004000 // Enable Request to Send
|
||||
#define UART_CTL_RTS 0x00000800 // Request to Send
|
||||
#define UART_CTL_DTR 0x00000400 // Data Terminal Ready
|
||||
#define UART_CTL_RXE 0x00000200 // UART Receive Enable
|
||||
#define UART_CTL_TXE 0x00000100 // UART Transmit Enable
|
||||
#define UART_CTL_LBE 0x00000080 // UART Loop Back Enable
|
||||
#define UART_CTL_LIN 0x00000040 // LIN Mode Enable
|
||||
#define UART_CTL_HSE 0x00000020 // High-Speed Enable
|
||||
#define UART_CTL_EOT 0x00000010 // End of Transmission
|
||||
#define UART_CTL_SMART 0x00000008 // ISO 7816 Smart Card Support
|
||||
#define UART_CTL_SIRLP 0x00000004 // UART SIR Low-Power Mode
|
||||
#define UART_CTL_SIREN 0x00000002 // UART SIR Enable
|
||||
#define UART_CTL_UARTEN 0x00000001 // UART Enable
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the UART_O_IFLS register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define UART_IFLS_RX_M 0x00000038 // UART Receive Interrupt FIFO
|
||||
// Level Select
|
||||
#define UART_IFLS_RX1_8 0x00000000 // RX FIFO >= 1/8 full
|
||||
#define UART_IFLS_RX2_8 0x00000008 // RX FIFO >= 1/4 full
|
||||
#define UART_IFLS_RX4_8 0x00000010 // RX FIFO >= 1/2 full (default)
|
||||
#define UART_IFLS_RX6_8 0x00000018 // RX FIFO >= 3/4 full
|
||||
#define UART_IFLS_RX7_8 0x00000020 // RX FIFO >= 7/8 full
|
||||
#define UART_IFLS_TX_M 0x00000007 // UART Transmit Interrupt FIFO
|
||||
// Level Select
|
||||
#define UART_IFLS_TX1_8 0x00000000 // TX FIFO <= 1/8 full
|
||||
#define UART_IFLS_TX2_8 0x00000001 // TX FIFO <= 1/4 full
|
||||
#define UART_IFLS_TX4_8 0x00000002 // TX FIFO <= 1/2 full (default)
|
||||
#define UART_IFLS_TX6_8 0x00000003 // TX FIFO <= 3/4 full
|
||||
#define UART_IFLS_TX7_8 0x00000004 // TX FIFO <= 7/8 full
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the UART_O_IM register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define UART_IM_LME5IM 0x00008000 // LIN Mode Edge 5 Interrupt Mask
|
||||
#define UART_IM_LME1IM 0x00004000 // LIN Mode Edge 1 Interrupt Mask
|
||||
#define UART_IM_LMSBIM 0x00002000 // LIN Mode Sync Break Interrupt
|
||||
// Mask
|
||||
#define UART_IM_9BITIM 0x00001000 // 9-Bit Mode Interrupt Mask
|
||||
#define UART_IM_OEIM 0x00000400 // UART Overrun Error Interrupt
|
||||
// Mask
|
||||
#define UART_IM_BEIM 0x00000200 // UART Break Error Interrupt Mask
|
||||
#define UART_IM_PEIM 0x00000100 // UART Parity Error Interrupt Mask
|
||||
#define UART_IM_FEIM 0x00000080 // UART Framing Error Interrupt
|
||||
// Mask
|
||||
#define UART_IM_RTIM 0x00000040 // UART Receive Time-Out Interrupt
|
||||
// Mask
|
||||
#define UART_IM_TXIM 0x00000020 // UART Transmit Interrupt Mask
|
||||
#define UART_IM_RXIM 0x00000010 // UART Receive Interrupt Mask
|
||||
#define UART_IM_DSRMIM 0x00000008 // UART Data Set Ready Modem
|
||||
// Interrupt Mask
|
||||
#define UART_IM_DCDMIM 0x00000004 // UART Data Carrier Detect Modem
|
||||
// Interrupt Mask
|
||||
#define UART_IM_CTSMIM 0x00000002 // UART Clear to Send Modem
|
||||
// Interrupt Mask
|
||||
#define UART_IM_RIMIM 0x00000001 // UART Ring Indicator Modem
|
||||
// Interrupt Mask
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the UART_O_RIS register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define UART_RIS_LME5RIS 0x00008000 // LIN Mode Edge 5 Raw Interrupt
|
||||
// Status
|
||||
#define UART_RIS_LME1RIS 0x00004000 // LIN Mode Edge 1 Raw Interrupt
|
||||
// Status
|
||||
#define UART_RIS_LMSBRIS 0x00002000 // LIN Mode Sync Break Raw
|
||||
// Interrupt Status
|
||||
#define UART_RIS_9BITRIS 0x00001000 // 9-Bit Mode Raw Interrupt Status
|
||||
#define UART_RIS_OERIS 0x00000400 // UART Overrun Error Raw Interrupt
|
||||
// Status
|
||||
#define UART_RIS_BERIS 0x00000200 // UART Break Error Raw Interrupt
|
||||
// Status
|
||||
#define UART_RIS_PERIS 0x00000100 // UART Parity Error Raw Interrupt
|
||||
// Status
|
||||
#define UART_RIS_FERIS 0x00000080 // UART Framing Error Raw Interrupt
|
||||
// Status
|
||||
#define UART_RIS_RTRIS 0x00000040 // UART Receive Time-Out Raw
|
||||
// Interrupt Status
|
||||
#define UART_RIS_TXRIS 0x00000020 // UART Transmit Raw Interrupt
|
||||
// Status
|
||||
#define UART_RIS_RXRIS 0x00000010 // UART Receive Raw Interrupt
|
||||
// Status
|
||||
#define UART_RIS_DSRRIS 0x00000008 // UART Data Set Ready Modem Raw
|
||||
// Interrupt Status
|
||||
#define UART_RIS_DCDRIS 0x00000004 // UART Data Carrier Detect Modem
|
||||
// Raw Interrupt Status
|
||||
#define UART_RIS_CTSRIS 0x00000002 // UART Clear to Send Modem Raw
|
||||
// Interrupt Status
|
||||
#define UART_RIS_RIRIS 0x00000001 // UART Ring Indicator Modem Raw
|
||||
// Interrupt Status
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the UART_O_MIS register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define UART_MIS_LME5MIS 0x00008000 // LIN Mode Edge 5 Masked Interrupt
|
||||
// Status
|
||||
#define UART_MIS_LME1MIS 0x00004000 // LIN Mode Edge 1 Masked Interrupt
|
||||
// Status
|
||||
#define UART_MIS_LMSBMIS 0x00002000 // LIN Mode Sync Break Masked
|
||||
// Interrupt Status
|
||||
#define UART_MIS_9BITMIS 0x00001000 // 9-Bit Mode Masked Interrupt
|
||||
// Status
|
||||
#define UART_MIS_OEMIS 0x00000400 // UART Overrun Error Masked
|
||||
// Interrupt Status
|
||||
#define UART_MIS_BEMIS 0x00000200 // UART Break Error Masked
|
||||
// Interrupt Status
|
||||
#define UART_MIS_PEMIS 0x00000100 // UART Parity Error Masked
|
||||
// Interrupt Status
|
||||
#define UART_MIS_FEMIS 0x00000080 // UART Framing Error Masked
|
||||
// Interrupt Status
|
||||
#define UART_MIS_RTMIS 0x00000040 // UART Receive Time-Out Masked
|
||||
// Interrupt Status
|
||||
#define UART_MIS_TXMIS 0x00000020 // UART Transmit Masked Interrupt
|
||||
// Status
|
||||
#define UART_MIS_RXMIS 0x00000010 // UART Receive Masked Interrupt
|
||||
// Status
|
||||
#define UART_MIS_DSRMIS 0x00000008 // UART Data Set Ready Modem Masked
|
||||
// Interrupt Status
|
||||
#define UART_MIS_DCDMIS 0x00000004 // UART Data Carrier Detect Modem
|
||||
// Masked Interrupt Status
|
||||
#define UART_MIS_CTSMIS 0x00000002 // UART Clear to Send Modem Masked
|
||||
// Interrupt Status
|
||||
#define UART_MIS_RIMIS 0x00000001 // UART Ring Indicator Modem Masked
|
||||
// Interrupt Status
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the UART_O_ICR register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define UART_ICR_LME5IC 0x00008000 // LIN Mode Edge 5 Interrupt Clear
|
||||
#define UART_ICR_LME1IC 0x00004000 // LIN Mode Edge 1 Interrupt Clear
|
||||
#define UART_ICR_LMSBIC 0x00002000 // LIN Mode Sync Break Interrupt
|
||||
// Clear
|
||||
#define UART_ICR_9BITIC 0x00001000 // 9-Bit Mode Interrupt Clear
|
||||
#define UART_ICR_OEIC 0x00000400 // Overrun Error Interrupt Clear
|
||||
#define UART_ICR_BEIC 0x00000200 // Break Error Interrupt Clear
|
||||
#define UART_ICR_PEIC 0x00000100 // Parity Error Interrupt Clear
|
||||
#define UART_ICR_FEIC 0x00000080 // Framing Error Interrupt Clear
|
||||
#define UART_ICR_RTIC 0x00000040 // Receive Time-Out Interrupt Clear
|
||||
#define UART_ICR_TXIC 0x00000020 // Transmit Interrupt Clear
|
||||
#define UART_ICR_RXIC 0x00000010 // Receive Interrupt Clear
|
||||
#define UART_ICR_DSRMIC 0x00000008 // UART Data Set Ready Modem
|
||||
// Interrupt Clear
|
||||
#define UART_ICR_DCDMIC 0x00000004 // UART Data Carrier Detect Modem
|
||||
// Interrupt Clear
|
||||
#define UART_ICR_CTSMIC 0x00000002 // UART Clear to Send Modem
|
||||
// Interrupt Clear
|
||||
#define UART_ICR_RIMIC 0x00000001 // UART Ring Indicator Modem
|
||||
// Interrupt Clear
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the UART_O_DMACTL register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define UART_DMACTL_DMAERR 0x00000004 // DMA on Error
|
||||
#define UART_DMACTL_TXDMAE 0x00000002 // Transmit DMA Enable
|
||||
#define UART_DMACTL_RXDMAE 0x00000001 // Receive DMA Enable
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the UART_O_LCTL register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define UART_LCTL_BLEN_M 0x00000030 // Sync Break Length
|
||||
#define UART_LCTL_BLEN_13T 0x00000000 // Sync break length is 13T bits
|
||||
// (default)
|
||||
#define UART_LCTL_BLEN_14T 0x00000010 // Sync break length is 14T bits
|
||||
#define UART_LCTL_BLEN_15T 0x00000020 // Sync break length is 15T bits
|
||||
#define UART_LCTL_BLEN_16T 0x00000030 // Sync break length is 16T bits
|
||||
#define UART_LCTL_MASTER 0x00000001 // LIN Master Enable
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the UART_O_LSS register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define UART_LSS_TSS_M 0x0000FFFF // Timer Snap Shot
|
||||
#define UART_LSS_TSS_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the UART_O_LTIM register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define UART_LTIM_TIMER_M 0x0000FFFF // Timer Value
|
||||
#define UART_LTIM_TIMER_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the UART_O_9BITADDR
|
||||
// register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define UART_9BITADDR_9BITEN 0x00008000 // Enable 9-Bit Mode
|
||||
#define UART_9BITADDR_ADDR_M 0x000000FF // Self Address for 9-Bit Mode
|
||||
#define UART_9BITADDR_ADDR_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the UART_O_9BITAMASK
|
||||
// register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define UART_9BITAMASK_MASK_M 0x000000FF // Self Address Mask for 9-Bit Mode
|
||||
#define UART_9BITAMASK_MASK_S 0
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the UART_O_PP register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define UART_PP_NB 0x00000002 // 9-Bit Support
|
||||
#define UART_PP_SC 0x00000001 // Smart Card Support
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are defines for the bit fields in the UART_O_CC register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define UART_CC_CS_M 0x0000000F // UART Baud Clock Source
|
||||
#define UART_CC_CS_SYSCLK 0x00000000 // The system clock (default)
|
||||
#define UART_CC_CS_PIOSC 0x00000005 // PIOSC
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following definitions are deprecated.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#ifndef DEPRECATED
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are deprecated defines for the UART register offsets.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define UART_O_LCR_H 0x0000002C // Line Control Register, HIGH byte
|
||||
#define UART_O_PeriphID4 0x00000FD0
|
||||
#define UART_O_PeriphID5 0x00000FD4
|
||||
#define UART_O_PeriphID6 0x00000FD8
|
||||
#define UART_O_PeriphID7 0x00000FDC
|
||||
#define UART_O_PeriphID0 0x00000FE0
|
||||
#define UART_O_PeriphID1 0x00000FE4
|
||||
#define UART_O_PeriphID2 0x00000FE8
|
||||
#define UART_O_PeriphID3 0x00000FEC
|
||||
#define UART_O_PCellID0 0x00000FF0
|
||||
#define UART_O_PCellID1 0x00000FF4
|
||||
#define UART_O_PCellID2 0x00000FF8
|
||||
#define UART_O_PCellID3 0x00000FFC
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are deprecated defines for the bit fields in the UART_O_DR
|
||||
// register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define UART_DR_DATA_MASK 0x000000FF // UART data
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are deprecated defines for the bit fields in the UART_O_IBRD
|
||||
// register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define UART_IBRD_DIVINT_MASK 0x0000FFFF // Integer baud-rate divisor
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are deprecated defines for the bit fields in the UART_O_FBRD
|
||||
// register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define UART_FBRD_DIVFRAC_MASK 0x0000003F // Fractional baud-rate divisor
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are deprecated defines for the bit fields in the UART_O_LCR_H
|
||||
// register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define UART_LCR_H_SPS 0x00000080 // Stick Parity Select
|
||||
#define UART_LCR_H_WLEN 0x00000060 // Word length
|
||||
#define UART_LCR_H_WLEN_5 0x00000000 // 5 bit data
|
||||
#define UART_LCR_H_WLEN_6 0x00000020 // 6 bit data
|
||||
#define UART_LCR_H_WLEN_7 0x00000040 // 7 bit data
|
||||
#define UART_LCR_H_WLEN_8 0x00000060 // 8 bit data
|
||||
#define UART_LCR_H_FEN 0x00000010 // Enable FIFO
|
||||
#define UART_LCR_H_STP2 0x00000008 // Two Stop Bits Select
|
||||
#define UART_LCR_H_EPS 0x00000004 // Even Parity Select
|
||||
#define UART_LCR_H_PEN 0x00000002 // Parity Enable
|
||||
#define UART_LCR_H_BRK 0x00000001 // Send Break
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are deprecated defines for the bit fields in the UART_O_IFLS
|
||||
// register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define UART_IFLS_RX_MASK 0x00000038 // RX FIFO level mask
|
||||
#define UART_IFLS_TX_MASK 0x00000007 // TX FIFO level mask
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are deprecated defines for the bit fields in the UART_O_ICR
|
||||
// register.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define UART_ICR_LME5MIC 0x00008000 // LIN Mode Edge 5 Interrupt Clear
|
||||
#define UART_ICR_LME1MIC 0x00004000 // LIN Mode Edge 1 Interrupt Clear
|
||||
#define UART_ICR_LMSBMIC 0x00002000 // LIN Mode Sync Break Interrupt
|
||||
// Clear
|
||||
#define UART_RSR_ANY (UART_RSR_OE | UART_RSR_BE | UART_RSR_PE | \
|
||||
UART_RSR_FE)
|
||||
|
||||
//*****************************************************************************
|
||||
//
|
||||
// The following are deprecated defines for the Reset Values for UART
|
||||
// Registers.
|
||||
//
|
||||
//*****************************************************************************
|
||||
#define UART_RV_CTL 0x00000300
|
||||
#define UART_RV_PCellID1 0x000000F0
|
||||
#define UART_RV_PCellID3 0x000000B1
|
||||
#define UART_RV_FR 0x00000090
|
||||
#define UART_RV_PeriphID2 0x00000018
|
||||
#define UART_RV_IFLS 0x00000012
|
||||
#define UART_RV_PeriphID0 0x00000011
|
||||
#define UART_RV_PCellID0 0x0000000D
|
||||
#define UART_RV_PCellID2 0x00000005
|
||||
#define UART_RV_PeriphID3 0x00000001
|
||||
#define UART_RV_PeriphID4 0x00000000
|
||||
#define UART_RV_LCR_H 0x00000000
|
||||
#define UART_RV_PeriphID6 0x00000000
|
||||
#define UART_RV_DR 0x00000000
|
||||
#define UART_RV_RSR 0x00000000
|
||||
#define UART_RV_ECR 0x00000000
|
||||
#define UART_RV_PeriphID5 0x00000000
|
||||
#define UART_RV_RIS 0x00000000
|
||||
#define UART_RV_FBRD 0x00000000
|
||||
#define UART_RV_IM 0x00000000
|
||||
#define UART_RV_MIS 0x00000000
|
||||
#define UART_RV_ICR 0x00000000
|
||||
#define UART_RV_PeriphID1 0x00000000
|
||||
#define UART_RV_PeriphID7 0x00000000
|
||||
#define UART_RV_IBRD 0x00000000
|
||||
|
||||
#endif
|
||||
|
||||
#endif // __HW_UART_H__
|
File diff suppressed because it is too large
Load Diff
|
@ -0,0 +1,3 @@
|
|||
SRC_DIR := Libraries
|
||||
|
||||
include $(KERNEL_ROOT)/compiler.mk
|
|
@ -82,14 +82,18 @@ void Kd233Start(uint32_t mhartid)
|
|||
/*kernel start entry*/
|
||||
entry();
|
||||
break;
|
||||
#ifdef ARCH_SMP
|
||||
|
||||
case CPU1:
|
||||
while(0x2018050420191010 != cpu2_boot_flag) { ///< waiting for boot flag ,then start cpu1 core
|
||||
|
||||
}
|
||||
SecondaryCpuCStart();
|
||||
break;
|
||||
#ifndef ARCH_SMP
|
||||
asm volatile("wfi");
|
||||
#endif
|
||||
}
|
||||
#ifdef ARCH_SMP
|
||||
SecondaryCpuCStart();
|
||||
#endif
|
||||
break;
|
||||
|
||||
default:
|
||||
break;
|
||||
}
|
||||
|
|
|
@ -81,14 +81,17 @@ void Kd233Start(uint32_t mhartid)
|
|||
/*kernel start entry*/
|
||||
entry();
|
||||
break;
|
||||
#ifdef ARCH_SMP
|
||||
case CPU1:
|
||||
while(0x2018050420191010 != cpu2_boot_flag) { ///< waiting for boot flag ,then start cpu1 core
|
||||
|
||||
}
|
||||
SecondaryCpuCStart();
|
||||
break;
|
||||
#ifndef ARCH_SMP
|
||||
asm volatile("wfi");
|
||||
#endif
|
||||
}
|
||||
#ifdef ARCH_SMP
|
||||
SecondaryCpuCStart();
|
||||
#endif
|
||||
break;
|
||||
|
||||
default:
|
||||
break;
|
||||
}
|
||||
|
|
|
@ -77,14 +77,17 @@ void Kd233Start(uint32_t mhartid)
|
|||
/*kernel start entry*/
|
||||
entry();
|
||||
break;
|
||||
#ifdef ARCH_SMP
|
||||
case CPU1:
|
||||
while(0x2018050420191010 != cpu2_boot_flag) { ///< waiting for boot flag ,then start cpu1 core
|
||||
|
||||
}
|
||||
SecondaryCpuCStart();
|
||||
break;
|
||||
#ifndef ARCH_SMP
|
||||
asm volatile("wfi");
|
||||
#endif
|
||||
}
|
||||
#ifdef ARCH_SMP
|
||||
SecondaryCpuCStart();
|
||||
#endif
|
||||
break;
|
||||
|
||||
default:
|
||||
break;
|
||||
}
|
||||
|
|
|
@ -1,3 +1,3 @@
|
|||
SRC_DIR := connection perception intelligent
|
||||
SRC_DIR := connection perception intelligent security
|
||||
|
||||
include $(KERNEL_ROOT)/compiler.mk
|
||||
|
|
|
@ -1,3 +1,23 @@
|
|||
menu "Security"
|
||||
|
||||
menuconfig CRYPTO
|
||||
bool "using crypto"
|
||||
default n
|
||||
if CRYPTO
|
||||
menuconfig CRYPTO_SM3
|
||||
bool "using sm3"
|
||||
default n
|
||||
|
||||
menuconfig CRYPTO_SM4
|
||||
bool "using sm4"
|
||||
default n
|
||||
|
||||
menuconfig CRYPTO_SM9
|
||||
select CRYPTO_SM3
|
||||
select CRYPTO_SM4
|
||||
bool "using sm9"
|
||||
|
||||
default n
|
||||
endif
|
||||
|
||||
endmenu
|
||||
|
|
|
@ -0,0 +1,5 @@
|
|||
ifeq ($(CONFIG_CRYPTO), y)
|
||||
SRC_DIR := crypto
|
||||
endif
|
||||
|
||||
include $(KERNEL_ROOT)/compiler.mk
|
|
@ -0,0 +1,15 @@
|
|||
SRC_FILES :=
|
||||
|
||||
ifeq ($(CONFIG_CRYPTO_SM3), y)
|
||||
SRC_FILES += sm3/sm3.c sm3/sm3_hmac.c test/sm3_test.c
|
||||
endif
|
||||
|
||||
ifeq ($(CONFIG_CRYPTO_SM4), y)
|
||||
SRC_FILES += sm4/sm4_common.c sm4/sms4_setkey.c sm4/sms4_enc.c sm4/sm4_enc_mode.c test/sm4_test.c
|
||||
endif
|
||||
|
||||
ifeq ($(CONFIG_CRYPTO_SM9), y)
|
||||
SRC_FILES += sm9/bignum.c sm9/ecc.c sm9/qn.c sm9/join.c sm9/sm9_util.c sm9/sm9_para.c sm9/sm9.c test/sm9_test.c
|
||||
endif
|
||||
|
||||
include $(KERNEL_ROOT)/compiler.mk
|
|
@ -0,0 +1,79 @@
|
|||
/*
|
||||
* Copyright (c) 2020 AIIT Ubiquitous Team
|
||||
* XiUOS is licensed under Mulan PSL v2.
|
||||
* You can use this software according to the terms and conditions of the Mulan PSL v2.
|
||||
* You may obtain bn1 copy of Mulan PSL v2 at:
|
||||
* http://license.coscl.org.cn/MulanPSL2
|
||||
* THIS SOFTWARE IS PROVIDED ON AN "AS IS" BASIS, WITHOUT WARRANTIES OF ANY KIND,
|
||||
* EITHER EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO NON-INFRINGEMENT,
|
||||
* MERCHANTABILITY OR FIT FOR A PARTICULAR PURPOSE.
|
||||
* See the Mulan PSL v2 for more details.
|
||||
*/
|
||||
|
||||
/**
|
||||
* @file bignum.h
|
||||
* @brief arithmetic of big number, included by ecc.h
|
||||
* @version 1.0
|
||||
* @author AIIT Ubiquitous Team
|
||||
* @date 2021-04-24
|
||||
*/
|
||||
|
||||
#ifndef BIGNUM_H
|
||||
#define BIGNUM_H
|
||||
|
||||
#include <stddef.h>
|
||||
#include <stdint.h>
|
||||
#include <stdio.h>
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
#include <time.h>
|
||||
#include <xiuos.h>
|
||||
|
||||
#define BIGNUMBER_SIZE_8WORD 8
|
||||
#define BIGNUMBER_SIZE_16WORD 16
|
||||
|
||||
#define BIG8W_BYTESIZE 32
|
||||
|
||||
#define bool uint8_t
|
||||
#define true 1
|
||||
#define false 0
|
||||
|
||||
typedef struct bignum_8uint32 {
|
||||
uint32_t word[BIGNUMBER_SIZE_8WORD];
|
||||
} big8w;
|
||||
|
||||
typedef struct bignum_16uint32 {
|
||||
uint32_t word[BIGNUMBER_SIZE_16WORD];
|
||||
uint8_t length;
|
||||
} big16w;
|
||||
|
||||
typedef struct SM9Curve {
|
||||
big8w b;
|
||||
big8w q;
|
||||
big8w N;
|
||||
} sm9curve;
|
||||
|
||||
extern sm9curve curve;
|
||||
|
||||
// used in Montgomery Mult
|
||||
/** power(2, 32) - (curve.q.word[0] 's reverse under power(2, 32)) */
|
||||
extern uint32_t qlow_reverse;
|
||||
/** power(2, 32) - (curve.N.word[0] 's reverse under power(2, 32)) */
|
||||
extern uint32_t Nlow_reverse;
|
||||
/** (2^(256*2)) mod curve.q; used in big numbers' mult(Montgomery Mult) */
|
||||
extern big8w q_2k;
|
||||
/** (2^(256*2)) mod curve.N; used in big numbers' mult(Montgomery Mult) */
|
||||
extern big8w N_2k;
|
||||
|
||||
void Big8wPrint(big8w* bignum);
|
||||
unsigned char Big8wHighestbit(big8w* bignum);
|
||||
bool Big8wIsZero(big8w* bignum);
|
||||
bool Big8wBigThan(big8w* bn1, big8w* bn2);
|
||||
bool Big8wEqual(big8w* bn1, big8w* bn2);
|
||||
big8w Big8wMinusMod(big8w bn1, big8w bn2, big8w p);
|
||||
big8w Big8wAddMod(big8w bn1, big8w bn2, big8w p);
|
||||
big8w Big16wmod8w(big16w bignum16w, big8w p);
|
||||
big8w Big8wReverse(big8w bignum, big8w N);
|
||||
big8w Big8wMultMod(big8w bn1, big8w bn2, big8w p);
|
||||
|
||||
#endif
|
|
@ -0,0 +1,42 @@
|
|||
/*
|
||||
* Copyright (c) 2020 AIIT Ubiquitous Team
|
||||
* XiUOS is licensed under Mulan PSL v2.
|
||||
* You can use this software according to the terms and conditions of the Mulan PSL v2.
|
||||
* You may obtain a copy of Mulan PSL v2 at:
|
||||
* http://license.coscl.org.cn/MulanPSL2
|
||||
* THIS SOFTWARE IS PROVIDED ON AN "AS IS" BASIS, WITHOUT WARRANTIES OF ANY KIND,
|
||||
* EITHER EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO NON-INFRINGEMENT,
|
||||
* MERCHANTABILITY OR FIT FOR A PARTICULAR PURPOSE.
|
||||
* See the Mulan PSL v2 for more details.
|
||||
*/
|
||||
|
||||
/**
|
||||
* @file ecc.h
|
||||
* @brief arithmetic in ecc, included by qn.h
|
||||
* @version 1.0
|
||||
* @author AIIT Ubiquitous Team
|
||||
* @date 2021-04-24
|
||||
*/
|
||||
|
||||
#ifndef ECC_H
|
||||
#define ECC_H
|
||||
|
||||
#include <bignum.h>
|
||||
|
||||
typedef struct G1_base_group_point {
|
||||
big8w x;
|
||||
big8w y;
|
||||
} G1point;
|
||||
|
||||
typedef struct SM9ecn{
|
||||
big8w x;
|
||||
big8w y;
|
||||
big8w z;
|
||||
} ecn;
|
||||
|
||||
void G1pointPrint(G1point *point);
|
||||
bool PointInG1(G1point point);
|
||||
G1point G1pointAdd(G1point point1, G1point point2);
|
||||
G1point G1pointMult(big8w bignum, G1point point);
|
||||
|
||||
#endif
|
|
@ -0,0 +1,43 @@
|
|||
/*
|
||||
* Copyright (c) 2020 AIIT Ubiquitous Team
|
||||
* XiUOS is licensed under Mulan PSL v2.
|
||||
* You can use this software according to the terms and conditions of the Mulan PSL v2.
|
||||
* You may obtain a copy of Mulan PSL v2 at:
|
||||
* http://license.coscl.org.cn/MulanPSL2
|
||||
* THIS SOFTWARE IS PROVIDED ON AN "AS IS" BASIS, WITHOUT WARRANTIES OF ANY KIND,
|
||||
* EITHER EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO NON-INFRINGEMENT,
|
||||
* MERCHANTABILITY OR FIT FOR A PARTICULAR PURPOSE.
|
||||
* See the Mulan PSL v2 for more details.
|
||||
*/
|
||||
|
||||
/**
|
||||
* @file join.h
|
||||
* @brief convert data type and join string
|
||||
* @version 1.0
|
||||
* @author AIIT Ubiquitous Team
|
||||
* @date 2021-04-24
|
||||
*/
|
||||
|
||||
#ifndef JOIN_H
|
||||
#define JOIN_H
|
||||
|
||||
#include <qn.h>
|
||||
#include <sm3.h>
|
||||
|
||||
void Big8wIntou8string(big8w* bignum, uint8_t* string, uint32_t startindex);
|
||||
void Q12Intou8string(q12* num, uint8_t* string, uint32_t startindex);
|
||||
void U8stringToG1point(uint8_t *string, G1point* ret);
|
||||
|
||||
void JoinIDhid(uint8_t *ID, uint8_t IDlen, uint8_t hid, uint8_t *ret);
|
||||
void JoinMsgW(uint8_t *message, uint32_t msglen, q12 *w, uint8_t* ret);
|
||||
void JoinIDAIDBRARBg123(
|
||||
uint8_t *ID_Challenger, uint8_t ID_Challenger_len,
|
||||
uint8_t *ID_Responser, uint8_t ID_Responser_len,
|
||||
G1point* R_Challenger, G1point* R_Responser,
|
||||
q12 *g1, q12 *g2, q12 *g3,
|
||||
uint8_t* ret);
|
||||
void JoinCwID(G1point *C, q12 *w, uint8_t *ID, uint8_t IDlen, uint8_t *ret);
|
||||
|
||||
void XOR(unsigned char *msg, uint32_t msglen, unsigned char *K, unsigned char *ret);
|
||||
|
||||
#endif
|
|
@ -0,0 +1,71 @@
|
|||
/*
|
||||
* Copyright (c) 2020 AIIT Ubiquitous Team
|
||||
* XiUOS is licensed under Mulan PSL v2.
|
||||
* You can use this software according to the terms and conditions of the Mulan PSL v2.
|
||||
* You may obtain a copy of Mulan PSL v2 at:
|
||||
* http://license.coscl.org.cn/MulanPSL2
|
||||
* THIS SOFTWARE IS PROVIDED ON AN "AS IS" BASIS, WITHOUT WARRANTIES OF ANY KIND,
|
||||
* EITHER EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO NON-INFRINGEMENT,
|
||||
* MERCHANTABILITY OR FIT FOR A PARTICULAR PURPOSE.
|
||||
* See the Mulan PSL v2 for more details.
|
||||
*/
|
||||
|
||||
/**
|
||||
* @file qn.h
|
||||
* @brief arithmetic in extention field, and arithmetic in group G2, frobenius and LastPower in BiLinearPairing
|
||||
* @version 1.0
|
||||
* @author AIIT Ubiquitous Team
|
||||
* @date 2021-04-24
|
||||
*/
|
||||
|
||||
#ifndef QN_H
|
||||
#define QN_H
|
||||
|
||||
#include <ecc.h>
|
||||
|
||||
typedef struct q2_num {
|
||||
big8w high;
|
||||
big8w low;
|
||||
} q2;
|
||||
|
||||
typedef struct G2_q2group_point {
|
||||
q2 x;
|
||||
q2 y;
|
||||
} G2point;
|
||||
|
||||
typedef struct q4_num {
|
||||
q2 high;
|
||||
q2 low;
|
||||
} q4;
|
||||
|
||||
typedef struct q12_num {
|
||||
|
||||
q4 high;
|
||||
q4 mid;
|
||||
q4 low;
|
||||
|
||||
} q12;
|
||||
|
||||
typedef struct big_12bignum {
|
||||
big8w word[12];
|
||||
} big_12big;
|
||||
|
||||
extern big8w t; // sm9 ecc parameter
|
||||
extern big8w qnr; // (-1/2) mod curve.q
|
||||
extern big8w frobenius_constant_1[12];
|
||||
extern big8w frobenius_constant_2[12];
|
||||
|
||||
void G2pointPrint(G2point *point);
|
||||
void Q12Print(q12* number);
|
||||
void Q12To12big(q12 *num, big_12big *ret);
|
||||
G2point G2PointAdd(G2point point1, G2point point2);
|
||||
G2point G2PointMult(big8w num, G2point point);
|
||||
void Q12Zero(q12 *num);
|
||||
q12 Q12MultMod(q12 a, q12 b);
|
||||
q12 Q12PowerMod(q12 g, big8w r);
|
||||
void Q12Frobenius(q12 *f, uint8_t flag);
|
||||
void G2pointFrobenius(G2point Q, G2point* Q1, uint8_t flag);
|
||||
void Line(G1point P, G2point *T, G2point Q, bool doubleflag, q12 *f);
|
||||
void LastPower(q12 *f);
|
||||
|
||||
#endif
|
|
@ -0,0 +1,94 @@
|
|||
/* ====================================================================
|
||||
* Copyright (c) 2014 - 2017 The GmSSL Project. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
*
|
||||
* 2. 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.
|
||||
*
|
||||
* 3. All advertising materials mentioning features or use of this
|
||||
* software must display the following acknowledgment:
|
||||
* "This product includes software developed by the GmSSL Project.
|
||||
* (http://gmssl.org/)"
|
||||
*
|
||||
* 4. The name "GmSSL Project" must not be used to endorse or promote
|
||||
* products derived from this software without prior written
|
||||
* permission. For written permission, please contact
|
||||
* guanzhi1980@gmail.com.
|
||||
*
|
||||
* 5. Products derived from this software may not be called "GmSSL"
|
||||
* nor may "GmSSL" appear in their names without prior written
|
||||
* permission of the GmSSL Project.
|
||||
*
|
||||
* 6. Redistributions of any form whatsoever must retain the following
|
||||
* acknowledgment:
|
||||
* "This product includes software developed by the GmSSL Project
|
||||
* (http://gmssl.org/)"
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE GmSSL PROJECT ``AS IS'' AND ANY
|
||||
* EXPRESSED 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 GmSSL PROJECT OR
|
||||
* ITS 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 SM3_H
|
||||
#define SM3_H
|
||||
|
||||
#include <string.h>
|
||||
#include <stdio.h>
|
||||
#include <time.h>
|
||||
|
||||
#define SM3_DIGEST_LENGTH 32
|
||||
#define SM3_BLOCK_SIZE 64
|
||||
#define SM3_CBLOCK (SM3_BLOCK_SIZE)
|
||||
#define SM3_HMAC_SIZE (SM3_DIGEST_LENGTH)
|
||||
|
||||
# define ROL32(a,n) (((a)<<(n))|(((a)&0xffffffff)>>(32-(n))))
|
||||
# define GETU32(p) ((uint32_t)(p)[0]<<24|(uint32_t)(p)[1]<<16|(uint32_t)(p)[2]<<8|(uint32_t)(p)[3])
|
||||
# define PUTU32(p,v) ((p)[0]=(uint8_t)((v)>>24),(p)[1]=(uint8_t)((v)>>16),(p)[2]=(uint8_t)((v)>>8),(p)[3]=(uint8_t)(v))
|
||||
|
||||
#define FAR
|
||||
|
||||
typedef struct {
|
||||
uint32_t digest[8];
|
||||
uint64_t nblocks;
|
||||
unsigned char block[64];
|
||||
int num;
|
||||
} sm3_ctx_t;
|
||||
|
||||
typedef struct {
|
||||
sm3_ctx_t sm3_ctx;
|
||||
unsigned char key[SM3_BLOCK_SIZE];
|
||||
} sm3_hmac_ctx_t;
|
||||
|
||||
void sm3_init(sm3_ctx_t *ctx);
|
||||
void sm3_update(sm3_ctx_t *ctx, const unsigned char* data, size_t data_len);
|
||||
void sm3_final(sm3_ctx_t *ctx, unsigned char digest[SM3_DIGEST_LENGTH]);
|
||||
void sm3_compress(uint32_t digest[8], const unsigned char block[SM3_BLOCK_SIZE]);
|
||||
void sm3(const unsigned char *data, size_t datalen, unsigned char digest[SM3_DIGEST_LENGTH]);
|
||||
int sm3_file(char *path, unsigned char output[32]);
|
||||
void sm3_compute_id_digest(unsigned char z[32], const char *id, const unsigned char x[32], const unsigned char y[32]);
|
||||
void sm3_hmac_init(sm3_hmac_ctx_t *ctx, const unsigned char *key, size_t key_len);
|
||||
void sm3_hmac_update(sm3_hmac_ctx_t *ctx, const unsigned char *data, size_t data_len);
|
||||
void sm3_hmac_final(sm3_hmac_ctx_t *ctx, unsigned char mac[SM3_HMAC_SIZE]);
|
||||
void sm3_hmac(const unsigned char *data, size_t data_len, const unsigned char *key, size_t key_len, unsigned char mac[SM3_HMAC_SIZE]);
|
||||
|
||||
void sm3_test_case();
|
||||
|
||||
#endif
|
|
@ -0,0 +1,122 @@
|
|||
/* ====================================================================
|
||||
* Copyright (c) 2014 - 2017 The GmSSL Project. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
*
|
||||
* 2. 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.
|
||||
*
|
||||
* 3. All advertising materials mentioning features or use of this
|
||||
* software must display the following acknowledgment:
|
||||
* "This product includes software developed by the GmSSL Project.
|
||||
* (http://gmssl.org/)"
|
||||
*
|
||||
* 4. The name "GmSSL Project" must not be used to endorse or promote
|
||||
* products derived from this software without prior written
|
||||
* permission. For written permission, please contact
|
||||
* guanzhi1980@gmail.com.
|
||||
*
|
||||
* 5. Products derived from this software may not be called "GmSSL"
|
||||
* nor may "GmSSL" appear in their names without prior written
|
||||
* permission of the GmSSL Project.
|
||||
*
|
||||
* 6. Redistributions of any form whatsoever must retain the following
|
||||
* acknowledgment:
|
||||
* "This product includes software developed by the GmSSL Project
|
||||
* (http://gmssl.org/)"
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE GmSSL PROJECT ``AS IS'' AND ANY
|
||||
* EXPRESSED 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 GmSSL PROJECT OR
|
||||
* ITS 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.
|
||||
* ====================================================================
|
||||
*/
|
||||
|
||||
/*************************************************
|
||||
File name: sm4.h
|
||||
Description: sm4 header file
|
||||
Others: take GMSSL master/include/openssl/sms4.h
|
||||
https://github.com/guanzhi/GmSSL/blob/master/include/openssl/sms4.h
|
||||
History:
|
||||
1. Date: 2021-04-25
|
||||
Author: AIIT XUOS Lab
|
||||
*************************************************/
|
||||
|
||||
|
||||
#ifndef SM4_H
|
||||
#define SM4_H
|
||||
|
||||
#include <stdio.h>
|
||||
#include <string.h>
|
||||
|
||||
# define SMS4_KEY_LENGTH 16
|
||||
# define SMS4_BLOCK_SIZE 16
|
||||
# define SMS4_IV_LENGTH (SMS4_BLOCK_SIZE)
|
||||
# define SMS4_NUM_ROUNDS 32
|
||||
|
||||
# define SM4_ERROR_UNKNOW -1
|
||||
# define SM4_MALLOC_FAIL -2
|
||||
# define SM4_BAD_KEY_LENGTH -3
|
||||
# define SM4_BAD_PADDING_FORMAT -4
|
||||
# define SM4_BAD_LENGTH -5
|
||||
|
||||
#define FAR
|
||||
typedef signed char int8_t;
|
||||
typedef unsigned char uint8_t;
|
||||
typedef short int16_t;
|
||||
typedef unsigned short uint16_t;
|
||||
typedef int int32_t;
|
||||
typedef unsigned int uint32_t;
|
||||
|
||||
typedef struct {
|
||||
uint32_t rk[SMS4_NUM_ROUNDS];
|
||||
} sms4_key_t;
|
||||
|
||||
typedef struct {
|
||||
sms4_key_t k1;
|
||||
sms4_key_t k2;
|
||||
sms4_key_t k3;
|
||||
} sms4_ede_key_t;
|
||||
|
||||
# define sms4_decrypt(in, out, key) sms4_encrypt(in,out,key)
|
||||
void sms4_set_encrypt_key(sms4_key_t *key, const unsigned char user_key[16]);
|
||||
void sms4_set_decrypt_key(sms4_key_t *key, const unsigned char user_key[16]);
|
||||
void sms4_encrypt(const unsigned char in[16], unsigned char out[16], const sms4_key_t *key);
|
||||
void sms4_ecb_encrypt(const unsigned char *in, unsigned char *out, const sms4_key_t *key, int enc);
|
||||
|
||||
void Sms4EcbEncryptBlocks(const uint8_t *in,int ilen, uint8_t *out, const sms4_key_t *key);
|
||||
void Sms4EcbDecryptBlocks(const uint8_t *in,int ilen, uint8_t *out, const sms4_key_t *key);
|
||||
int Sms4EcbDecryptNoPadding(const uint8_t *in,int ilen, uint8_t *out,int *olen , const sms4_key_t *key);
|
||||
int Sms4EcbEncryptNoPadding(const uint8_t *in,int ilen, uint8_t *out,int *olen, const sms4_key_t *key);
|
||||
int Sms4EcbEncryptZeroPadding(const uint8_t *in,int ilen, uint8_t *out,int *olen, const sms4_key_t *key);
|
||||
int Sms4EcbDecryptZeroPadding(const uint8_t *in,int ilen, uint8_t *out,int *olen, const sms4_key_t *key);
|
||||
int Sms4EcbEncryptPkcs7Padding(const uint8_t *in,int ilen, uint8_t *out,int *olen, const sms4_key_t *key);
|
||||
int Sms4EcbDecryptPkcs7Padding(const uint8_t *in,int ilen, uint8_t *out,int *olen, const sms4_key_t *key);
|
||||
|
||||
void Sms4CbcEncryptBlocks(const unsigned char *in, int ilen, unsigned char *out,unsigned char *iv, const sms4_key_t *key);
|
||||
void Sms4CbcDecryptBlocks(const unsigned char *in, int ilen, unsigned char *out,unsigned char *iv, const sms4_key_t *key);
|
||||
int Sms4CbcDecryptNoPadding(const uint8_t *in,int ilen, uint8_t *out,int *olen, uint8_t *iv,const sms4_key_t *key);
|
||||
int Sms4CbcEncryptNoPadding(const uint8_t *in, int ilen, uint8_t *out, int *olen, uint8_t *iv, const sms4_key_t *key);
|
||||
int Sms4CbcEncryptZeroPadding(const uint8_t *in, int ilen, uint8_t *out, int *olen, uint8_t *iv, const sms4_key_t *key);
|
||||
int Sms4CbcDecryptZeroPadding(const uint8_t *in,int ilen, uint8_t *out,int *olen, uint8_t *iv, const sms4_key_t *key);
|
||||
int Sms4CbcEncryptPkcs7Padding(const uint8_t *in,int ilen, uint8_t *out,int *olen, uint8_t *iv, const sms4_key_t *key);
|
||||
int Sms4CbcDecryptPkcs7Padding(const uint8_t *in,int ilen, uint8_t *out,int *olen, uint8_t *iv, const sms4_key_t *key);
|
||||
|
||||
// void sm4_test();
|
||||
void sm4_test_case();
|
||||
#endif
|
|
@ -0,0 +1,72 @@
|
|||
/*
|
||||
* Copyright (c) 2020 AIIT Ubiquitous Team
|
||||
* XiUOS is licensed under Mulan PSL v2.
|
||||
* You can use this software according to the terms and conditions of the Mulan PSL v2.
|
||||
* You may obtain a copy of Mulan PSL v2 at:
|
||||
* http://license.coscl.org.cn/MulanPSL2
|
||||
* THIS SOFTWARE IS PROVIDED ON AN "AS IS" BASIS, WITHOUT WARRANTIES OF ANY KIND,
|
||||
* EITHER EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO NON-INFRINGEMENT,
|
||||
* MERCHANTABILITY OR FIT FOR A PARTICULAR PURPOSE.
|
||||
* See the Mulan PSL v2 for more details.
|
||||
*/
|
||||
|
||||
/**
|
||||
* @file sm9.h
|
||||
* @brief API of SM9
|
||||
* @version 1.0
|
||||
* @author AIIT Ubiquitous Team
|
||||
* @date 2021-04-24
|
||||
*/
|
||||
|
||||
#ifndef SM9_H
|
||||
#define SM9_H
|
||||
|
||||
#include <sm9_util.h>
|
||||
#include <sm9_para.h>
|
||||
|
||||
typedef struct SM9Signature {
|
||||
big8w h;
|
||||
G1point S;
|
||||
} Signature;
|
||||
|
||||
typedef struct SM9_Key_Package {
|
||||
unsigned char* K;
|
||||
G1point C;
|
||||
} Key_Package;
|
||||
|
||||
void SM9Init();
|
||||
Signature SM9Sign(unsigned char *message, uint32_t msglen, G1point ds, G2point Ppub_s);
|
||||
bool SM9VerifySignature(
|
||||
unsigned char *ID, unsigned char ID_len, unsigned char hid,
|
||||
unsigned char *message, uint32_t msglen,
|
||||
Signature signature, G2point Ppub_s);
|
||||
|
||||
void SM9KeyExchangeProduceR(unsigned char* ID, unsigned char IDlen, big8w* r, G1point* R, G1point encrypt_publickey);
|
||||
bool SM9KeyExchangeProduceKey(G1point* RA, G1point* RB, big8w* r, uint32_t klen_bitsize,
|
||||
unsigned char* challengerID, unsigned char challengerIDlen,
|
||||
unsigned char* responserID, unsigned char responserIDlen,
|
||||
q12 *g1, q12* g2, q12* g3, char* resultkey, bool sponsor,
|
||||
G1point encrypt_publickey, G2point encrypt_secretkey);
|
||||
bool SM9KeyExchangeVerifyKey(q12 *g1, q12 *g2, q12 *g3, G1point *RA, G1point *RB,
|
||||
unsigned char *challengerID, unsigned char challengerIDlen,
|
||||
unsigned char *responserID, unsigned char responserIDlen,
|
||||
unsigned char *S1, unsigned char *SA);
|
||||
|
||||
void SM9KeyPackage(unsigned char* ID, unsigned char IDlen, unsigned char hid, G1point Ppub_e, uint32_t klen_bitsize, unsigned char* K, G1point* C);
|
||||
bool SM9KeyDepackage(G1point C, G2point de, unsigned char* ID, unsigned char IDlen, unsigned int klen_bitsize, unsigned char* K);
|
||||
|
||||
bool SM9EncryptWithKDF(unsigned char *message, unsigned int msglen_bitsize, unsigned int K2_len_bitsize,
|
||||
unsigned char *ID, unsigned char IDlen, unsigned char hid, G1point Ppub_e, unsigned char *C);
|
||||
bool SM9DecryptWithKDF(unsigned char *ID, unsigned char IDlen,
|
||||
unsigned char *message, unsigned int msglen_bitsize, unsigned int K2_len_bitsize,
|
||||
unsigned char *C, G2point encrypt_secretkey);
|
||||
|
||||
bool SM9EncryptWithSM4(unsigned char *message, unsigned int msglen_bytesize,
|
||||
unsigned int K1_len_bitsize, unsigned int K2_len_bitsize,
|
||||
unsigned char *ID, unsigned char IDlen, unsigned char hid, G1point Ppub_e,
|
||||
unsigned char *C);
|
||||
bool SM9DecryptWithSM4(unsigned char *ID, unsigned char IDlen,
|
||||
unsigned char *message, unsigned int msglen, unsigned int K1_len_bitsize, unsigned int K2_len_bitsize,
|
||||
unsigned char *C, unsigned int Cbyteslen, G2point encrypt_secretkey);
|
||||
|
||||
#endif
|
|
@ -0,0 +1,66 @@
|
|||
/*
|
||||
* Copyright (c) 2020 AIIT Ubiquitous Team
|
||||
* XiUOS is licensed under Mulan PSL v2.
|
||||
* You can use this software according to the terms and conditions of the Mulan PSL v2.
|
||||
* You may obtain a copy of Mulan PSL v2 at:
|
||||
* http://license.coscl.org.cn/MulanPSL2
|
||||
* THIS SOFTWARE IS PROVIDED ON AN "AS IS" BASIS, WITHOUT WARRANTIES OF ANY KIND,
|
||||
* EITHER EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO NON-INFRINGEMENT,
|
||||
* MERCHANTABILITY OR FIT FOR A PARTICULAR PURPOSE.
|
||||
* See the Mulan PSL v2 for more details.
|
||||
*/
|
||||
|
||||
/**
|
||||
* @file sm9_para.h
|
||||
* @brief initialize paramters of SM9
|
||||
* @version 1.0
|
||||
* @author AIIT Ubiquitous Team
|
||||
* @date 2021-04-24
|
||||
*/
|
||||
|
||||
#ifndef SM9_PARA_H
|
||||
#define SM9_PARA_H
|
||||
|
||||
#include <join.h>
|
||||
|
||||
//extern char *device_id;
|
||||
//extern char *platform_id;
|
||||
|
||||
extern G1point P1;
|
||||
extern G2point P2;
|
||||
//extern G2point sign_publickey, encrypt_secretkey;
|
||||
//extern G1point sign_secretkey, encrypt_publickey;
|
||||
|
||||
extern const uint32_t sm9_q[BIGNUMBER_SIZE_8WORD];
|
||||
extern const uint32_t sm9_N[BIGNUMBER_SIZE_8WORD];
|
||||
extern const uint32_t sm9_P1_x[BIGNUMBER_SIZE_8WORD];
|
||||
extern const uint32_t sm9_P1_y[BIGNUMBER_SIZE_8WORD];
|
||||
extern const uint32_t sm9_P2_x_high[BIGNUMBER_SIZE_8WORD];
|
||||
extern const uint32_t sm9_P2_x_low[BIGNUMBER_SIZE_8WORD];
|
||||
extern const uint32_t sm9_P2_y_high[BIGNUMBER_SIZE_8WORD];
|
||||
extern const uint32_t sm9_P2_y_low[BIGNUMBER_SIZE_8WORD];
|
||||
extern const uint32_t fc1_1[BIGNUMBER_SIZE_8WORD];
|
||||
extern const uint32_t fc1_2[BIGNUMBER_SIZE_8WORD];
|
||||
extern const uint32_t fc1_3[BIGNUMBER_SIZE_8WORD];
|
||||
extern const uint32_t fc1_4[BIGNUMBER_SIZE_8WORD];
|
||||
extern const uint32_t fc1_5[BIGNUMBER_SIZE_8WORD];
|
||||
extern const uint32_t fc1_6[BIGNUMBER_SIZE_8WORD];
|
||||
extern const uint32_t fc1_7[BIGNUMBER_SIZE_8WORD];
|
||||
extern const uint32_t fc1_8[BIGNUMBER_SIZE_8WORD];
|
||||
extern const uint32_t fc1_9[BIGNUMBER_SIZE_8WORD];
|
||||
extern const uint32_t fc1_10[BIGNUMBER_SIZE_8WORD];
|
||||
extern const uint32_t fc1_11[BIGNUMBER_SIZE_8WORD];
|
||||
extern const uint32_t fc2_2[BIGNUMBER_SIZE_8WORD];
|
||||
extern const uint32_t fc2_3[BIGNUMBER_SIZE_8WORD];
|
||||
extern const uint32_t fc2_4[BIGNUMBER_SIZE_8WORD];
|
||||
extern const uint32_t fc2_5[BIGNUMBER_SIZE_8WORD];
|
||||
extern const uint32_t fc2_6[BIGNUMBER_SIZE_8WORD];
|
||||
extern const uint32_t fc2_7[BIGNUMBER_SIZE_8WORD];
|
||||
extern const uint32_t fc2_8[BIGNUMBER_SIZE_8WORD];
|
||||
extern const uint32_t fc2_9[BIGNUMBER_SIZE_8WORD];
|
||||
extern const uint32_t fc2_10[BIGNUMBER_SIZE_8WORD];
|
||||
extern const uint32_t fc2_11[BIGNUMBER_SIZE_8WORD];
|
||||
extern const uint32_t sm9_qnr[BIGNUMBER_SIZE_8WORD];
|
||||
extern const uint32_t sm9_q_2k[BIGNUMBER_SIZE_8WORD];
|
||||
extern const uint32_t sm9_N_2k[BIGNUMBER_SIZE_8WORD];
|
||||
#endif
|
|
@ -0,0 +1,31 @@
|
|||
/*
|
||||
* Copyright (c) 2020 AIIT Ubiquitous Team
|
||||
* XiUOS is licensed under Mulan PSL v2.
|
||||
* You can use this software according to the terms and conditions of the Mulan PSL v2.
|
||||
* You may obtain a copy of Mulan PSL v2 at:
|
||||
* http://license.coscl.org.cn/MulanPSL2
|
||||
* THIS SOFTWARE IS PROVIDED ON AN "AS IS" BASIS, WITHOUT WARRANTIES OF ANY KIND,
|
||||
* EITHER EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO NON-INFRINGEMENT,
|
||||
* MERCHANTABILITY OR FIT FOR A PARTICULAR PURPOSE.
|
||||
* See the Mulan PSL v2 for more details.
|
||||
*/
|
||||
|
||||
/**
|
||||
* @file sm9_test.h
|
||||
* @brief tests of SM9
|
||||
* @version 1.0
|
||||
* @author AIIT Ubiquitous Team
|
||||
* @date 2021-04-24
|
||||
*/
|
||||
|
||||
#ifndef SM9_TEST_H
|
||||
#define SM9_TEST_H
|
||||
|
||||
#include <sm9.h>
|
||||
|
||||
void SignAndVerifyTest();
|
||||
void SM9KeyExchangeTest();
|
||||
void SM9PackDepackTest();
|
||||
void SM9EncryptDecryptTest();
|
||||
|
||||
#endif
|
|
@ -0,0 +1,40 @@
|
|||
/*
|
||||
* Copyright (c) 2020 AIIT Ubiquitous Team
|
||||
* XiUOS is licensed under Mulan PSL v2.
|
||||
* You can use this software according to the terms and conditions of the Mulan PSL v2.
|
||||
* You may obtain a copy of Mulan PSL v2 at:
|
||||
* http://license.coscl.org.cn/MulanPSL2
|
||||
* THIS SOFTWARE IS PROVIDED ON AN "AS IS" BASIS, WITHOUT WARRANTIES OF ANY KIND,
|
||||
* EITHER EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO NON-INFRINGEMENT,
|
||||
* MERCHANTABILITY OR FIT FOR A PARTICULAR PURPOSE.
|
||||
* See the Mulan PSL v2 for more details.
|
||||
*/
|
||||
|
||||
/**
|
||||
* @file sm9_util.h
|
||||
* @brief the function called by SM9 function, including hash, KDF, produce random number, encrypt and decrypt algorithm, BiLinearPairing
|
||||
* @version 1.0
|
||||
* @author AIIT Ubiquitous Team
|
||||
* @date 2021-04-24
|
||||
*/
|
||||
|
||||
#ifndef SM9_UTIL_H
|
||||
#define SM9_UTIL_H
|
||||
|
||||
#include <join.h>
|
||||
#include <sm4.h>
|
||||
|
||||
#define SM3OUT_32BYTES 32 // (256 / 8)
|
||||
|
||||
void HashTwice(uint8_t *ID_A, uint8_t ID_A_len, uint8_t *ID_B, uint8_t ID_B_len,
|
||||
G1point *RA, G1point *RB,
|
||||
q12 *g1, q12 *g2, q12 *g3, uint8_t funcflag, uint8_t *ret);
|
||||
big8w RandomNumGenerate();
|
||||
bool StringEqualZero(uint8_t* string, uint32_t stringlen);
|
||||
big8w H(uint8_t *Z, uint32_t Zlen, uint8_t funcflag);
|
||||
void KDF(uint8_t *Z, uint32_t Zlen, uint32_t klen, uint8_t *ret);
|
||||
void SM4EncryptWithEcbMode(uint8_t* message, uint32_t msglen, uint8_t* key, uint8_t* ciphertext);
|
||||
void SM4DecryptWithEcbMode(uint8_t* ciphertext, uint32_t ciphertextlen, uint8_t* message, int msglen, uint8_t* key);
|
||||
q12 BiLinearPairing(G1point P, G2point Q);
|
||||
|
||||
#endif
|
|
@ -0,0 +1,474 @@
|
|||
/* ====================================================================
|
||||
* Copyright (c) 2014 - 2017 The GmSSL Project. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
*
|
||||
* 2. 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.
|
||||
*
|
||||
* 3. All advertising materials mentioning features or use of this
|
||||
* software must display the following acknowledgment:
|
||||
* "This product includes software developed by the GmSSL Project.
|
||||
* (http://gmssl.org/)"
|
||||
*
|
||||
* 4. The name "GmSSL Project" must not be used to endorse or promote
|
||||
* products derived from this software without prior written
|
||||
* permission. For written permission, please contact
|
||||
* guanzhi1980@gmail.com.
|
||||
*
|
||||
* 5. Products derived from this software may not be called "GmSSL"
|
||||
* nor may "GmSSL" appear in their names without prior written
|
||||
* permission of the GmSSL Project.
|
||||
*
|
||||
* 6. Redistributions of any form whatsoever must retain the following
|
||||
* acknowledgment:
|
||||
* "This product includes software developed by the GmSSL Project
|
||||
* (http://gmssl.org/)"
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE GmSSL PROJECT ``AS IS'' AND ANY
|
||||
* EXPRESSED 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 GmSSL PROJECT OR
|
||||
* ITS 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 <sm3.h>
|
||||
|
||||
static void sm3_compress_blocks(uint32_t digest[8],
|
||||
const unsigned char *data, size_t blocks);
|
||||
|
||||
void sm3_init(sm3_ctx_t *ctx)
|
||||
{
|
||||
memset(ctx, 0, sizeof(*ctx));
|
||||
ctx->digest[0] = 0x7380166F;
|
||||
ctx->digest[1] = 0x4914B2B9;
|
||||
ctx->digest[2] = 0x172442D7;
|
||||
ctx->digest[3] = 0xDA8A0600;
|
||||
ctx->digest[4] = 0xA96F30BC;
|
||||
ctx->digest[5] = 0x163138AA;
|
||||
ctx->digest[6] = 0xE38DEE4D;
|
||||
ctx->digest[7] = 0xB0FB0E4E;
|
||||
}
|
||||
|
||||
void sm3_compute_id_digest(unsigned char z[32], const char *id,
|
||||
const unsigned char x[32], const unsigned char y[32])
|
||||
{
|
||||
unsigned char zin[] = {
|
||||
0x00, 0x80,
|
||||
0x31, 0x32, 0x33, 0x34, 0x35, 0x36, 0x37, 0x38,
|
||||
0x31, 0x32, 0x33, 0x34, 0x35, 0x36, 0x37, 0x38,
|
||||
0xFF, 0xFF, 0xFF, 0xFE, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0x00, 0x00, 0x00, 0x00,
|
||||
0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFC,
|
||||
0x28, 0xE9, 0xFA, 0x9E, 0x9D, 0x9F, 0x5E, 0x34,
|
||||
0x4D, 0x5A, 0x9E, 0x4B, 0xCF, 0x65, 0x09, 0xA7,
|
||||
0xF3, 0x97, 0x89, 0xF5, 0x15, 0xAB, 0x8F, 0x92,
|
||||
0xDD, 0xBC, 0xBD, 0x41, 0x4D, 0x94, 0x0E, 0x93,
|
||||
0x32, 0xC4, 0xAE, 0x2C, 0x1F, 0x19, 0x81, 0x19,
|
||||
0x5F, 0x99, 0x04, 0x46, 0x6A, 0x39, 0xC9, 0x94,
|
||||
0x8F, 0xE3, 0x0B, 0xBF, 0xF2, 0x66, 0x0B, 0xE1,
|
||||
0x71, 0x5A, 0x45, 0x89, 0x33, 0x4C, 0x74, 0xC7,
|
||||
0xBC, 0x37, 0x36, 0xA2, 0xF4, 0xF6, 0x77, 0x9C,
|
||||
0x59, 0xBD, 0xCE, 0xE3, 0x6B, 0x69, 0x21, 0x53,
|
||||
0xD0, 0xA9, 0x87, 0x7C, 0xC6, 0x2A, 0x47, 0x40,
|
||||
0x02, 0xDF, 0x32, 0xE5, 0x21, 0x39, 0xF0, 0xA0,
|
||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||
0x80, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
|
||||
0x00, 0x00, 0x00, 0x00, 0x06, 0x90,
|
||||
};
|
||||
|
||||
if (!id || strcmp(id, "1234567812345678")) {
|
||||
unsigned int digest[8] = {
|
||||
0xadadedb5U, 0x0446043fU, 0x08a87aceU, 0xe86d2243U,
|
||||
0x8e232383U, 0xbfc81fe2U, 0xcf9117c8U, 0x4707011dU,
|
||||
};
|
||||
memcpy(&zin[128], x, 32);
|
||||
memcpy(&zin[160], y, 32);
|
||||
sm3_compress_blocks(digest, zin, 2);
|
||||
PUTU32(z , digest[0]);
|
||||
PUTU32(z + 4, digest[1]);
|
||||
PUTU32(z + 8, digest[2]);
|
||||
PUTU32(z + 12, digest[3]);
|
||||
PUTU32(z + 16, digest[4]);
|
||||
PUTU32(z + 20, digest[5]);
|
||||
PUTU32(z + 24, digest[6]);
|
||||
PUTU32(z + 28, digest[7]);
|
||||
|
||||
} else {
|
||||
sm3_ctx_t ctx;
|
||||
unsigned char idbits[2];
|
||||
size_t len;
|
||||
|
||||
len = strlen(id);
|
||||
idbits[0] = (unsigned char)(len >> 5);
|
||||
idbits[1] = (unsigned char)(len << 3);
|
||||
|
||||
sm3_init(&ctx);
|
||||
sm3_update(&ctx, idbits, 2);
|
||||
sm3_update(&ctx, (unsigned char *)id, len);
|
||||
sm3_update(&ctx, zin + 18, 128);
|
||||
sm3_update(&ctx, x, 32);
|
||||
sm3_update(&ctx, y, 32);
|
||||
sm3_final(&ctx, z);
|
||||
}
|
||||
}
|
||||
|
||||
int sm3_sm2_init(sm3_ctx_t *ctx, const char *id,
|
||||
const unsigned char *x, const unsigned char *y)
|
||||
{
|
||||
unsigned char z[32];
|
||||
if ((id && strlen(id) > 65535/8) || !x || !y) {
|
||||
return 0;
|
||||
}
|
||||
sm3_compute_id_digest(z, id, x, y);
|
||||
sm3_init(ctx);
|
||||
sm3_update(ctx, z, 32);
|
||||
return 1;
|
||||
}
|
||||
|
||||
void sm3_update(sm3_ctx_t *ctx, const unsigned char *data, size_t data_len)
|
||||
{
|
||||
size_t blocks;
|
||||
|
||||
if (ctx->num) {
|
||||
unsigned int left = SM3_BLOCK_SIZE - ctx->num;
|
||||
if (data_len < left) {
|
||||
memcpy(ctx->block + ctx->num, data, data_len);
|
||||
ctx->num += data_len;
|
||||
return;
|
||||
} else {
|
||||
memcpy(ctx->block + ctx->num, data, left);
|
||||
sm3_compress_blocks(ctx->digest, ctx->block, 1);
|
||||
ctx->nblocks++;
|
||||
data += left;
|
||||
data_len -= left;
|
||||
}
|
||||
}
|
||||
|
||||
blocks = data_len / SM3_BLOCK_SIZE;
|
||||
sm3_compress_blocks(ctx->digest, data, blocks);
|
||||
ctx->nblocks += blocks;
|
||||
data += SM3_BLOCK_SIZE * blocks;
|
||||
data_len -= SM3_BLOCK_SIZE * blocks;
|
||||
|
||||
ctx->num = data_len;
|
||||
if (data_len) {
|
||||
memcpy(ctx->block, data, data_len);
|
||||
}
|
||||
}
|
||||
|
||||
void sm3_final(sm3_ctx_t *ctx, unsigned char *digest)
|
||||
{
|
||||
int i;
|
||||
|
||||
ctx->block[ctx->num] = 0x80;
|
||||
|
||||
if (ctx->num + 9 <= SM3_BLOCK_SIZE) {
|
||||
memset(ctx->block + ctx->num + 1, 0, SM3_BLOCK_SIZE - ctx->num - 9);
|
||||
} else {
|
||||
memset(ctx->block + ctx->num + 1, 0, SM3_BLOCK_SIZE - ctx->num - 1);
|
||||
sm3_compress(ctx->digest, ctx->block);
|
||||
memset(ctx->block, 0, SM3_BLOCK_SIZE - 8);
|
||||
}
|
||||
PUTU32(ctx->block + 56, ctx->nblocks >> 23);
|
||||
PUTU32(ctx->block + 60, (ctx->nblocks << 9) + (ctx->num << 3));
|
||||
|
||||
sm3_compress(ctx->digest, ctx->block);
|
||||
for (i = 0; i < 8; i++) {
|
||||
PUTU32(digest + i*4, ctx->digest[i]);
|
||||
}
|
||||
}
|
||||
|
||||
#define ROTL(x,n) (((x)<<(n)) | ((x)>>(32-(n))))
|
||||
#define P0(x) ((x) ^ ROL32((x), 9) ^ ROL32((x),17))
|
||||
#define P1(x) ((x) ^ ROL32((x),15) ^ ROL32((x),23))
|
||||
|
||||
#define FF00(x,y,z) ((x) ^ (y) ^ (z))
|
||||
#define FF16(x,y,z) (((x)&(y)) | ((x)&(z)) | ((y)&(z)))
|
||||
#define GG00(x,y,z) ((x) ^ (y) ^ (z))
|
||||
#define GG16(x,y,z) ((((y)^(z)) & (x)) ^ (z))
|
||||
|
||||
#define R(A, B, C, D, E, F, G, H, xx) \
|
||||
SS1 = ROL32((ROL32(A, 12) + E + K[j]), 7); \
|
||||
SS2 = SS1 ^ ROL32(A, 12); \
|
||||
TT1 = FF##xx(A, B, C) + D + SS2 + (W[j] ^ W[j + 4]); \
|
||||
TT2 = GG##xx(E, F, G) + H + SS1 + W[j]; \
|
||||
B = ROL32(B, 9); \
|
||||
H = TT1; \
|
||||
F = ROL32(F, 19); \
|
||||
D = P0(TT2); \
|
||||
j++
|
||||
|
||||
#define R8(A, B, C, D, E, F, G, H, xx) \
|
||||
R(A, B, C, D, E, F, G, H, xx); \
|
||||
R(H, A, B, C, D, E, F, G, xx); \
|
||||
R(G, H, A, B, C, D, E, F, xx); \
|
||||
R(F, G, H, A, B, C, D, E, xx); \
|
||||
R(E, F, G, H, A, B, C, D, xx); \
|
||||
R(D, E, F, G, H, A, B, C, xx); \
|
||||
R(C, D, E, F, G, H, A, B, xx); \
|
||||
R(B, C, D, E, F, G, H, A, xx)
|
||||
|
||||
|
||||
|
||||
#define T00 0x79cc4519U
|
||||
#define T16 0x7a879d8aU
|
||||
|
||||
#define K0 0x79cc4519U
|
||||
#define K1 0xf3988a32U
|
||||
#define K2 0xe7311465U
|
||||
#define K3 0xce6228cbU
|
||||
#define K4 0x9cc45197U
|
||||
#define K5 0x3988a32fU
|
||||
#define K6 0x7311465eU
|
||||
#define K7 0xe6228cbcU
|
||||
#define K8 0xcc451979U
|
||||
#define K9 0x988a32f3U
|
||||
#define K10 0x311465e7U
|
||||
#define K11 0x6228cbceU
|
||||
#define K12 0xc451979cU
|
||||
#define K13 0x88a32f39U
|
||||
#define K14 0x11465e73U
|
||||
#define K15 0x228cbce6U
|
||||
#define K16 0x9d8a7a87U
|
||||
#define K17 0x3b14f50fU
|
||||
#define K18 0x7629ea1eU
|
||||
#define K19 0xec53d43cU
|
||||
#define K20 0xd8a7a879U
|
||||
#define K21 0xb14f50f3U
|
||||
#define K22 0x629ea1e7U
|
||||
#define K23 0xc53d43ceU
|
||||
#define K24 0x8a7a879dU
|
||||
#define K25 0x14f50f3bU
|
||||
#define K26 0x29ea1e76U
|
||||
#define K27 0x53d43cecU
|
||||
#define K28 0xa7a879d8U
|
||||
#define K29 0x4f50f3b1U
|
||||
#define K30 0x9ea1e762U
|
||||
#define K31 0x3d43cec5U
|
||||
#define K32 0x7a879d8aU
|
||||
#define K33 0xf50f3b14U
|
||||
#define K34 0xea1e7629U
|
||||
#define K35 0xd43cec53U
|
||||
#define K36 0xa879d8a7U
|
||||
#define K37 0x50f3b14fU
|
||||
#define K38 0xa1e7629eU
|
||||
#define K39 0x43cec53dU
|
||||
#define K40 0x879d8a7aU
|
||||
#define K41 0x0f3b14f5U
|
||||
#define K42 0x1e7629eaU
|
||||
#define K43 0x3cec53d4U
|
||||
#define K44 0x79d8a7a8U
|
||||
#define K45 0xf3b14f50U
|
||||
#define K46 0xe7629ea1U
|
||||
#define K47 0xcec53d43U
|
||||
#define K48 0x9d8a7a87U
|
||||
#define K49 0x3b14f50fU
|
||||
#define K50 0x7629ea1eU
|
||||
#define K51 0xec53d43cU
|
||||
#define K52 0xd8a7a879U
|
||||
#define K53 0xb14f50f3U
|
||||
#define K54 0x629ea1e7U
|
||||
#define K55 0xc53d43ceU
|
||||
#define K56 0x8a7a879dU
|
||||
#define K57 0x14f50f3bU
|
||||
#define K58 0x29ea1e76U
|
||||
#define K59 0x53d43cecU
|
||||
#define K60 0xa7a879d8U
|
||||
#define K61 0x4f50f3b1U
|
||||
#define K62 0x9ea1e762U
|
||||
#define K63 0x3d43cec5U
|
||||
|
||||
uint32_t K[64] = {
|
||||
K0, K1, K2, K3, K4, K5, K6, K7,
|
||||
K8, K9, K10, K11, K12, K13, K14, K15,
|
||||
K16, K17, K18, K19, K20, K21, K22, K23,
|
||||
K24, K25, K26, K27, K28, K29, K30, K31,
|
||||
K32, K33, K34, K35, K36, K37, K38, K39,
|
||||
K40, K41, K42, K43, K44, K45, K46, K47,
|
||||
K48, K49, K50, K51, K52, K53, K54, K55,
|
||||
K56, K57, K58, K59, K60, K61, K62, K63,
|
||||
/*
|
||||
0x79cc4519U, 0xf3988a32U, 0xe7311465U, 0xce6228cbU,
|
||||
0x9cc45197U, 0x3988a32fU, 0x7311465eU, 0xe6228cbcU,
|
||||
0xcc451979U, 0x988a32f3U, 0x311465e7U, 0x6228cbceU,
|
||||
0xc451979cU, 0x88a32f39U, 0x11465e73U, 0x228cbce6U,
|
||||
0x9d8a7a87U, 0x3b14f50fU, 0x7629ea1eU, 0xec53d43cU,
|
||||
0xd8a7a879U, 0xb14f50f3U, 0x629ea1e7U, 0xc53d43ceU,
|
||||
0x8a7a879dU, 0x14f50f3bU, 0x29ea1e76U, 0x53d43cecU,
|
||||
0xa7a879d8U, 0x4f50f3b1U, 0x9ea1e762U, 0x3d43cec5U,
|
||||
0x7a879d8aU, 0xf50f3b14U, 0xea1e7629U, 0xd43cec53U,
|
||||
0xa879d8a7U, 0x50f3b14fU, 0xa1e7629eU, 0x43cec53dU,
|
||||
0x879d8a7aU, 0x0f3b14f5U, 0x1e7629eaU, 0x3cec53d4U,
|
||||
0x79d8a7a8U, 0xf3b14f50U, 0xe7629ea1U, 0xcec53d43U,
|
||||
0x9d8a7a87U, 0x3b14f50fU, 0x7629ea1eU, 0xec53d43cU,
|
||||
0xd8a7a879U, 0xb14f50f3U, 0x629ea1e7U, 0xc53d43ceU,
|
||||
0x8a7a879dU, 0x14f50f3bU, 0x29ea1e76U, 0x53d43cecU,
|
||||
0xa7a879d8U, 0x4f50f3b1U, 0x9ea1e762U, 0x3d43cec5U,
|
||||
*/
|
||||
};
|
||||
|
||||
static void sm3_compress_blocks(uint32_t digest[8],
|
||||
const unsigned char *data, size_t blocks)
|
||||
{
|
||||
uint32_t A;
|
||||
uint32_t B;
|
||||
uint32_t C;
|
||||
uint32_t D;
|
||||
uint32_t E;
|
||||
uint32_t F;
|
||||
uint32_t G;
|
||||
uint32_t H;
|
||||
uint32_t W[68];
|
||||
uint32_t SS1, SS2, TT1, TT2;
|
||||
int j;
|
||||
|
||||
while (blocks--) {
|
||||
|
||||
A = digest[0];
|
||||
B = digest[1];
|
||||
C = digest[2];
|
||||
D = digest[3];
|
||||
E = digest[4];
|
||||
F = digest[5];
|
||||
G = digest[6];
|
||||
H = digest[7];
|
||||
|
||||
for (j = 0; j < 16; j++)
|
||||
W[j] = GETU32(data + j*4);
|
||||
|
||||
for (; j < 68; j++)
|
||||
W[j] = P1(W[j - 16] ^ W[j - 9] ^ ROL32(W[j - 3], 15))
|
||||
^ ROL32(W[j - 13], 7) ^ W[j - 6];
|
||||
|
||||
|
||||
|
||||
j = 0;
|
||||
|
||||
#define FULL_UNROLL
|
||||
#ifdef FULL_UNROLL
|
||||
R8(A, B, C, D, E, F, G, H, 00);
|
||||
R8(A, B, C, D, E, F, G, H, 00);
|
||||
R8(A, B, C, D, E, F, G, H, 16);
|
||||
R8(A, B, C, D, E, F, G, H, 16);
|
||||
R8(A, B, C, D, E, F, G, H, 16);
|
||||
R8(A, B, C, D, E, F, G, H, 16);
|
||||
R8(A, B, C, D, E, F, G, H, 16);
|
||||
R8(A, B, C, D, E, F, G, H, 16);
|
||||
#else
|
||||
for (; j < 16; j++) {
|
||||
SS1 = ROL32((ROL32(A, 12) + E + K(j)), 7);
|
||||
SS2 = SS1 ^ ROL32(A, 12);
|
||||
TT1 = FF00(A, B, C) + D + SS2 + (W[j] ^ W[j + 4]);
|
||||
TT2 = GG00(E, F, G) + H + SS1 + W[j];
|
||||
D = C;
|
||||
C = ROL32(B, 9);
|
||||
B = A;
|
||||
A = TT1;
|
||||
H = G;
|
||||
G = ROL32(F, 19);
|
||||
F = E;
|
||||
E = P0(TT2);
|
||||
}
|
||||
|
||||
for (; j < 64; j++) {
|
||||
SS1 = ROL32((ROL32(A, 12) + E + K(j)), 7);
|
||||
SS2 = SS1 ^ ROL32(A, 12);
|
||||
TT1 = FF16(A, B, C) + D + SS2 + (W[j] ^ W[j + 4]);
|
||||
TT2 = GG16(E, F, G) + H + SS1 + W[j];
|
||||
D = C;
|
||||
C = ROL32(B, 9);
|
||||
B = A;
|
||||
A = TT1;
|
||||
H = G;
|
||||
G = ROL32(F, 19);
|
||||
F = E;
|
||||
E = P0(TT2);
|
||||
}
|
||||
#endif
|
||||
|
||||
digest[0] ^= A;
|
||||
digest[1] ^= B;
|
||||
digest[2] ^= C;
|
||||
digest[3] ^= D;
|
||||
digest[4] ^= E;
|
||||
digest[5] ^= F;
|
||||
digest[6] ^= G;
|
||||
digest[7] ^= H;
|
||||
|
||||
data += 64;
|
||||
}
|
||||
}
|
||||
|
||||
void sm3_compress(uint32_t digest[8], const unsigned char block[64])
|
||||
{
|
||||
return sm3_compress_blocks(digest, block, 1);
|
||||
}
|
||||
|
||||
void sm3(const unsigned char *msg, size_t msglen,
|
||||
unsigned char dgst[SM3_DIGEST_LENGTH])
|
||||
{
|
||||
sm3_ctx_t ctx;
|
||||
|
||||
sm3_init(&ctx);
|
||||
sm3_update(&ctx, msg, msglen);
|
||||
sm3_final(&ctx, dgst);
|
||||
|
||||
memset(&ctx, 0, sizeof(sm3_ctx_t));
|
||||
}
|
||||
|
||||
int sm3_file(char *path, unsigned char output[32])
|
||||
{
|
||||
FILE *f;
|
||||
size_t n;
|
||||
sm3_ctx_t ctx;
|
||||
unsigned char buf[1024];
|
||||
|
||||
if ((f = fopen(path, "rb")) == NULL)
|
||||
return(1);
|
||||
|
||||
sm3_init(&ctx);
|
||||
|
||||
while ((n = fread(buf, 1, sizeof(buf), f)) > 0)
|
||||
sm3_update(&ctx, buf, (int)n);
|
||||
|
||||
sm3_final(&ctx, output);
|
||||
|
||||
memset(&ctx, 0, sizeof(sm3_ctx_t));
|
||||
|
||||
if (ferror(f) != 0)
|
||||
{
|
||||
fclose(f);
|
||||
return(2);
|
||||
}
|
||||
|
||||
fclose(f);
|
||||
return(0);
|
||||
}
|
|
@ -0,0 +1,125 @@
|
|||
/* ====================================================================
|
||||
* Copyright (c) 2014 - 2017 The GmSSL Project. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
*
|
||||
* 2. 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.
|
||||
*
|
||||
* 3. All advertising materials mentioning features or use of this
|
||||
* software must display the following acknowledgment:
|
||||
* "This product includes software developed by the GmSSL Project.
|
||||
* (http://gmssl.org/)"
|
||||
*
|
||||
* 4. The name "GmSSL Project" must not be used to endorse or promote
|
||||
* products derived from this software without prior written
|
||||
* permission. For written permission, please contact
|
||||
* guanzhi1980@gmail.com.
|
||||
*
|
||||
* 5. Products derived from this software may not be called "GmSSL"
|
||||
* nor may "GmSSL" appear in their names without prior written
|
||||
* permission of the GmSSL Project.
|
||||
*
|
||||
* 6. Redistributions of any form whatsoever must retain the following
|
||||
* acknowledgment:
|
||||
* "This product includes software developed by the GmSSL Project
|
||||
* (http://gmssl.org/)"
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE GmSSL PROJECT ``AS IS'' AND ANY
|
||||
* EXPRESSED 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 GmSSL PROJECT OR
|
||||
* ITS 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 <sm3.h>
|
||||
|
||||
/**
|
||||
* HMAC_k(m) = H((k ^ opad), H((k ^ ipad), m))
|
||||
* pseudo-code:
|
||||
* function hmac(key, message)
|
||||
* opad = [0x5c * blocksize]
|
||||
* ipad = [0x36 * blocksize]
|
||||
* if (length(key) > blocksize) then
|
||||
* key = hash(key)
|
||||
* end if
|
||||
* for i from 0 to length(key) - 1 step 1
|
||||
* ipad[i] = ipad[i] XOR key[i]
|
||||
* opad[i] = opad[i] XOR key[i]
|
||||
* end for
|
||||
* return hash(opad || hash(ipad || message))
|
||||
* end function
|
||||
*/
|
||||
|
||||
|
||||
#define IPAD 0x36
|
||||
#define OPAD 0x5C
|
||||
|
||||
void sm3_hmac_init(sm3_hmac_ctx_t *ctx, const unsigned char *key, size_t key_len)
|
||||
{
|
||||
int i;
|
||||
|
||||
if (key_len <= SM3_BLOCK_SIZE) {
|
||||
memcpy(ctx->key, key, key_len);
|
||||
memset(ctx->key + key_len, 0, SM3_BLOCK_SIZE - key_len);
|
||||
} else {
|
||||
sm3_init(&ctx->sm3_ctx);
|
||||
sm3_update(&ctx->sm3_ctx, key, key_len);
|
||||
sm3_final(&ctx->sm3_ctx, ctx->key);
|
||||
memset(ctx->key + SM3_DIGEST_LENGTH, 0,
|
||||
SM3_BLOCK_SIZE - SM3_DIGEST_LENGTH);
|
||||
}
|
||||
for (i = 0; i < SM3_BLOCK_SIZE; i++) {
|
||||
ctx->key[i] ^= IPAD;
|
||||
}
|
||||
|
||||
sm3_init(&ctx->sm3_ctx);
|
||||
sm3_update(&ctx->sm3_ctx, ctx->key, SM3_BLOCK_SIZE);
|
||||
}
|
||||
|
||||
void sm3_hmac_update(sm3_hmac_ctx_t *ctx,
|
||||
const unsigned char *data, size_t data_len)
|
||||
{
|
||||
sm3_update(&ctx->sm3_ctx, data, data_len);
|
||||
}
|
||||
|
||||
void sm3_hmac_final(sm3_hmac_ctx_t *ctx, unsigned char mac[SM3_HMAC_SIZE])
|
||||
{
|
||||
int i;
|
||||
for (i = 0; i < SM3_BLOCK_SIZE; i++) {
|
||||
ctx->key[i] ^= (IPAD ^ OPAD);
|
||||
}
|
||||
sm3_final(&ctx->sm3_ctx, mac);
|
||||
sm3_init(&ctx->sm3_ctx);
|
||||
sm3_update(&ctx->sm3_ctx, ctx->key, SM3_BLOCK_SIZE);
|
||||
sm3_update(&ctx->sm3_ctx, mac, SM3_DIGEST_LENGTH);
|
||||
sm3_final(&ctx->sm3_ctx, mac);
|
||||
}
|
||||
|
||||
void sm3_hmac(const unsigned char *data, size_t data_len,
|
||||
const unsigned char *key, size_t key_len,
|
||||
unsigned char mac[SM3_HMAC_SIZE])
|
||||
{
|
||||
sm3_hmac_ctx_t ctx;
|
||||
sm3_hmac_init(&ctx, key, key_len);
|
||||
sm3_hmac_update(&ctx, data, data_len);
|
||||
sm3_hmac_final(&ctx, mac);
|
||||
memset(&ctx, 0, sizeof(ctx));
|
||||
}
|
||||
|
File diff suppressed because it is too large
Load Diff
|
@ -0,0 +1,265 @@
|
|||
/**
|
||||
* Copyright (c) 2020 AIIT Ubiquitous Team
|
||||
* XiUOS is licensed under Mulan PSL v2.
|
||||
* You can use this software according to the terms and conditions of the Mulan PSL v2.
|
||||
* You may obtain bn1 copy of Mulan PSL v2 at:
|
||||
* http://license.coscl.org.cn/MulanPSL2
|
||||
* THIS SOFTWARE IS PROVIDED ON AN "AS IS" BASIS, WITHOUT WARRANTIES OF ANY KIND,
|
||||
* EITHER EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO NON-INFRINGEMENT,
|
||||
* MERCHANTABILITY OR FIT FOR A PARTICULAR PURPOSE.
|
||||
* See the Mulan PSL v2 for more details.
|
||||
*/
|
||||
|
||||
/**
|
||||
* @file sm4_enc_mode.c
|
||||
* @brief sm4 encry and decrypt functions
|
||||
* @version 1.0
|
||||
* @author AIIT Ubiquitous Team
|
||||
* @date 2021-04-24
|
||||
*/
|
||||
|
||||
#include <sm4.h>
|
||||
|
||||
int ZeroPadding(const uint8_t *input, int ilen, uint8_t *output, int *olen) {
|
||||
int padding_len = 0;
|
||||
if (ilen % 16 == 0) {
|
||||
padding_len = ilen + 16;
|
||||
}
|
||||
else {
|
||||
padding_len = ilen + (16 - ilen % 16);
|
||||
}
|
||||
memset(output, 0x00, sizeof(char) * padding_len);
|
||||
memcpy(output, input, ilen);
|
||||
*olen = padding_len;
|
||||
return *olen;
|
||||
}
|
||||
|
||||
int ZeroUnPadding(uint8_t *input, int *ilen) {
|
||||
if ( *ilen % 16 != 0) {
|
||||
return SM4_BAD_PADDING_FORMAT;
|
||||
}
|
||||
while (*(input + *ilen - 1) == 0x00) {
|
||||
(*ilen)--;
|
||||
}
|
||||
return *ilen;
|
||||
}
|
||||
|
||||
int Pkcs7Padding(const uint8_t *input, int ilen, uint8_t *output , int *olen) {
|
||||
int len_after_Padding;
|
||||
uint8_t padding_value;
|
||||
if (ilen == 0)
|
||||
{
|
||||
return SM4_BAD_LENGTH;
|
||||
}
|
||||
padding_value = 16 - ilen % 16;
|
||||
len_after_Padding = ilen + padding_value;
|
||||
|
||||
memset(output, 0x00, sizeof(char) * len_after_Padding);
|
||||
memcpy(output, input, ilen);
|
||||
for (int i = ilen; i < len_after_Padding; i++) {
|
||||
*(output + i) = padding_value;
|
||||
}
|
||||
*olen = len_after_Padding;
|
||||
return *olen;
|
||||
}
|
||||
|
||||
int Pkcs7UnPadding(uint8_t *input, int *ilen) {
|
||||
if (*ilen % 16 != 0) {
|
||||
return SM4_BAD_PADDING_FORMAT;
|
||||
}
|
||||
uint8_t value = *(input + *ilen - 1);
|
||||
*ilen = *ilen - value;
|
||||
*(input + *ilen) = 0x00;
|
||||
return *ilen;
|
||||
}
|
||||
|
||||
|
||||
void Sms4EcbEncryptBlocks(const uint8_t *in, int ilen, uint8_t *out,
|
||||
const sms4_key_t *key)
|
||||
{
|
||||
int blocks;
|
||||
blocks = ilen / 16;
|
||||
|
||||
while (blocks--) {
|
||||
sms4_encrypt(in, out, key);
|
||||
in += 16;
|
||||
out += 16;
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
void Sms4EcbDecryptBlocks(const uint8_t *in, int ilen, uint8_t *out, const sms4_key_t *key)
|
||||
{
|
||||
int blocks;
|
||||
blocks = ilen / 16;
|
||||
|
||||
while (blocks--) {
|
||||
sms4_decrypt(in, out, key);
|
||||
in += 16;
|
||||
out += 16;
|
||||
}
|
||||
}
|
||||
|
||||
int Sms4EcbDecryptNoPadding(const uint8_t *in, int ilen, uint8_t *out, int *olen , const sms4_key_t *key)
|
||||
{
|
||||
if ( ilen % 16 != 0){
|
||||
return SM4_BAD_LENGTH;
|
||||
}
|
||||
Sms4EcbDecryptBlocks(in ,ilen, out , key );
|
||||
*olen = ilen;
|
||||
return *olen;
|
||||
}
|
||||
|
||||
int Sms4EcbEncryptNoPadding(const uint8_t *in, int ilen, uint8_t *out, int *olen,
|
||||
const sms4_key_t *key)
|
||||
{
|
||||
if ( ilen % 16 != 0){
|
||||
return SM4_BAD_LENGTH;
|
||||
}
|
||||
memset(out, 0x00, sizeof(char) * ilen);
|
||||
Sms4EcbEncryptBlocks(in ,ilen, out , key );
|
||||
*olen = ilen;
|
||||
return *olen;
|
||||
}
|
||||
|
||||
|
||||
int Sms4EcbEncryptZeroPadding(const uint8_t *in, int ilen, uint8_t *out, int *olen,
|
||||
const sms4_key_t *key)
|
||||
{
|
||||
uint8_t *padding_value;
|
||||
int plen;
|
||||
int res ;
|
||||
res = ZeroPadding(in, ilen, out, olen);
|
||||
if (res < 0){
|
||||
return res;
|
||||
}
|
||||
Sms4EcbEncryptBlocks(out, *olen, out, key);
|
||||
return *olen;
|
||||
}
|
||||
|
||||
int Sms4EcbDecryptZeroPadding(const uint8_t *in, int ilen, uint8_t *out, int *olen,
|
||||
const sms4_key_t *key)
|
||||
{
|
||||
int res = 0;
|
||||
Sms4EcbDecryptBlocks(in, ilen, out, key);
|
||||
res = ZeroUnPadding(out, olen);
|
||||
return res;
|
||||
}
|
||||
|
||||
int Sms4EcbEncryptPkcs7Padding(const uint8_t *in, int ilen, uint8_t *out, int *olen,
|
||||
const sms4_key_t *key)
|
||||
{
|
||||
int res;
|
||||
res = Pkcs7Padding(in, ilen, out, olen);
|
||||
if (res < 0) {
|
||||
return res;
|
||||
}
|
||||
Sms4EcbEncryptBlocks(out, *olen, out, key);
|
||||
return *olen;
|
||||
}
|
||||
|
||||
int Sms4EcbDecryptPkcs7Padding(const uint8_t *in, int ilen, uint8_t *out, int *olen,
|
||||
const sms4_key_t *key)
|
||||
{
|
||||
int res;
|
||||
Sms4EcbDecryptBlocks(in, ilen, out, key);
|
||||
res = Pkcs7UnPadding(out, olen);
|
||||
return res;
|
||||
}
|
||||
|
||||
void Sms4CbcEncryptBlocks(const unsigned char *in, int ilen, unsigned char *out,unsigned char *iv,
|
||||
const sms4_key_t *key)
|
||||
{
|
||||
int blocks, i;
|
||||
blocks = ilen / 16;
|
||||
while (blocks--) {
|
||||
for( i = 0; i < 16; i++ )
|
||||
out[i] = (unsigned char)( in[i] ^ iv[i] );
|
||||
sms4_encrypt(out, out, key);
|
||||
memcpy( iv, out, 16 );
|
||||
in += 16;
|
||||
out += 16;
|
||||
}
|
||||
}
|
||||
|
||||
void Sms4CbcDecryptBlocks(const unsigned char *in, int ilen, unsigned char *out,unsigned char *iv,
|
||||
const sms4_key_t *key)
|
||||
{
|
||||
int blocks, i;
|
||||
blocks = ilen / 16;
|
||||
unsigned char temp[16];
|
||||
while (blocks--) {
|
||||
memcpy( temp, in, 16 );
|
||||
sms4_decrypt(in, out, key);
|
||||
for( i = 0; i < 16; i++ )
|
||||
out[i] = (unsigned char)( out[i] ^ iv[i] );
|
||||
memcpy( iv, temp, 16 );
|
||||
in += 16;
|
||||
out += 16;
|
||||
}
|
||||
}
|
||||
|
||||
int Sms4CbcDecryptNoPadding(const uint8_t *in, int ilen, uint8_t *out, int *olen, uint8_t *iv,const sms4_key_t *key)
|
||||
{
|
||||
if ( ilen % 16 != 0){
|
||||
return SM4_BAD_LENGTH;
|
||||
}
|
||||
*olen = ilen;
|
||||
Sms4CbcDecryptBlocks(in , ilen, out ,iv, key );
|
||||
return *olen;
|
||||
}
|
||||
|
||||
int Sms4CbcEncryptNoPadding(const uint8_t *in, int ilen, uint8_t *out, int *olen,uint8_t *iv,
|
||||
const sms4_key_t *key)
|
||||
{
|
||||
if ( ilen % 16 != 0){
|
||||
return SM4_BAD_LENGTH;
|
||||
}
|
||||
*olen = ilen;
|
||||
Sms4CbcEncryptBlocks(in , ilen, out , iv, key );
|
||||
return *olen;
|
||||
}
|
||||
|
||||
int Sms4CbcEncryptZeroPadding(const uint8_t *in, int ilen, uint8_t *out, int *olen, uint8_t *iv,
|
||||
const sms4_key_t *key)
|
||||
{
|
||||
int res ;
|
||||
res = ZeroPadding(in, ilen, out, olen);
|
||||
if (res < 0)
|
||||
return res;
|
||||
Sms4CbcEncryptBlocks(out, *olen, out,iv, key);
|
||||
return *olen;
|
||||
}
|
||||
|
||||
int Sms4CbcDecryptZeroPadding(const uint8_t *in, int ilen, uint8_t *out, int *olen, uint8_t *iv,
|
||||
const sms4_key_t *key)
|
||||
{
|
||||
|
||||
*olen = ilen;
|
||||
int res ;
|
||||
Sms4CbcDecryptBlocks(in, ilen, out,iv, key);
|
||||
res = ZeroUnPadding(out, olen);
|
||||
return res;
|
||||
}
|
||||
|
||||
int Sms4CbcEncryptPkcs7Padding(const uint8_t *in, int ilen, uint8_t *out, int *olen, uint8_t *iv,
|
||||
const sms4_key_t *key)
|
||||
{
|
||||
int res;
|
||||
res = Pkcs7Padding(in, ilen, out, olen);
|
||||
if (res < 0)
|
||||
return res;
|
||||
Sms4CbcEncryptBlocks(out, *olen, out,iv, key);
|
||||
return *olen;
|
||||
}
|
||||
|
||||
int Sms4CbcDecryptPkcs7Padding(const uint8_t *in, int ilen, uint8_t *out, int *olen, uint8_t *iv,
|
||||
const sms4_key_t *key)
|
||||
{
|
||||
*olen = ilen;
|
||||
int res;
|
||||
Sms4CbcDecryptBlocks(in, ilen, out,iv, key);
|
||||
res = Pkcs7UnPadding(out, olen);
|
||||
return res;
|
||||
}
|
||||
|
|
@ -0,0 +1,131 @@
|
|||
/* ====================================================================
|
||||
* Copyright (c) 2014 - 2019 The GmSSL Project. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
*
|
||||
* 2. 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.
|
||||
*
|
||||
* 3. All advertising materials mentioning features or use of this
|
||||
* software must display the following acknowledgment:
|
||||
* "This product includes software developed by the GmSSL Project.
|
||||
* (http://gmssl.org/)"
|
||||
*
|
||||
* 4. The name "GmSSL Project" must not be used to endorse or promote
|
||||
* products derived from this software without prior written
|
||||
* permission. For written permission, please contact
|
||||
* guanzhi1980@gmail.com.
|
||||
*
|
||||
* 5. Products derived from this software may not be called "GmSSL"
|
||||
* nor may "GmSSL" appear in their names without prior written
|
||||
* permission of the GmSSL Project.
|
||||
*
|
||||
* 6. Redistributions of any form whatsoever must retain the following
|
||||
* acknowledgment:
|
||||
* "This product includes software developed by the GmSSL Project
|
||||
* (http://gmssl.org/)"
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE GmSSL PROJECT ``AS IS'' AND ANY
|
||||
* EXPRESSED 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 GmSSL PROJECT OR
|
||||
* ITS 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 <sm4.h>
|
||||
#include "sms4_lcl.h"
|
||||
|
||||
#define L32(x) \
|
||||
((x) ^ \
|
||||
ROL32((x), 2) ^ \
|
||||
ROL32((x), 10) ^ \
|
||||
ROL32((x), 18) ^ \
|
||||
ROL32((x), 24))
|
||||
|
||||
#define ROUND_SBOX(x0, x1, x2, x3, x4, i) \
|
||||
x4 = x1 ^ x2 ^ x3 ^ *(rk + i); \
|
||||
x4 = S32(x4); \
|
||||
x4 = x0 ^ L32(x4)
|
||||
|
||||
#define ROUND_TBOX(x0, x1, x2, x3, x4, i) \
|
||||
x4 = x1 ^ x2 ^ x3 ^ *(rk + i); \
|
||||
t0 = ROL32(SMS4_T[(uint8_t)x4], 8); \
|
||||
x4 >>= 8; \
|
||||
x0 ^= t0; \
|
||||
t0 = ROL32(SMS4_T[(uint8_t)x4], 16); \
|
||||
x4 >>= 8; \
|
||||
x0 ^= t0; \
|
||||
t0 = ROL32(SMS4_T[(uint8_t)x4], 24); \
|
||||
x4 >>= 8; \
|
||||
x0 ^= t0; \
|
||||
t1 = SMS4_T[x4]; \
|
||||
x4 = x0 ^ t1
|
||||
|
||||
#define ROUND_DBOX(x0, x1, x2, x3, x4, i) \
|
||||
x4 = x1 ^ x2 ^ x3 ^ *(rk + i); \
|
||||
x4 = x0 ^ SMS4_D[(uint16_t)(x4 >> 16)] ^ \
|
||||
ROL32(SMS4_D[(uint16_t)x4], 16)
|
||||
|
||||
#define ROUND ROUND_TBOX
|
||||
|
||||
void sms4_encrypt(const unsigned char in[16], unsigned char out[16], const sms4_key_t *key)
|
||||
{
|
||||
const uint *rk = key->rk;
|
||||
uint x0, x1, x2, x3, x4;
|
||||
uint t0, t1;
|
||||
|
||||
x0 = GETU32(in);
|
||||
x1 = GETU32(in + 4);
|
||||
x2 = GETU32(in + 8);
|
||||
x3 = GETU32(in + 12);
|
||||
#define ROUND ROUND_TBOX
|
||||
ROUNDS(x0, x1, x2, x3, x4);
|
||||
|
||||
PUTU32(out, x0);
|
||||
PUTU32(out + 4, x4);
|
||||
PUTU32(out + 8, x3);
|
||||
PUTU32(out + 12, x2);
|
||||
}
|
||||
|
||||
/* caller make sure counter not overflow */
|
||||
void sms4_ctr32_encrypt_blocks(const unsigned char *in, unsigned char *out,
|
||||
int blocks, const sms4_key_t *key, const unsigned char iv[16])
|
||||
{
|
||||
const uint *rk = key->rk;
|
||||
unsigned int c0 = GETU32(iv);
|
||||
unsigned int c1 = GETU32(iv + 4);
|
||||
unsigned int c2 = GETU32(iv + 8);
|
||||
unsigned int c3 = GETU32(iv + 12);
|
||||
uint x0, x1, x2, x3, x4;
|
||||
uint t0, t1;
|
||||
|
||||
while (blocks--) {
|
||||
x0 = c0;
|
||||
x1 = c1;
|
||||
x2 = c2;
|
||||
x3 = c3;
|
||||
ROUNDS(x0, x1, x2, x3, x4);
|
||||
PUTU32(out, GETU32(in) ^ x0);
|
||||
PUTU32(out + 4, GETU32(in + 4) ^ x4);
|
||||
PUTU32(out + 8, GETU32(in + 8) ^ x3);
|
||||
PUTU32(out + 12, GETU32(in + 12) ^ x2);
|
||||
in += 16;
|
||||
out += 16;
|
||||
c3++;
|
||||
}
|
||||
}
|
|
@ -0,0 +1,103 @@
|
|||
/* ====================================================================
|
||||
* Copyright (c) 2014 - 2019 The GmSSL Project. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
*
|
||||
* 2. 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.
|
||||
*
|
||||
* 3. All advertising materials mentioning features or use of this
|
||||
* software must display the following acknowledgment:
|
||||
* "This product includes software developed by the GmSSL Project.
|
||||
* (http://gmssl.org/)"
|
||||
*
|
||||
* 4. The name "GmSSL Project" must not be used to endorse or promote
|
||||
* products derived from this software without prior written
|
||||
* permission. For written permission, please contact
|
||||
* guanzhi1980@gmail.com.
|
||||
*
|
||||
* 5. Products derived from this software may not be called "GmSSL"
|
||||
* nor may "GmSSL" appear in their names without prior written
|
||||
* permission of the GmSSL Project.
|
||||
*
|
||||
* 6. Redistributions of any form whatsoever must retain the following
|
||||
* acknowledgment:
|
||||
* "This product includes software developed by the GmSSL Project
|
||||
* (http://gmssl.org/)"
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE GmSSL PROJECT ``AS IS'' AND ANY
|
||||
* EXPRESSED 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 GmSSL PROJECT OR
|
||||
* ITS 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 HEADER_SMS4_LCL_H
|
||||
#define HEADER_SMS4_LCL_H
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
# define ROL32(a,n) (((a)<<(n))|(((a)&0xffffffff)>>(32-(n))))
|
||||
# define GETU32(p) ((uint)(p)[0]<<24|(uint)(p)[1]<<16|(uint)(p)[2]<<8|(uint)(p)[3])
|
||||
# define PUTU32(p,v) ((p)[0]=(uint8_t)((v)>>24),(p)[1]=(uint8_t)((v)>>16),(p)[2]=(uint8_t)((v)>>8),(p)[3]=(uint8_t)(v))
|
||||
|
||||
extern const uint8_t SMS4_S[256];
|
||||
extern const uint32_t SMS4_T[256];
|
||||
extern const uint32_t SMS4_D[65536];
|
||||
|
||||
#define S32(A) \
|
||||
((SMS4_S[((A) >> 24) ] << 24) ^ \
|
||||
(SMS4_S[((A) >> 16) & 0xff] << 16) ^ \
|
||||
(SMS4_S[((A) >> 8) & 0xff] << 8) ^ \
|
||||
(SMS4_S[((A)) & 0xff]))
|
||||
|
||||
#define ROUNDS(x0, x1, x2, x3, x4) \
|
||||
ROUND(x0, x1, x2, x3, x4, 0); \
|
||||
ROUND(x1, x2, x3, x4, x0, 1); \
|
||||
ROUND(x2, x3, x4, x0, x1, 2); \
|
||||
ROUND(x3, x4, x0, x1, x2, 3); \
|
||||
ROUND(x4, x0, x1, x2, x3, 4); \
|
||||
ROUND(x0, x1, x2, x3, x4, 5); \
|
||||
ROUND(x1, x2, x3, x4, x0, 6); \
|
||||
ROUND(x2, x3, x4, x0, x1, 7); \
|
||||
ROUND(x3, x4, x0, x1, x2, 8); \
|
||||
ROUND(x4, x0, x1, x2, x3, 9); \
|
||||
ROUND(x0, x1, x2, x3, x4, 10); \
|
||||
ROUND(x1, x2, x3, x4, x0, 11); \
|
||||
ROUND(x2, x3, x4, x0, x1, 12); \
|
||||
ROUND(x3, x4, x0, x1, x2, 13); \
|
||||
ROUND(x4, x0, x1, x2, x3, 14); \
|
||||
ROUND(x0, x1, x2, x3, x4, 15); \
|
||||
ROUND(x1, x2, x3, x4, x0, 16); \
|
||||
ROUND(x2, x3, x4, x0, x1, 17); \
|
||||
ROUND(x3, x4, x0, x1, x2, 18); \
|
||||
ROUND(x4, x0, x1, x2, x3, 19); \
|
||||
ROUND(x0, x1, x2, x3, x4, 20); \
|
||||
ROUND(x1, x2, x3, x4, x0, 21); \
|
||||
ROUND(x2, x3, x4, x0, x1, 22); \
|
||||
ROUND(x3, x4, x0, x1, x2, 23); \
|
||||
ROUND(x4, x0, x1, x2, x3, 24); \
|
||||
ROUND(x0, x1, x2, x3, x4, 25); \
|
||||
ROUND(x1, x2, x3, x4, x0, 26); \
|
||||
ROUND(x2, x3, x4, x0, x1, 27); \
|
||||
ROUND(x3, x4, x0, x1, x2, 28); \
|
||||
ROUND(x4, x0, x1, x2, x3, 29); \
|
||||
ROUND(x0, x1, x2, x3, x4, 30); \
|
||||
ROUND(x1, x2, x3, x4, x0, 31)
|
||||
|
||||
#endif
|
|
@ -0,0 +1,119 @@
|
|||
/* ====================================================================
|
||||
* Copyright (c) 2014 - 2019 The GmSSL Project. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
*
|
||||
* 2. 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.
|
||||
*
|
||||
* 3. All advertising materials mentioning features or use of this
|
||||
* software must display the following acknowledgment:
|
||||
* "This product includes software developed by the GmSSL Project.
|
||||
* (http://gmssl.org/)"
|
||||
*
|
||||
* 4. The name "GmSSL Project" must not be used to endorse or promote
|
||||
* products derived from this software without prior written
|
||||
* permission. For written permission, please contact
|
||||
* guanzhi1980@gmail.com.
|
||||
*
|
||||
* 5. Products derived from this software may not be called "GmSSL"
|
||||
* nor may "GmSSL" appear in their names without prior written
|
||||
* permission of the GmSSL Project.
|
||||
*
|
||||
* 6. Redistributions of any form whatsoever must retain the following
|
||||
* acknowledgment:
|
||||
* "This product includes software developed by the GmSSL Project
|
||||
* (http://gmssl.org/)"
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE GmSSL PROJECT ``AS IS'' AND ANY
|
||||
* EXPRESSED 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 GmSSL PROJECT OR
|
||||
* ITS 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 "sms4_lcl.h"
|
||||
#include <sm4.h>
|
||||
#include <stdint.h>
|
||||
|
||||
static uint FK[4] = {
|
||||
0xa3b1bac6, 0x56aa3350, 0x677d9197, 0xb27022dc,
|
||||
};
|
||||
|
||||
static uint CK[32] = {
|
||||
0x00070e15, 0x1c232a31, 0x383f464d, 0x545b6269,
|
||||
0x70777e85, 0x8c939aa1, 0xa8afb6bd, 0xc4cbd2d9,
|
||||
0xe0e7eef5, 0xfc030a11, 0x181f262d, 0x343b4249,
|
||||
0x50575e65, 0x6c737a81, 0x888f969d, 0xa4abb2b9,
|
||||
0xc0c7ced5, 0xdce3eaf1, 0xf8ff060d, 0x141b2229,
|
||||
0x30373e45, 0x4c535a61, 0x686f767d, 0x848b9299,
|
||||
0xa0a7aeb5, 0xbcc3cad1, 0xd8dfe6ed, 0xf4fb0209,
|
||||
0x10171e25, 0x2c333a41, 0x484f565d, 0x646b7279,
|
||||
};
|
||||
|
||||
|
||||
#define L32_(x) \
|
||||
((x) ^ \
|
||||
ROL32((x), 13) ^ \
|
||||
ROL32((x), 23))
|
||||
|
||||
#define ENC_ROUND(x0, x1, x2, x3, x4, i) \
|
||||
x4 = x1 ^ x2 ^ x3 ^ *(CK + i); \
|
||||
x4 = S32(x4); \
|
||||
x4 = x0 ^ L32_(x4); \
|
||||
*(rk + i) = x4
|
||||
|
||||
#define DEC_ROUND(x0, x1, x2, x3, x4, i) \
|
||||
x4 = x1 ^ x2 ^ x3 ^ *(CK + i); \
|
||||
x4 = S32(x4); \
|
||||
x4 = x0 ^ L32_(x4); \
|
||||
*(rk + 31 - i) = x4
|
||||
|
||||
void sms4_set_encrypt_key(sms4_key_t *key, const unsigned char user_key[16])
|
||||
{
|
||||
uint *rk = key->rk;
|
||||
uint x0, x1, x2, x3, x4;
|
||||
|
||||
x0 = GETU32(user_key) ^ FK[0];
|
||||
x1 = GETU32(user_key + 4) ^ FK[1];
|
||||
x2 = GETU32(user_key + 8) ^ FK[2];
|
||||
x3 = GETU32(user_key + 12) ^ FK[3];
|
||||
|
||||
#define ROUND ENC_ROUND
|
||||
ROUNDS(x0, x1, x2, x3, x4);
|
||||
#undef ROUND
|
||||
|
||||
x0 = x1 = x2 = x3 = x4 = 0;
|
||||
}
|
||||
|
||||
void sms4_set_decrypt_key(sms4_key_t *key, const unsigned char user_key[16])
|
||||
{
|
||||
uint *rk = key->rk;
|
||||
uint x0, x1, x2, x3, x4;
|
||||
|
||||
x0 = GETU32(user_key) ^ FK[0];
|
||||
x1 = GETU32(user_key + 4) ^ FK[1];
|
||||
x2 = GETU32(user_key + 8) ^ FK[2];
|
||||
x3 = GETU32(user_key + 12) ^ FK[3];
|
||||
|
||||
#define ROUND DEC_ROUND
|
||||
ROUNDS(x0, x1, x2, x3, x4);
|
||||
#undef ROUND
|
||||
|
||||
x0 = x1 = x2 = x3 = x4 = 0;
|
||||
}
|
|
@ -0,0 +1,719 @@
|
|||
/**
|
||||
* Copyright (c) 2020 AIIT Ubiquitous Team
|
||||
* XiUOS is licensed under Mulan PSL v2.
|
||||
* You can use this software according to the terms and conditions of the Mulan PSL v2.
|
||||
* You may obtain bn1 copy of Mulan PSL v2 at:
|
||||
* http://license.coscl.org.cn/MulanPSL2
|
||||
* THIS SOFTWARE IS PROVIDED ON AN "AS IS" BASIS, WITHOUT WARRANTIES OF ANY KIND,
|
||||
* EITHER EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO NON-INFRINGEMENT,
|
||||
* MERCHANTABILITY OR FIT FOR A PARTICULAR PURPOSE.
|
||||
* See the Mulan PSL v2 for more details.
|
||||
*/
|
||||
|
||||
/**
|
||||
* @file bignum.c
|
||||
* @brief arithmetic of big number
|
||||
* @version 1.0
|
||||
* @author AIIT Ubiquitous Team
|
||||
* @date 2021-04-24
|
||||
*/
|
||||
|
||||
#include <bignum.h>
|
||||
|
||||
sm9curve curve;
|
||||
// used in Montgomery Mult
|
||||
uint32_t qlow_reverse = 0x2f2ee42b; // power(2, 32) - (curve.q.word[0] 's reverse under power(2, 32))
|
||||
uint32_t Nlow_reverse = 0x51974b53; // power(2, 32) - (curve.N.word[0] 's reverse under power(2, 32))
|
||||
big8w q_2k; // (2^(256*2)) mod curve.q; used in big numbers' mult(Montgomery Mult)
|
||||
big8w N_2k; // (2^(256*2)) mod curve.N; used in big numbers' mult(Montgomery Mult)
|
||||
|
||||
/**
|
||||
* @brief This function is to print the big number in hex.
|
||||
*
|
||||
* @param bignum pointer of a big number
|
||||
*
|
||||
* @return null
|
||||
*
|
||||
*/
|
||||
void Big8wPrint(big8w* bignum)
|
||||
{
|
||||
int i = BIGNUMBER_SIZE_8WORD - 1;
|
||||
while (bignum->word[i] == 0 && i >= 0)
|
||||
i--;
|
||||
if (i < 0) {
|
||||
KPrintf("0x00\n");
|
||||
return;
|
||||
}
|
||||
|
||||
KPrintf("0x %08x", bignum->word[i]);
|
||||
|
||||
if(i--) // i > 0
|
||||
for (; i>=0; i--)
|
||||
KPrintf(" %08x", bignum->word[i]);
|
||||
|
||||
KPrintf("\n");
|
||||
}
|
||||
/**
|
||||
* @brief This function is to get the index of highest bit of highest word.
|
||||
*
|
||||
* @param bignum pointer of a big number
|
||||
*
|
||||
* @return null
|
||||
*
|
||||
*/
|
||||
uint8_t Big8wHighestbit(big8w* bignum)
|
||||
{
|
||||
uint8_t i = BIGNUMBER_SIZE_8WORD - 1;
|
||||
uint32_t elem;
|
||||
|
||||
while (bignum->word[i] == 0 && i >= 0)
|
||||
i--;
|
||||
elem = bignum->word[i];
|
||||
|
||||
i = 32;
|
||||
while(--i)
|
||||
if ((elem >> i) & 1)
|
||||
break;
|
||||
|
||||
return i;
|
||||
}
|
||||
/**
|
||||
*
|
||||
* @brief This function is to judge if a big number is zero
|
||||
*
|
||||
* @param bignum pointer of a big number
|
||||
*
|
||||
* @return true if bignum == 0; else false
|
||||
*
|
||||
*/
|
||||
bool Big8wIsZero(big8w* bignum)
|
||||
{
|
||||
char i = 0;
|
||||
|
||||
for (i = 0; i < BIGNUMBER_SIZE_8WORD; i++)
|
||||
if (bignum->word[i])
|
||||
return false;
|
||||
|
||||
return true;
|
||||
}
|
||||
/**
|
||||
*
|
||||
* @brief return bn1 >= bn2
|
||||
*
|
||||
* @param bn1 the first big number
|
||||
* @param bn2 the second big number
|
||||
*
|
||||
* @return true if bn1 >= bn2; false if bn1 < bn2
|
||||
*
|
||||
*/
|
||||
bool Big8wBigThan(big8w* bn1, big8w* bn2)
|
||||
{
|
||||
uint8_t i = BIGNUMBER_SIZE_8WORD - 1;
|
||||
|
||||
for (; i; i--) {
|
||||
if (bn1->word[i] > bn2->word[i])
|
||||
return true;
|
||||
|
||||
else if (bn1->word[i] < bn2->word[i])
|
||||
return false;
|
||||
}
|
||||
|
||||
return bn1->word[i] >= bn2->word[i];
|
||||
}
|
||||
/**
|
||||
* @brief reutrn bn1 == bn2
|
||||
*
|
||||
* @param bn1 the first big number
|
||||
* @param bn2 the second big number
|
||||
*
|
||||
* @return true if bn1 == bn2; else false
|
||||
*
|
||||
*/
|
||||
bool Big8wEqual(big8w* bn1, big8w* bn2)
|
||||
{
|
||||
uint8_t i = BIGNUMBER_SIZE_8WORD - 1;
|
||||
|
||||
for (; i; i--)
|
||||
if (bn1->word[i] != bn2->word[i])
|
||||
return false;
|
||||
|
||||
return bn1->word[i] == bn2->word[i];
|
||||
}
|
||||
/**
|
||||
* @brief compute (bn1 - bn2)%p
|
||||
*
|
||||
* @param bn1 the first big number, smaller than p
|
||||
* @param bn2 the second big number, smaller than p
|
||||
* @param p a big number, the module number
|
||||
*
|
||||
* @return ret, a big number
|
||||
*/
|
||||
big8w Big8wMinusMod(big8w bn1, big8w bn2, big8w p)
|
||||
{
|
||||
bool borrow = 0;
|
||||
char i = 0;
|
||||
big8w ret;
|
||||
|
||||
memset(ret.word, 0x00, BIG8W_BYTESIZE);
|
||||
|
||||
if (Big8wEqual(&bn2, &bn1))
|
||||
return ret;
|
||||
|
||||
else if (Big8wBigThan(&bn2, &bn1)) { // p - (bn2 - bn1)
|
||||
ret = Big8wMinusMod(bn2, bn1, p);
|
||||
ret = Big8wMinusMod(p, ret, p);
|
||||
return ret;
|
||||
}
|
||||
|
||||
borrow = 0;
|
||||
for (i = 0; i < BIGNUMBER_SIZE_8WORD; i++){
|
||||
ret.word[i] = bn1.word[i] - bn2.word[i] - borrow;
|
||||
borrow = (ret.word[i] < bn1.word[i] || ((ret.word[i] == bn1.word[i]) && borrow == 0)) ? 0 : 1;
|
||||
}
|
||||
|
||||
return ret;
|
||||
}
|
||||
/**
|
||||
* @brief compute (bn1 + bn2)%p
|
||||
*
|
||||
* @param bn1 the first big number
|
||||
* @param bn2 the second big number
|
||||
* @param p a big number, the module number
|
||||
*
|
||||
* @return ret, a big number
|
||||
*
|
||||
*/
|
||||
big8w Big8wAddMod(big8w bn1, big8w bn2, big8w p)
|
||||
{
|
||||
bool flag = 0;
|
||||
uint8_t i = 0;
|
||||
big8w ret;
|
||||
|
||||
memset(ret.word, 0x00, BIG8W_BYTESIZE);
|
||||
|
||||
for (i = 0; i < BIGNUMBER_SIZE_8WORD; i++){
|
||||
ret.word[i] = bn1.word[i] + bn2.word[i] + flag;
|
||||
flag = (
|
||||
(ret.word[i] > bn1.word[i] && ret.word[i] > bn2.word[i] )
|
||||
|| ((ret.word[i]==bn1.word[i] ||ret.word[i]==bn2.word[i]) && flag == 0)
|
||||
) ? 0 : 1;
|
||||
}
|
||||
|
||||
if (flag) {
|
||||
// (2^(32*8)) + ret - p = (2^(32*8)-1) - (p - ret) + 1
|
||||
// ret = p - ret
|
||||
ret = Big8wMinusMod(p, ret, p);
|
||||
|
||||
// ret = (2^(32*8)-1) - (p - ret)
|
||||
for (i = 0; i < BIGNUMBER_SIZE_8WORD; i++)
|
||||
ret.word[i] = 0xffffffff - ret.word[i];
|
||||
|
||||
// ret++
|
||||
i = 0;
|
||||
while (i < BIGNUMBER_SIZE_8WORD && ret.word[i] == 0xffffffff)
|
||||
i++;
|
||||
ret.word[i]++; // plus one
|
||||
if (i)
|
||||
while (--i)
|
||||
ret.word[i] = 0;
|
||||
}
|
||||
|
||||
if (Big8wBigThan(&ret, &p))
|
||||
ret = Big8wMinusMod(ret, p, p);
|
||||
|
||||
return ret;
|
||||
}
|
||||
/**
|
||||
* @brief big number << (kround * 32 + rest), result store in big16w
|
||||
*
|
||||
* @param bignum a big number
|
||||
* @param kround (left shift bits) // 32
|
||||
* @param rest (left shift bits) % 32
|
||||
* @param length length of bignum, size = unsigned int
|
||||
* @param highestbit index of the highest bit of highest word of bignum, 0 <= highest <= 31
|
||||
*
|
||||
* @return ret, 16word big number
|
||||
*
|
||||
*/
|
||||
big16w Big16wLeftShift(big8w bignum, uint8_t kround, uint8_t rest, uint8_t length, uint8_t highestbit)
|
||||
{
|
||||
char i = 0;
|
||||
big16w ret;
|
||||
memset(ret.word, 0x00, BIG8W_BYTESIZE * 2);
|
||||
|
||||
for (i = 0; i <= length; i++)
|
||||
ret.word[i + kround] = bignum.word[i];
|
||||
ret.length = length + kround;
|
||||
|
||||
if (rest) {
|
||||
if (rest + highestbit > 31)
|
||||
ret.length++;
|
||||
for (i = ret.length; i >kround; i--)
|
||||
ret.word[i] = ret.word[i] << rest | ret.word[i - 1] >> (32 - rest);
|
||||
ret.word[i] <<= rest;
|
||||
}
|
||||
|
||||
return ret;
|
||||
}
|
||||
/**
|
||||
* @brief This function is to get the index of highest bit of highest word of a big number of 16word size.
|
||||
*
|
||||
* @param bignum16w pointer of a big number of 16word size.
|
||||
*
|
||||
* @return ret, unsigned char
|
||||
*
|
||||
*/
|
||||
uint8_t Big16wHighestbit(big16w bignum16w)
|
||||
{
|
||||
uint8_t ret = 31;
|
||||
uint32_t elem = bignum16w.word[bignum16w.length];
|
||||
|
||||
if (bignum16w.length == 0 && bignum16w.word[bignum16w.length] == 0)
|
||||
return 0;
|
||||
|
||||
while (true) {
|
||||
if (((elem >> ret) & 1) == 0)
|
||||
ret--;
|
||||
else
|
||||
return ret;
|
||||
} // end while
|
||||
|
||||
}
|
||||
/**
|
||||
* @brief return bn1 >= bn2
|
||||
*
|
||||
* @param bn1 the first big number of 16word size.
|
||||
* @param bn2 the second big number of 16word size.
|
||||
*
|
||||
* @return true if bn1 >= bn2; else false
|
||||
*
|
||||
*/
|
||||
bool Big16wBigThan(big16w bn1, big16w bn2)
|
||||
{
|
||||
uint8_t i;
|
||||
|
||||
if (bn1.length > bn2.length)
|
||||
return true;
|
||||
else if (bn1.length < bn2.length)
|
||||
return false;
|
||||
|
||||
for (i = bn1.length; i > 0; i--){
|
||||
if (bn1.word[i] > bn2.word[i])
|
||||
return true;
|
||||
else if (bn1.word[i] < bn2.word[i])
|
||||
return false;
|
||||
}
|
||||
|
||||
return bn1.word[0] >= bn2.word[0];
|
||||
}
|
||||
/**
|
||||
* @brief return (bn1 - bn2)
|
||||
*
|
||||
* @param bn1 the first big number of 16word size.
|
||||
* @param bn2 the second big number of 16word size.
|
||||
*
|
||||
* @return (bn1 - bn2), a big numbe of 16word size
|
||||
*
|
||||
*/
|
||||
big16w Big16wMinus(big16w bn1, big16w bn2)
|
||||
{
|
||||
bool borrow;
|
||||
char len = bn1.length;
|
||||
int i = 0;
|
||||
big16w ret;
|
||||
|
||||
memset(ret.word, 0x00, BIG8W_BYTESIZE * 2);
|
||||
|
||||
borrow = 0;
|
||||
for (i = 0; i <= bn1.length; i++){
|
||||
ret.word[i] = bn1.word[i] - bn2.word[i] - borrow;
|
||||
borrow = (ret.word[i] < bn1.word[i] || ((ret.word[i] == bn1.word[i]) && borrow == 0)) ? 0 : 1;
|
||||
}
|
||||
|
||||
i = bn1.length;
|
||||
while (ret.word[i] == 0)
|
||||
i--;
|
||||
ret.length = i;
|
||||
if (i < 0)
|
||||
ret.length = 0;
|
||||
|
||||
return ret;
|
||||
}
|
||||
/**
|
||||
*
|
||||
* @brief This function is only called by function H(), which is in topfunc.h
|
||||
* while(bignum16w.length > 7) // bignum16w > p
|
||||
* bignum16w = bignum16w - (p << gap) or bignum16w = (p << gap) - bignum16w, turn = !turn
|
||||
*
|
||||
* if (turn) // bignum16w == (p - bignum16w) mod p, bignum16w == (- ret) mod p
|
||||
* bignum16w = p - bignum16w
|
||||
*
|
||||
* @param bignum16w big number of 16word size.
|
||||
* @param p big number, the module number.
|
||||
*
|
||||
* @return bignum16w % p.
|
||||
*
|
||||
*/
|
||||
big8w Big16wmod8w(big16w bignum16w, big8w p)
|
||||
{
|
||||
bool turn = false;
|
||||
char plen = 7;
|
||||
char pbit = Big8wHighestbit(&p);
|
||||
int gap;
|
||||
big8w ret;
|
||||
big16w temp;
|
||||
|
||||
memset(ret.word, 0x00, BIG8W_BYTESIZE);
|
||||
|
||||
while (p.word[plen] == 0)
|
||||
plen--;
|
||||
|
||||
while (bignum16w.length > 7){
|
||||
gap = bignum16w.length * 32 + Big16wHighestbit(bignum16w) - 255; // 255 = bitlen of p
|
||||
temp = Big16wLeftShift(p, gap >> 5, gap & 0x1f, plen, pbit);
|
||||
if (Big16wBigThan(bignum16w, temp))
|
||||
bignum16w = Big16wMinus(bignum16w, temp);
|
||||
else {
|
||||
bignum16w = Big16wMinus(temp, bignum16w);
|
||||
turn = !turn;
|
||||
}// end else
|
||||
}
|
||||
|
||||
for (gap = 7; gap >= 0; gap--)
|
||||
ret.word[gap] = bignum16w.word[gap];
|
||||
while (Big8wBigThan(&ret, &p))
|
||||
ret = Big8wMinusMod(ret, p, p);
|
||||
if (turn)
|
||||
ret = Big8wMinusMod(p, ret, p);
|
||||
|
||||
return ret;
|
||||
}
|
||||
/**
|
||||
* @brief big number right shift
|
||||
*
|
||||
* @param bignum big number
|
||||
* @param round bit length of big number to right shift
|
||||
*
|
||||
* @return big number = (bignum >> round)
|
||||
*
|
||||
*/
|
||||
big8w Big8wRightShift(big8w bignum, uint8_t round)
|
||||
{
|
||||
uint8_t kround = round >> 5;
|
||||
uint8_t rest = round & 0x1f;
|
||||
char i;
|
||||
big8w ret;
|
||||
memset(ret.word, 0x00, BIG8W_BYTESIZE);
|
||||
|
||||
for (i = 0; i < BIGNUMBER_SIZE_8WORD - kround; i++)
|
||||
ret.word[i] = bignum.word[i + kround];
|
||||
|
||||
if (rest) {
|
||||
if (kround) {
|
||||
for (i = 0; i < BIGNUMBER_SIZE_8WORD - kround; i++) {
|
||||
ret.word[i] = (ret.word[i] >> rest) | (ret.word[i + 1] << (32 - rest));
|
||||
} // end for
|
||||
}else {
|
||||
for (i = 0; i < BIGNUMBER_SIZE_8WORD - 1; i++) {
|
||||
ret.word[i] = (ret.word[i] >> rest) | (ret.word[i + 1] << (32 - rest));
|
||||
} // end for
|
||||
ret.word[7] >>= rest;
|
||||
}
|
||||
} // end if
|
||||
|
||||
return ret;
|
||||
}
|
||||
/**
|
||||
*
|
||||
* @brief return (bignum + N)>>1. (bignum + N) is even. only called by Big8wReverse, more in Big8wReverse
|
||||
*
|
||||
* @param bignum the first big number
|
||||
* @param N the second big number
|
||||
*
|
||||
* @return a big number = (bignum + N) >> 1.
|
||||
*
|
||||
*/
|
||||
big8w PlusAndRightShiftOne(big8w bignum, big8w N)
|
||||
{
|
||||
bool flag = 0;
|
||||
uint8_t i = 0;
|
||||
big8w ret;
|
||||
|
||||
memset(ret.word, 0x00, BIG8W_BYTESIZE);
|
||||
|
||||
for (i = 0; i < BIGNUMBER_SIZE_8WORD; i++) {
|
||||
ret.word[i] = bignum.word[i] + N.word[i] + flag;
|
||||
|
||||
flag = (
|
||||
(ret.word[i] > bignum.word[i] && ret.word[i] > N.word[i])
|
||||
|| ((ret.word[i] == bignum.word[i] || ret.word[i] == N.word[i]) && flag == 0)
|
||||
) ? 0 : 1;
|
||||
}
|
||||
|
||||
ret = Big8wRightShift(ret, 1);
|
||||
if (flag)
|
||||
ret.word[7] |= 0x80000000;
|
||||
|
||||
return ret;
|
||||
}
|
||||
/**
|
||||
*
|
||||
* @brief get reverse of bignum under N; implemented with Stein algorithm.
|
||||
* Calls: Big8wRightShift, PlusAndRightShiftOne, Big8wEqual, Big8wMinusMod
|
||||
*
|
||||
* @param bignum a big number
|
||||
* @param N a big prime number
|
||||
*
|
||||
* @return a big number = (bignum)^(-1) mod N
|
||||
*
|
||||
*/
|
||||
big8w Big8wReverse(big8w bignum, big8w N)
|
||||
{
|
||||
bool flag1, flag2;
|
||||
big8w ret, zero, one, x1, y1, x2, y2, temp;
|
||||
|
||||
memset(ret.word, 0x00, BIG8W_BYTESIZE);
|
||||
memset(zero.word, 0x00, BIG8W_BYTESIZE);
|
||||
memset(one.word, 0x00, BIG8W_BYTESIZE);
|
||||
|
||||
one.word[0] = 1;
|
||||
|
||||
x1 = bignum, y1 = one;
|
||||
x2 = N, y2 = zero;
|
||||
|
||||
while (true){
|
||||
flag1 = ((x1.word[0]&1) == 0), flag2 = ((y1.word[0]&1) == 0);
|
||||
if (flag1 && flag2) {
|
||||
x1 = Big8wRightShift(x1, 1);
|
||||
y1 = Big8wRightShift(y1, 1);
|
||||
}
|
||||
else if (flag1 && !flag2) {
|
||||
x1 = Big8wRightShift(x1, 1);
|
||||
y1 = PlusAndRightShiftOne(y1, N);
|
||||
}
|
||||
if (Big8wEqual(&x1, &one))
|
||||
return y1;
|
||||
|
||||
flag1 = ((x2.word[0]&1) == 0), flag2 = ((y2.word[0]&1) == 0);
|
||||
if (flag1 && flag2) {
|
||||
x2 = Big8wRightShift(x2, 1);
|
||||
y2 = Big8wRightShift(y2, 1);
|
||||
}
|
||||
else if (flag1 && !flag2) {
|
||||
x2 = Big8wRightShift(x2, 1);
|
||||
y2 = PlusAndRightShiftOne(y2, N);
|
||||
}
|
||||
if (Big8wEqual(&x2, &one))
|
||||
return y2;
|
||||
|
||||
if (Big8wBigThan(&x1, &x2)) {
|
||||
x1 = Big8wMinusMod(x1, x2, N);
|
||||
y1 = Big8wMinusMod(y1, y2, N);
|
||||
if (Big8wEqual(&x1, &one))
|
||||
return y1;
|
||||
}
|
||||
else {
|
||||
x2 = Big8wMinusMod(x2, x1, N);
|
||||
y2 = Big8wMinusMod(y2, y1, N);
|
||||
if (Big8wEqual(&x2, &one))
|
||||
return y2;
|
||||
}
|
||||
|
||||
} // end while
|
||||
}
|
||||
/**
|
||||
*
|
||||
* @brief return bn1 >= bn2
|
||||
*
|
||||
* @param bn1 string of unsigned int, length <= BIGNUMBER_SIZE + 1.
|
||||
* @param bn2 string of unsigned int, length <= BIGNUMBER_SIZE + 1.
|
||||
*
|
||||
* @return true if bn1 >= bn2; else false
|
||||
*
|
||||
*/
|
||||
bool U32CMP(uint32_t* bn1, uint32_t* bn2)
|
||||
{
|
||||
int i;
|
||||
|
||||
for (i = BIGNUMBER_SIZE_8WORD + 1; i; i--) {
|
||||
if (bn1[i] > bn2[i])
|
||||
return true;
|
||||
else if (bn1[i] < bn2[i])
|
||||
return false;
|
||||
}
|
||||
|
||||
return bn1[0] >= bn2[0];
|
||||
}
|
||||
/**
|
||||
* @brief This function is to compute a big number multiply a unsinged int number.
|
||||
*
|
||||
* @param bignum big number
|
||||
* @param elem unsigned int
|
||||
* @param ret pointer of a string of unsigned int, length <= BIGNUMBER_SIZE_WORD + 2. store the result.
|
||||
*
|
||||
* @result ret = bignum * elem,
|
||||
*
|
||||
*/
|
||||
void Big8wMultNum(big8w bignum, uint32_t elem, uint32_t* ret)
|
||||
{
|
||||
char i = 0;
|
||||
uint32_t overflow = 0;
|
||||
uint64_t temp;
|
||||
|
||||
memset(ret, 0x00, sizeof(uint32_t) * (BIGNUMBER_SIZE_8WORD + 2));
|
||||
|
||||
for (i = 0; i < BIGNUMBER_SIZE_8WORD; i++) {
|
||||
temp = ((uint64_t)elem * (uint64_t)bignum.word[i]) + (uint64_t)overflow;
|
||||
ret[i] = temp;
|
||||
overflow = temp >> 32;
|
||||
}
|
||||
|
||||
ret[BIGNUMBER_SIZE_8WORD] = overflow;
|
||||
}
|
||||
/**
|
||||
* @brief add two unsigned int strings.
|
||||
*
|
||||
* @param bn1 string of unsigned int, lenght < BIGNUMBER_SIZE_8WORD + 2
|
||||
* @param bn2 string of unsigned int, lenght < BIGNUMBER_SIZE_8WORD + 2
|
||||
* @param ret string of unsigned int, lenght < BIGNUMBER_SIZE_8WORD + 2, store the result
|
||||
*
|
||||
* @result ret, string of unsigned int
|
||||
*/
|
||||
void U32Add(uint32_t* bn1, uint32_t* bn2, uint32_t* ret)
|
||||
{
|
||||
char i;
|
||||
bool overflow = 0;
|
||||
uint64_t temp;
|
||||
|
||||
for (i = 0; i < BIGNUMBER_SIZE_8WORD + 2; i++){
|
||||
temp = (uint64_t)bn1[i] + (uint64_t)bn2[i] + (uint64_t)overflow;
|
||||
ret[i] = temp;
|
||||
overflow = temp >> 32;
|
||||
}
|
||||
}
|
||||
/**
|
||||
* @brief two unsigned int strings run minus.
|
||||
*
|
||||
* @param bn1 the first string of unsigned int, lenght <= BIGNUMBER_SIZE_8WORD + 2
|
||||
* @param bn2 the second string of unsigned int, lenght <= BIGNUMBER_SIZE_8WORD + 2
|
||||
* @param ret the result string of unsigned int, lenght <= BIGNUMBER_SIZE_8WORD + 2, store the result
|
||||
*
|
||||
* @result ret
|
||||
*/
|
||||
void U32Minus(uint32_t* bn1, uint32_t* bn2, uint32_t* ret)
|
||||
{
|
||||
char i;
|
||||
bool borrow = 0, newborrow;
|
||||
|
||||
for (i = 0; i < BIGNUMBER_SIZE_8WORD + 2; i++){
|
||||
newborrow = (uint64_t)bn1[i] < ((uint64_t)bn2[i] + borrow);
|
||||
ret[i] = bn1[i] - bn2[i] - borrow;
|
||||
borrow = newborrow;
|
||||
}
|
||||
}
|
||||
/**
|
||||
*
|
||||
* @brief Montogery multyply algorithm; Calls: Big8wMultNum, U32CMP, U32Add, U32Minus; Called By: Big8wMultMod
|
||||
* montmult(bn1, bn2, p) = bn1 * bn2 * (2^(32*8)) mod p
|
||||
*
|
||||
* @param bn1 the first big number
|
||||
* @param bn2 the second big number
|
||||
* @param p big number, the module number
|
||||
* @param fill unsigned int, precomputed number
|
||||
* @param ret pointer of a string of unsigned int, store the result
|
||||
*
|
||||
* @result ret
|
||||
*
|
||||
*/
|
||||
void Big8wMontMult(big8w bn1, big8w bn2, big8w p, uint32_t fill, uint32_t* ret)
|
||||
{
|
||||
int i;
|
||||
int numindex = BIGNUMBER_SIZE_8WORD - 1;
|
||||
uint32_t temp[BIGNUMBER_SIZE_8WORD + 1 + 1]; // big8w mult uint32_t and add overflow
|
||||
uint32_t elem, time;
|
||||
|
||||
memset(temp, 0x00, sizeof(uint32_t) * (BIGNUMBER_SIZE_8WORD + 1 + 1));
|
||||
memset(ret, 0x00, sizeof(uint32_t) * (BIGNUMBER_SIZE_8WORD + 1 + 1));
|
||||
|
||||
while (bn2.word[numindex] == 0)
|
||||
numindex--;
|
||||
if (numindex < 0)
|
||||
return;
|
||||
|
||||
for (numindex = 0; numindex < BIGNUMBER_SIZE_8WORD; numindex++){
|
||||
elem = bn2.word[numindex];
|
||||
Big8wMultNum(bn1, elem, temp);
|
||||
U32Add(temp, ret, ret);
|
||||
Big8wMultNum(p, fill*ret[0], temp);
|
||||
U32Add(temp, ret, ret);
|
||||
|
||||
for (i = 0; i < BIGNUMBER_SIZE_8WORD + 1; i++)
|
||||
{ // ret.word[0] = 0, (ret >> 32) == ret * (2^(-32)) mod p
|
||||
ret[i] = ret[i + 1];
|
||||
}
|
||||
ret[i] = 0;
|
||||
}
|
||||
|
||||
for (i = 0; i < BIGNUMBER_SIZE_8WORD; i++)
|
||||
temp[i] = p.word[i];
|
||||
temp[i] = 0, temp[i + 1] = 0;
|
||||
|
||||
if (U32CMP(ret, temp))
|
||||
U32Minus(ret, temp, ret);
|
||||
}
|
||||
/**
|
||||
*
|
||||
* @brief return (bn1*bn2 mod p); call twice Montogery multiply algorithm. Only suitable for sm9, the input big8w p is q or N.
|
||||
* montmult(A, B, p) = A * B * (2^(-32*8)) mod p, which can be computed fastly.
|
||||
* so multmod(A, B, p) can be computed by:
|
||||
* ret = montmult(A, B, p) = A*B*(2^(-256)) mod p
|
||||
* ret = montmult(ret, 2^(256*2), p) = ret * 2^(256*2) * (2^(-256)) mod p (computed fastly)
|
||||
* = A * B * (2^(-256)) * (2^(256*2)) * (2^(-256)) mod p = A * B mod p (verify the algorithm)
|
||||
* N_2k = (2^(256*2)) mod curve.N; q_2k = (2^(256*2)) mod curve.q
|
||||
* fill = (2^32 - ((p.word[0])^(-1) mod (2^32))).
|
||||
* fill is precalculated, module number p could be prime number curve.q or curve.N
|
||||
* more details see the theory of Montogery multiply algorithm
|
||||
*
|
||||
* @param bn1 the first big number
|
||||
* @param bn2 the second big number
|
||||
* @param p big number, the module number.
|
||||
*
|
||||
* @return ret, big number, ret = bn1 * bn2 mod p.
|
||||
*
|
||||
*/
|
||||
big8w Big8wMultMod(big8w bn1, big8w bn2, big8w p)
|
||||
{
|
||||
bool flag; // to decide use N_2k or q_2k
|
||||
char i;
|
||||
uint32_t res[BIGNUMBER_SIZE_8WORD + 1 + 1];
|
||||
uint32_t fill;
|
||||
big8w ret;
|
||||
|
||||
memset(ret.word, 0x00, BIG8W_BYTESIZE);
|
||||
|
||||
if (Big8wEqual(&p, &curve.q)){
|
||||
fill = qlow_reverse;
|
||||
flag = 1;
|
||||
}
|
||||
else {
|
||||
fill = Nlow_reverse;
|
||||
flag = 0;
|
||||
}
|
||||
|
||||
if (Big8wIsZero(&bn1) || Big8wIsZero(&bn2))
|
||||
return ret;
|
||||
|
||||
Big8wMontMult(bn1, bn2, p, fill, res);
|
||||
for (i = 0; i < BIGNUMBER_SIZE_8WORD; i++)
|
||||
ret.word[i] = res[i];
|
||||
|
||||
if (flag)
|
||||
Big8wMontMult(ret, q_2k, p, fill, res);
|
||||
else
|
||||
Big8wMontMult(ret, N_2k, p, fill, res);
|
||||
|
||||
for (i = 0; i < BIGNUMBER_SIZE_8WORD; i++)
|
||||
ret.word[i] = res[i];
|
||||
|
||||
return ret;
|
||||
}
|
|
@ -0,0 +1,158 @@
|
|||
/*
|
||||
* Copyright (c) 2020 AIIT Ubiquitous Team
|
||||
* XiUOS is licensed under Mulan PSL v2.
|
||||
* You can use this software according to the terms and conditions of the Mulan PSL v2.
|
||||
* You may obtain a copy of Mulan PSL v2 at:
|
||||
* http://license.coscl.org.cn/MulanPSL2
|
||||
* THIS SOFTWARE IS PROVIDED ON AN "AS IS" BASIS, WITHOUT WARRANTIES OF ANY KIND,
|
||||
* EITHER EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO NON-INFRINGEMENT,
|
||||
* MERCHANTABILITY OR FIT FOR A PARTICULAR PURPOSE.
|
||||
* See the Mulan PSL v2 for more details.
|
||||
*/
|
||||
|
||||
/**
|
||||
* @file ecc.c
|
||||
* @brief arithmetic in ecc
|
||||
* @version 1.0
|
||||
* @author AIIT Ubiquitous Team
|
||||
* @date 2021-04-24
|
||||
*/
|
||||
#include <ecc.h>
|
||||
|
||||
/**
|
||||
* @brief Print the point(x, y)
|
||||
*
|
||||
* @param point pointer of a point in group G1.
|
||||
*
|
||||
* @return null
|
||||
*/
|
||||
void G1pointPrint(G1point *point)
|
||||
{
|
||||
Big8wPrint(&point->x);
|
||||
Big8wPrint(&point->y);
|
||||
}
|
||||
/**
|
||||
* @brief judge whether the point in group G1
|
||||
*
|
||||
* @param point a point(x, y)
|
||||
*
|
||||
* @return true if point in group G1; else false
|
||||
*
|
||||
*/
|
||||
bool PointInG1(G1point point)
|
||||
{
|
||||
big8w y_power2;
|
||||
big8w temp;
|
||||
|
||||
y_power2 = Big8wMultMod(point.y, point.y, curve.q); // y^2 mod curve.q
|
||||
|
||||
temp = Big8wMultMod(point.x, point.x, curve.q);
|
||||
temp = Big8wMultMod(temp, point.x, curve.q); // x^3
|
||||
|
||||
temp = Big8wAddMod(temp, curve.b, curve.q); // x^3 + b
|
||||
|
||||
return Big8wEqual(&y_power2, &temp);
|
||||
}
|
||||
/**
|
||||
*
|
||||
* @brief compute the sum of two points in group G1; set infinite point O as (0, 0), tell if exist O before points add.
|
||||
* Calls: big8wIszero, Big8wEqual, Big8wAddMod, Big8wMinusMod, Big8wReverse
|
||||
* Called By: G1pointMult
|
||||
*
|
||||
* @param point1 the first point in group G1
|
||||
* @param point2 the second point in group G1
|
||||
*
|
||||
* @return a point in group
|
||||
*
|
||||
*/
|
||||
G1point G1pointAdd(G1point point1, G1point point2)
|
||||
{
|
||||
G1point ret;
|
||||
big8w lambda, temp;
|
||||
|
||||
// infinite point
|
||||
if (Big8wIsZero(&point1.x) && Big8wIsZero(&point1.y))
|
||||
return point2;
|
||||
else if (Big8wIsZero(&point1.x) && Big8wIsZero(&point1.y))
|
||||
return point1;
|
||||
|
||||
if (Big8wEqual(&point1.x, &point2.x)) {
|
||||
|
||||
if (!Big8wEqual(&point1.y, &point2.y)){ // x1=x2, y1 != y2(y1 = -y2), ret = O (0, 0)
|
||||
memset(ret.x.word, 0x00, BIG8W_BYTESIZE);
|
||||
memset(ret.y.word, 0x00, BIG8W_BYTESIZE);
|
||||
return ret;
|
||||
}
|
||||
|
||||
temp = Big8wAddMod(point1.y, point1.y, curve.q); // 2*y1
|
||||
temp = Big8wReverse(temp, curve.q); // 1/2*y1
|
||||
temp = Big8wMultMod(point1.x, temp, curve.q); // x1*(1/2*y1)
|
||||
temp = Big8wMultMod(point1.x, temp, curve.q); // x1*x1*(1/2*y1)
|
||||
lambda = Big8wAddMod(temp, Big8wAddMod(temp, temp, curve.q), curve.q); // 3*x1*x1*(1/2*y1)
|
||||
}
|
||||
else {
|
||||
temp = Big8wMinusMod(point1.x, point2.x, curve.q);
|
||||
temp = Big8wReverse(temp, curve.q); // 1/(x2 - x1)
|
||||
|
||||
lambda = Big8wMinusMod(point1.y, point2.y, curve.q); // y2 - y1
|
||||
lambda = Big8wMultMod(temp, lambda, curve.q);
|
||||
}
|
||||
|
||||
ret.x = Big8wMultMod(lambda, lambda, curve.q); // k*k
|
||||
temp = Big8wAddMod(point1.x, point2.x, curve.q); // x1 + x2
|
||||
ret.x = Big8wMinusMod(ret.x, temp, curve.q); // x3 = lambda*lambda - x1 - x2
|
||||
|
||||
ret.y = Big8wMinusMod(point1.x, ret.x, curve.q); // y3 = lambda*(x1 - x3) - y1
|
||||
ret.y = Big8wMultMod(lambda, ret.y, curve.q);
|
||||
ret.y = Big8wMinusMod(ret.y, point1.y, curve.q);
|
||||
|
||||
return ret;
|
||||
}
|
||||
/**
|
||||
*
|
||||
* @brief mult point; scan bits of bignum
|
||||
*
|
||||
* @param bignum big number, bignum > 0
|
||||
* @param point point in group G1
|
||||
*
|
||||
* @return a point in group G1
|
||||
*
|
||||
*/
|
||||
// could optimized by scan the segment of continuous 1.
|
||||
G1point G1pointMult(big8w bignum, G1point point)
|
||||
{
|
||||
bool flag = 0;
|
||||
int i = BIGNUMBER_SIZE_8WORD - 1;
|
||||
int index = Big8wHighestbit(&bignum);
|
||||
uint32_t elem;
|
||||
G1point ret = point;
|
||||
G1point temp = point;
|
||||
|
||||
while (bignum.word[i] == 0)
|
||||
i--;
|
||||
elem = bignum.word[i];
|
||||
|
||||
index--;
|
||||
while (index>=0) {
|
||||
flag = (elem >> (index--)) & 1;
|
||||
ret = G1pointAdd(temp, temp);
|
||||
if (flag)
|
||||
ret = G1pointAdd(ret, point);
|
||||
temp = ret;
|
||||
}
|
||||
|
||||
i--;
|
||||
for (; i>=0; i--) {
|
||||
elem = bignum.word[i];
|
||||
index = 31;
|
||||
while (index>=0) {
|
||||
flag = (elem >> (index--)) & 1;
|
||||
ret = G1pointAdd(temp, temp);
|
||||
if (flag)
|
||||
ret = G1pointAdd(ret, point);
|
||||
temp = ret;
|
||||
}
|
||||
}
|
||||
|
||||
return ret;
|
||||
}
|
|
@ -0,0 +1,254 @@
|
|||
/*
|
||||
* Copyright (c) 2020 AIIT Ubiquitous Team
|
||||
* XiUOS is licensed under Mulan PSL v2.
|
||||
* You can use this software according to the terms and conditions of the Mulan PSL v2.
|
||||
* You may obtain a copy of Mulan PSL v2 at:
|
||||
* http://license.coscl.org.cn/MulanPSL2
|
||||
* THIS SOFTWARE IS PROVIDED ON AN "AS IS" BASIS, WITHOUT WARRANTIES OF ANY KIND,
|
||||
* EITHER EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO NON-INFRINGEMENT,
|
||||
* MERCHANTABILITY OR FIT FOR A PARTICULAR PURPOSE.
|
||||
* See the Mulan PSL v2 for more details.
|
||||
*/
|
||||
|
||||
/**
|
||||
* @file join.c
|
||||
* @brief convert data type and join string
|
||||
* @version 1.0
|
||||
* @author AIIT Ubiquitous Team
|
||||
* @date 2021-04-24
|
||||
*/
|
||||
#include <join.h>
|
||||
|
||||
/**
|
||||
*
|
||||
* @brief convert big8w to char string and insert into string, start from startindex
|
||||
*
|
||||
* @param bignum a big number
|
||||
* @param string a string of unsigned char
|
||||
* @param startindex the start index of string convert to bignum
|
||||
*
|
||||
* @return string
|
||||
*
|
||||
*/
|
||||
void Big8wIntou8string(big8w* bignum, uint8_t* string, uint32_t startindex)
|
||||
{
|
||||
int index;
|
||||
uint32_t elem;
|
||||
|
||||
for (index = BIGNUMBER_SIZE_8WORD - 1; index >= 0; index--) {
|
||||
elem = bignum->word[index];
|
||||
string[startindex++] = (uint8_t)(elem >> 24);
|
||||
string[startindex++] = (uint8_t)(elem >> 16);
|
||||
string[startindex++] = (uint8_t)(elem >> 8);
|
||||
string[startindex++] = (uint8_t)(elem);
|
||||
}
|
||||
}
|
||||
/**
|
||||
*
|
||||
* @brief convert q12 to char string and insert into string, start from startindex
|
||||
*
|
||||
* @param num a pointer of a number in Fq12
|
||||
* @param string a string of unsigned int
|
||||
* @param startindex the start index of string to insert.
|
||||
*
|
||||
* @return string
|
||||
*
|
||||
*/
|
||||
void Q12Intou8string(q12* num, uint8_t* string, uint32_t startindex)
|
||||
{
|
||||
Big8wIntou8string(&num->high.high.high, string, startindex);
|
||||
startindex += BIG8W_BYTESIZE;
|
||||
|
||||
Big8wIntou8string(&num->high.high.low, string, startindex);
|
||||
startindex += BIG8W_BYTESIZE;
|
||||
|
||||
Big8wIntou8string(&num->high.low.high, string, startindex);
|
||||
startindex += BIG8W_BYTESIZE;
|
||||
|
||||
Big8wIntou8string(&num->high.low.low, string, startindex);
|
||||
startindex += BIG8W_BYTESIZE;
|
||||
|
||||
Big8wIntou8string(&num->mid.high.high, string, startindex);
|
||||
startindex += BIG8W_BYTESIZE;
|
||||
|
||||
Big8wIntou8string(&num->mid.high.low, string, startindex);
|
||||
startindex += BIG8W_BYTESIZE;
|
||||
|
||||
Big8wIntou8string(&num->mid.low.high, string, startindex);
|
||||
startindex += BIG8W_BYTESIZE;
|
||||
|
||||
Big8wIntou8string(&num->mid.low.low, string, startindex);
|
||||
startindex += BIG8W_BYTESIZE;
|
||||
|
||||
Big8wIntou8string(&num->low.high.high, string, startindex);
|
||||
startindex += BIG8W_BYTESIZE;
|
||||
|
||||
Big8wIntou8string(&num->low.high.low, string, startindex);
|
||||
startindex += BIG8W_BYTESIZE;
|
||||
|
||||
Big8wIntou8string(&num->low.low.high, string, startindex);
|
||||
startindex += BIG8W_BYTESIZE;
|
||||
|
||||
Big8wIntou8string(&num->low.low.low, string, startindex);
|
||||
startindex += BIG8W_BYTESIZE;
|
||||
}
|
||||
/**
|
||||
* @brief convert unsigned char string to a point in group G1.
|
||||
*
|
||||
* @param string unsinged char string
|
||||
* @param ret pointer of a point in group G1
|
||||
*
|
||||
* @return ret
|
||||
*
|
||||
*/
|
||||
void U8stringToG1point(uint8_t* string, G1point *ret)
|
||||
{
|
||||
uint32_t i;
|
||||
|
||||
for (i = 1; i < BIGNUMBER_SIZE_8WORD + 1; i++)
|
||||
ret->x.word[BIGNUMBER_SIZE_8WORD - i] = GETU32((string + 4*(i-1)));
|
||||
|
||||
for (i = 1; i < BIGNUMBER_SIZE_8WORD + 1; i++)
|
||||
ret->y.word[BIGNUMBER_SIZE_8WORD - i] = GETU32((string + BIG8W_BYTESIZE + 4*(i-1)));
|
||||
}
|
||||
/**
|
||||
* @brief join ID and hid
|
||||
*
|
||||
* @param ID id, unsigned char string
|
||||
* @param hid hid(0x01, 0x02, 0x03), unsigned char, defined in SM9
|
||||
* @param ret unsigned char string, store the result of joined ID and hid
|
||||
*
|
||||
* @return ret
|
||||
*
|
||||
*/
|
||||
void JoinIDhid(uint8_t* ID, uint8_t IDlen, uint8_t hid, uint8_t* ret)
|
||||
{
|
||||
uint8_t i;
|
||||
|
||||
for (i = 0; i < IDlen; i++)
|
||||
ret[i] = ID[i];
|
||||
|
||||
ret[i] = hid;
|
||||
}
|
||||
/**
|
||||
* @brief join message and w(q12 number).
|
||||
*
|
||||
* @param message message, unsigned char string
|
||||
* @param msglen length of message, byte size
|
||||
* @param w pointer of a number in Fq12
|
||||
* @param ret unsigned char string, store the result
|
||||
*
|
||||
* @return ret
|
||||
*
|
||||
*/
|
||||
void JoinMsgW(uint8_t* message, uint32_t msglen, q12* w, uint8_t* ret)
|
||||
{
|
||||
uint32_t i = 0;
|
||||
|
||||
for (i = 0; i < msglen; i++)
|
||||
ret[i] = message[i];
|
||||
|
||||
Q12Intou8string(w, ret, msglen);
|
||||
}
|
||||
/**
|
||||
* @brief join IDA, IDB, RA, RB, g1, g2, g3, defined in SM9
|
||||
*
|
||||
* @param ID_Challenger id of challenger, unsigned char string
|
||||
* @param ID_Challenger_len length of the id of challenger, byte size, unsigned char
|
||||
* @param ID_Responser id of responser, unsigned char string
|
||||
* @param ID_Responser_len length of the id of responser, byte size, unsigned char
|
||||
* @param R_Challenger pointer of a point in group G1
|
||||
* @param R_Responser pointer of a point in group G1
|
||||
* @param g1 pointer of a number in Fq12, defined in SM9
|
||||
* @param g2 pointer of a number in Fq12, defined in SM9
|
||||
* @param g3 pointer of a number in Fq12, defined in SM9
|
||||
* @param ret unsigned char string, store the result
|
||||
*
|
||||
* @result ret
|
||||
*
|
||||
*/
|
||||
void JoinIDAIDBRARBg123(
|
||||
uint8_t *ID_Challenger, uint8_t ID_Challenger_len,
|
||||
uint8_t *ID_Responser, uint8_t ID_Responser_len,
|
||||
G1point* R_Challenger, G1point* R_Responser,
|
||||
q12 *g1, q12 *g2, q12 *g3,
|
||||
uint8_t* ret)
|
||||
{
|
||||
uint32_t i = 0;
|
||||
uint32_t index = 0;
|
||||
|
||||
index = 0;
|
||||
while (index < ID_Challenger_len)
|
||||
ret[i++] = ID_Challenger[index++];
|
||||
index = 0;
|
||||
while (index < ID_Responser_len)
|
||||
ret[i++] = ID_Responser[index++];
|
||||
|
||||
Big8wIntou8string(&R_Challenger->x, ret, i);
|
||||
i += BIG8W_BYTESIZE;
|
||||
|
||||
Big8wIntou8string(&R_Challenger->y, ret, i);
|
||||
i += BIG8W_BYTESIZE;
|
||||
|
||||
Big8wIntou8string(&R_Responser->x, ret, i);
|
||||
i += BIG8W_BYTESIZE;
|
||||
|
||||
Big8wIntou8string(&R_Responser->y, ret, i);
|
||||
i += BIG8W_BYTESIZE;
|
||||
|
||||
Q12Intou8string(g1, ret, i);
|
||||
i += BIG8W_BYTESIZE * 12;
|
||||
|
||||
Q12Intou8string(g2, ret, i);
|
||||
i += BIG8W_BYTESIZE * 12;
|
||||
|
||||
Q12Intou8string(g3, ret, i);
|
||||
|
||||
}
|
||||
/**
|
||||
* @brief join C, w, ID, defined in SM9
|
||||
*
|
||||
* @param C a pointer of a point in group G1
|
||||
* @param w a pointer of a number in Fq12
|
||||
* @param ID unsinged char string
|
||||
* @param IDlen length of ID, byte size, unsinged char
|
||||
* @param ret unsinged char string , store the result
|
||||
*
|
||||
* @result ret
|
||||
*
|
||||
*/
|
||||
void JoinCwID(G1point* C, q12* w, uint8_t* ID, uint8_t IDlen, uint8_t* ret)
|
||||
{
|
||||
uint8_t index = 0;
|
||||
uint32_t i = 0;
|
||||
|
||||
Big8wIntou8string(&C->x, ret, i);
|
||||
i += BIG8W_BYTESIZE;
|
||||
Big8wIntou8string(&C->y, ret, i);
|
||||
i += BIG8W_BYTESIZE;
|
||||
|
||||
Q12Intou8string(w, ret, i);
|
||||
i += BIG8W_BYTESIZE * 12;
|
||||
|
||||
while (index < IDlen)
|
||||
ret[i++] = ID[index++];
|
||||
}
|
||||
/**
|
||||
*
|
||||
* @brief msg xor K; u8string xor u8string
|
||||
*
|
||||
* @param msg message, unsigned char string
|
||||
* @param msglen length of message, byte size, unsigned int
|
||||
* @param K produced by KDF(), unsigned char string
|
||||
* @param ret unsigned char string, store the result
|
||||
*
|
||||
* @result ret
|
||||
*
|
||||
*/
|
||||
void XOR(unsigned char* msg, uint32_t msglen, unsigned char* K, unsigned char* ret)
|
||||
{
|
||||
uint32_t i;
|
||||
for (i = 0; i < msglen; i++)
|
||||
ret[i] = msg[i] ^ K[i];
|
||||
|
||||
}
|
|
@ -0,0 +1,970 @@
|
|||
/*
|
||||
* Copyright (c) 2020 AIIT Ubiquitous Team
|
||||
* XiUOS is licensed under Mulan PSL v2.
|
||||
* You can use this software according to the terms and conditions of the Mulan PSL v2.
|
||||
* You may obtain a copy of Mulan PSL v2 at:
|
||||
* http://license.coscl.org.cn/MulanPSL2
|
||||
* THIS SOFTWARE IS PROVIDED ON AN "AS IS" BASIS, WITHOUT WARRANTIES OF ANY KIND,
|
||||
* EITHER EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO NON-INFRINGEMENT,
|
||||
* MERCHANTABILITY OR FIT FOR A PARTICULAR PURPOSE.
|
||||
* See the Mulan PSL v2 for more details.
|
||||
*/
|
||||
|
||||
/**
|
||||
* @file qn.c
|
||||
* @brief arithmetic in extention field, and arithmetic in group G2, frobenius and LastPower in BiLinearPairing
|
||||
* @version 1.0
|
||||
* @author AIIT Ubiquitous Team
|
||||
* @date 2021-04-24
|
||||
*/
|
||||
#include <qn.h>
|
||||
|
||||
big8w t; // sm9 ecc parameter
|
||||
big8w qnr; // (-1/2) mod curve.q
|
||||
big8w frobenius_constant_1[12];
|
||||
big8w frobenius_constant_2[12];
|
||||
/**
|
||||
* @brief print the point in group G2
|
||||
*
|
||||
* @param point a pointer of point in group G2
|
||||
*
|
||||
* @return null
|
||||
*
|
||||
*/
|
||||
void G2pointPrint(G2point* point)
|
||||
{
|
||||
Big8wPrint(&point->x.high);
|
||||
Big8wPrint(&point->x.low);
|
||||
Big8wPrint(&point->y.high);
|
||||
Big8wPrint(&point->y.low);
|
||||
}
|
||||
/**
|
||||
* @brief print a number in Fq12
|
||||
*
|
||||
* @param number a pointer of number in Fq12
|
||||
*
|
||||
* @return null
|
||||
*
|
||||
*/
|
||||
void Q12Print(q12* number)
|
||||
{
|
||||
Big8wPrint(&number->high.high.high);
|
||||
Big8wPrint(&number->high.high.low);
|
||||
Big8wPrint(&number->high.low.high);
|
||||
Big8wPrint(&number->high.low.low);
|
||||
|
||||
Big8wPrint(&number->mid.high.high);
|
||||
Big8wPrint(&number->mid.high.low);
|
||||
Big8wPrint(&number->mid.low.high);
|
||||
Big8wPrint(&number->mid.low.low);
|
||||
|
||||
Big8wPrint(&number->low.high.high);
|
||||
Big8wPrint(&number->low.high.low);
|
||||
Big8wPrint(&number->low.low.high);
|
||||
Big8wPrint(&number->low.low.low);
|
||||
}
|
||||
/**
|
||||
* @brief convert q12 to big_12big
|
||||
*
|
||||
* @param num pointer of number in Fq12
|
||||
* @param ret pointer of big_12big, store the result
|
||||
*
|
||||
* @result ret
|
||||
*
|
||||
*/
|
||||
void Q12To12big(q12* num, big_12big* ret)
|
||||
{
|
||||
ret->word[0] = num->high.high.high;
|
||||
ret->word[1] = num->high.high.low;
|
||||
ret->word[2] = num->high.low.high;
|
||||
ret->word[3] = num->high.low.low;
|
||||
|
||||
ret->word[4] = num->mid.high.high;
|
||||
ret->word[5] = num->mid.high.low;
|
||||
ret->word[6] = num->mid.low.high;
|
||||
ret->word[7] = num->mid.low.low;
|
||||
|
||||
ret->word[8] = num->low.high.high;
|
||||
ret->word[9] = num->low.high.low;
|
||||
ret->word[10] = num->low.low.high;
|
||||
ret->word[11] = num->low.low.low;
|
||||
}
|
||||
/**
|
||||
* @brief set a number in Fq12 to 0
|
||||
*
|
||||
* @param num pointer of a number in Fq12
|
||||
*
|
||||
* @resulr num
|
||||
*
|
||||
*/
|
||||
void Q2Zero(q2* num)
|
||||
{
|
||||
memset(num->high.word, 0x00, BIG8W_BYTESIZE);
|
||||
memset(num->low.word, 0x00, BIG8W_BYTESIZE);
|
||||
}
|
||||
/**
|
||||
* @brief set a number in Fq4 to 0
|
||||
*
|
||||
* @param num number in Fq4
|
||||
*
|
||||
* @result num
|
||||
*
|
||||
*/
|
||||
void Q4Zero(q4* num)
|
||||
{
|
||||
Q2Zero(&num->high);
|
||||
Q2Zero(&num->low);
|
||||
}
|
||||
/**
|
||||
* @brief set a number in Fq12 to 0
|
||||
*
|
||||
* @param num pointer of a number in Fq12
|
||||
*
|
||||
* @result num
|
||||
*
|
||||
*/
|
||||
void Q12Zero(q12* num)
|
||||
{
|
||||
Q4Zero(&num->high);
|
||||
Q4Zero(&num->mid);
|
||||
Q4Zero(&num->low);
|
||||
}
|
||||
/**
|
||||
* @brief return num1 == num2
|
||||
*
|
||||
* @param num1 pointer of the first number in Fq2
|
||||
* @param num2 pointer of the second number in Fq2
|
||||
*
|
||||
* @return true if num1 == num2; else false
|
||||
*
|
||||
*/
|
||||
bool Q2Equal(q2* num1, q2* num2)
|
||||
{
|
||||
return Big8wEqual(&num1->high, &num2->high)
|
||||
&& Big8wEqual(&num1->low, &num2->low);
|
||||
}
|
||||
/**
|
||||
* @brief return (num1 + num2)
|
||||
*
|
||||
* @param num1 the first number in Fq2
|
||||
* @param num2 the second number in Fq2
|
||||
*
|
||||
* @return ret, a number in Fq2, ret = num1 + num2.
|
||||
*/
|
||||
q2 Q2Add(q2 num1, q2 num2)
|
||||
{
|
||||
q2 ret;
|
||||
|
||||
ret.high = Big8wAddMod(num1.high, num2.high, curve.q);
|
||||
ret.low = Big8wAddMod(num1.low, num2.low, curve.q);
|
||||
|
||||
return ret;
|
||||
}
|
||||
/**
|
||||
* @brief return (num1 - num2)
|
||||
*
|
||||
* @param num1 the first number in Fq2
|
||||
* @param num2 the second number in Fq2
|
||||
*
|
||||
* @return ret, a number in Fq2, ret = num1 - num2.
|
||||
*/
|
||||
q2 Q2Minus(q2 num1, q2 num2)
|
||||
{
|
||||
q2 ret;
|
||||
|
||||
ret.high = Big8wMinusMod(num1.high, num2.high, curve.q);
|
||||
ret.low = Big8wMinusMod(num1.low, num2.low, curve.q);
|
||||
|
||||
return ret;
|
||||
}
|
||||
/**
|
||||
* @brief
|
||||
* set num1 = (a, b), num2 = (c, d), num1*num2 = (a*d + b*c, b*d - 2*a*c)......(high, low)
|
||||
* Toom-Cook: (a*d + b*c) = (a + b)(c + d) - a*c - b*d
|
||||
* Calls: Big8wMultMod, Big8wAddMod, Big8wMinusMod
|
||||
* Called By: G2pointAdd, Q4Mult, Q2Reverse and more
|
||||
* @param num1 the first number in Fq2
|
||||
* @param num2 the second number in Fq2
|
||||
*
|
||||
* @return ret, a number in Fq2, ret = num1 * num2
|
||||
*
|
||||
*/
|
||||
q2 Q2Mult(q2 num1, q2 num2)
|
||||
{ // num1 = (a1, a0), num2 = (b1, b0).....(high, low)
|
||||
q2 ret;
|
||||
big8w a0b0, a1b1;
|
||||
// Toom-Cook
|
||||
a0b0 = Big8wMultMod(num1.low, num2.low, curve.q);
|
||||
a1b1 = Big8wMultMod(num1.high, num2.high, curve.q);
|
||||
|
||||
ret.high = Big8wMultMod(
|
||||
Big8wAddMod(num1.high, num1.low, curve.q),
|
||||
Big8wAddMod(num2.high, num2.low, curve.q),
|
||||
curve.q);
|
||||
|
||||
ret.high = Big8wMinusMod(
|
||||
ret.high,
|
||||
Big8wAddMod(a0b0, a1b1, curve.q),
|
||||
curve.q);
|
||||
|
||||
ret.low = Big8wMinusMod(
|
||||
a0b0,
|
||||
Big8wAddMod(a1b1, a1b1, curve.q),
|
||||
curve.q);
|
||||
|
||||
return ret;
|
||||
}
|
||||
/**
|
||||
*
|
||||
* @brief num1 = (a, b), num2 = (c, d), num1*num2*u = (b*d - 2*a*c, -2*(a*d +b*c)). compare Q2Mult
|
||||
*
|
||||
* @param num1 the first number in Fq2
|
||||
* @param num2 the second number in Fq2
|
||||
*
|
||||
* @return ret, a number in Fq2; ret = a * b * u
|
||||
*
|
||||
*/
|
||||
q2 Q2MultFlag(q2 num1, q2 num2)
|
||||
{
|
||||
q2 ret = Q2Mult(num1, num2);
|
||||
big8w temp = ret.high;
|
||||
|
||||
ret.high = ret.low;
|
||||
ret.low = Big8wMinusMod(
|
||||
curve.q,
|
||||
Big8wAddMod(temp, temp, curve.q), curve.q);
|
||||
|
||||
return ret;
|
||||
}
|
||||
/**
|
||||
*
|
||||
* @brief num = (a, b), num^(-1) = ((-a)/(b*b +2*a*a), b/(b*b, 2*a*a))
|
||||
*
|
||||
* @param num number in Fq2
|
||||
*
|
||||
* @return ret, number in Fq2, ret = num^(-1).
|
||||
*
|
||||
*/
|
||||
q2 Q2Reverse(q2 num)
|
||||
{
|
||||
big8w temp;
|
||||
q2 ret;
|
||||
|
||||
temp = Big8wMultMod(num.high, num.high, curve.q); // a*a
|
||||
temp = Big8wAddMod(temp, temp, curve.q); // 2*a*a
|
||||
temp = Big8wAddMod(temp,
|
||||
Big8wMultMod(num.low, num.low, curve.q), curve.q); // (b*b +2*a*a)
|
||||
temp = Big8wReverse(temp, curve.q); // (1/(b*b + 2*a*a))
|
||||
|
||||
ret.high = Big8wMinusMod(curve.q, num.high, curve.q); // (-a)
|
||||
ret.high = Big8wMultMod(ret.high, temp, curve.q);
|
||||
ret.low = Big8wMultMod(num.low, temp, curve.q);
|
||||
|
||||
return ret;
|
||||
}
|
||||
/**
|
||||
* @brief return (-num);(-num.high, -num.low) mod curve.q = (curve.q - num.high, curve.q - num.low)
|
||||
*
|
||||
* @param num number in Fq2
|
||||
*
|
||||
* @return ret, a number in Fq2
|
||||
*
|
||||
*/
|
||||
q2 Q2Negate(q2 num)
|
||||
{
|
||||
num.high = Big8wMinusMod(curve.q, num.high, curve.q);
|
||||
num.low = Big8wMinusMod(curve.q, num.low, curve.q);
|
||||
|
||||
return num;
|
||||
}
|
||||
/**
|
||||
* @brief
|
||||
*
|
||||
* @param num number in Fq2
|
||||
*
|
||||
* @return num
|
||||
*
|
||||
*/
|
||||
q2 Q2Txx(q2 num)
|
||||
{
|
||||
big8w temp;
|
||||
|
||||
temp = num.high;
|
||||
num.high = num.low;
|
||||
num.low = Big8wMinusMod(curve.q, temp, curve.q);
|
||||
num.low = Big8wAddMod(num.low, num.low, curve.q);
|
||||
|
||||
return num;
|
||||
}
|
||||
/**
|
||||
* @brief add of two points in group G2
|
||||
*
|
||||
* @param point1 the first point in group G2
|
||||
* @param point2 the second point in group G2
|
||||
*
|
||||
* @return ret, a point in group G2
|
||||
*
|
||||
*/
|
||||
G2point G2PointAdd(G2point point1, G2point point2)
|
||||
{
|
||||
q2 temp, lambda;
|
||||
G2point ret;
|
||||
|
||||
memset(&temp, 0x00, BIG8W_BYTESIZE * 2);
|
||||
|
||||
// temp = zero
|
||||
// infinite point judge
|
||||
if (Q2Equal(&point1.x, &temp) && Q2Equal(&point1.y, &temp))
|
||||
return point2;
|
||||
else if (Q2Equal(&point2.x, &temp) && Q2Equal(&point2.y, &temp))
|
||||
return point1;
|
||||
|
||||
if (Big8wEqual(&point1.x.high, &point2.x.high)
|
||||
&& Big8wEqual(&point1.x.low, &point2.x.low)) { // x1 = x2
|
||||
|
||||
if (!Big8wEqual(&point1.y.high, &point2.y.high)
|
||||
|| !Big8wEqual(&point1.y.low, &point2.y.low)) // y1 != y2 (y1 = -y2)
|
||||
{
|
||||
memset(&ret, 0x00, BIG8W_BYTESIZE * 4);
|
||||
return ret; // ret = O
|
||||
}
|
||||
|
||||
temp = Q2Mult(point1.x, point1.x);
|
||||
|
||||
lambda = Q2Add(temp, temp);
|
||||
lambda = Q2Add(lambda, temp);
|
||||
lambda = Q2Mult(lambda, Q2Reverse(Q2Add(point1.y, point1.y)));
|
||||
}
|
||||
|
||||
else {
|
||||
lambda = Q2Mult(
|
||||
Q2Minus(point1.y, point2.y),
|
||||
Q2Reverse(Q2Minus(point1.x, point2.x)));
|
||||
}
|
||||
|
||||
ret.x = Q2Mult(lambda, lambda);
|
||||
ret.x = Q2Minus(ret.x, point1.x);
|
||||
ret.x = Q2Minus(ret.x, point2.x);
|
||||
|
||||
ret.y = Q2Minus(point1.x, ret.x);
|
||||
ret.y = Q2Mult(lambda, ret.y);
|
||||
ret.y = Q2Minus(ret.y, point1.y);
|
||||
|
||||
return ret;
|
||||
}
|
||||
/**
|
||||
* @brief mult point in group G2. (num * point)
|
||||
*
|
||||
* @param num big number, num > 0
|
||||
* @param point point in group G2
|
||||
*
|
||||
* @return ret, a point in group G2
|
||||
*
|
||||
*/
|
||||
G2point G2PointMult(big8w num, G2point point)
|
||||
{
|
||||
bool flag = 0;
|
||||
int i = BIGNUMBER_SIZE_8WORD - 1;
|
||||
int index = Big8wHighestbit(&num);
|
||||
uint32_t elem;
|
||||
G2point ret = point, temp = point;
|
||||
|
||||
while (num.word[i] == 0)
|
||||
i--;
|
||||
elem = num.word[i];
|
||||
|
||||
index--;
|
||||
while (index >= 0) {
|
||||
flag = (elem >> (index--)) & 1;
|
||||
ret = G2PointAdd(temp, temp);
|
||||
if (flag)
|
||||
ret = G2PointAdd(ret, point);
|
||||
temp = ret;
|
||||
}
|
||||
|
||||
i--;
|
||||
for (; i >= 0; i--) {
|
||||
elem = num.word[i];
|
||||
index = 31;
|
||||
|
||||
while (index >= 0) {
|
||||
flag = (elem >> (index--)) & 1;
|
||||
ret = G2PointAdd(temp, temp);
|
||||
if (flag)
|
||||
ret = G2PointAdd(ret, point);
|
||||
temp = ret;
|
||||
}
|
||||
}
|
||||
|
||||
return ret;
|
||||
}
|
||||
/**
|
||||
* @brief return (num1 + num2)
|
||||
*
|
||||
* @param num1 the first number in Fq4
|
||||
* @param num2 the second number in Fq4
|
||||
*
|
||||
* @return ret, a number in Fq4, ret = (num1 + num2)
|
||||
*
|
||||
*/
|
||||
q4 Q4Add(q4 num1, q4 num2)
|
||||
{
|
||||
q4 ret;
|
||||
|
||||
ret.high = Q2Add(num1.high, num2.high);
|
||||
ret.low = Q2Add(num1.low, num2.low);
|
||||
|
||||
return ret;
|
||||
}
|
||||
/**
|
||||
* @brief return (num1 - num2)
|
||||
*
|
||||
* @param num1 the first number in Fq4
|
||||
* @param num2 the second number in Fq4
|
||||
*
|
||||
* @return ret, a number in Fq4, ret = (num1 - num2)
|
||||
*
|
||||
*/
|
||||
q4 Q4Minus(q4 num1, q4 num2)
|
||||
{
|
||||
q4 ret;
|
||||
|
||||
ret.high = Q2Minus(num1.high, num2.high);
|
||||
ret.low = Q2Minus(num1.low, num2.low);
|
||||
|
||||
return ret;
|
||||
}
|
||||
/**
|
||||
* @brief num1 * num2; num1, num2 are numbers in Fq4, the way to compute is similar to Q2Mult
|
||||
* q4 num = (num1, num2), similar to Q2Mult, except num1 = (a1, a0), a0, a1 is big8w
|
||||
*
|
||||
* @param num1 the first number in Fq4
|
||||
* @param num2 the second number in Fq4
|
||||
*
|
||||
* @return ret, a number in Fq4
|
||||
*/
|
||||
q4 Q4Mult(q4 num1, q4 num2)
|
||||
{// num1 = (a1, a0), num2 = (b1, b0). left high value
|
||||
q4 ret;
|
||||
q2 a0b0, a1b1;
|
||||
|
||||
// Toom-Cook
|
||||
a1b1 = Q2Mult(num1.high, num2.high);
|
||||
a0b0 = Q2Mult(num1.low, num2.low);
|
||||
|
||||
ret.high = Q2Mult(
|
||||
Q2Add(num1.high, num1.low),
|
||||
Q2Add(num2.high, num2.low));
|
||||
|
||||
ret.high = Q2Minus(
|
||||
ret.high,
|
||||
Q2Add(a0b0, a1b1));
|
||||
|
||||
ret.low.high = Big8wAddMod(a0b0.high, a1b1.low, curve.q);
|
||||
ret.low.low = Big8wMinusMod(
|
||||
a0b0.low,
|
||||
Big8wAddMod(a1b1.high, a1b1.high, curve.q),
|
||||
curve.q);
|
||||
|
||||
return ret;
|
||||
}
|
||||
/**
|
||||
* @brief return num1 * num2 * u; num1, num2 are numbers in Fq4
|
||||
*
|
||||
* @param num1 the first number in Fq4
|
||||
* @param num2 the second number in Fq4
|
||||
*
|
||||
* @return ret, a number in Fq4
|
||||
*
|
||||
*/
|
||||
q4 Q4MultFlag(q4 num1, q4 num2)
|
||||
{
|
||||
q4 ret;
|
||||
|
||||
ret.high = Q2Add(
|
||||
Q2Mult(num1.low, num2.low),
|
||||
Q2MultFlag(num1.high, num2.high));
|
||||
ret.low = Q2Add(
|
||||
Q2MultFlag(num1.high, num2.low),
|
||||
Q2MultFlag(num1.low, num2.high));
|
||||
|
||||
return ret;
|
||||
}
|
||||
/**
|
||||
* @brief
|
||||
*
|
||||
* @param num number in Fq4
|
||||
*
|
||||
* @return ret, a number in Fq4
|
||||
*
|
||||
*/
|
||||
q4 Q4Txx(q4 num)
|
||||
{
|
||||
q2 temp;
|
||||
|
||||
temp = num.high;
|
||||
num.high = num.low;
|
||||
num.low = Q2Txx(temp);
|
||||
|
||||
return num;
|
||||
}
|
||||
/**
|
||||
* @brief return (-num), similar to Q2Negate
|
||||
*
|
||||
* @param num a number in Fq4
|
||||
*
|
||||
* @return num, a number in Fq4
|
||||
*
|
||||
*/
|
||||
q4 Q4Negate(q4 num)
|
||||
{
|
||||
num.high = Q2Negate(num.high);
|
||||
num.low = Q2Negate(num.low);
|
||||
|
||||
return num;
|
||||
}
|
||||
/**
|
||||
* @brief return num^(-1)
|
||||
*
|
||||
* @param num number in Fq4
|
||||
*
|
||||
* @return num, number in Fq4
|
||||
*
|
||||
*/
|
||||
q4 Q4Reverse(q4 num)
|
||||
{
|
||||
q2 t1, t2;
|
||||
|
||||
t1 = Q2Mult(num.low, num.low);
|
||||
t2 = Q2Mult(num.high, num.high);
|
||||
t2 = Q2Txx(t2);
|
||||
t1 = Q2Minus(t1, t2);
|
||||
t1 = Q2Reverse(t1);
|
||||
num.low = Q2Mult(num.low, t1);
|
||||
t1 = Q2Negate(t1);
|
||||
num.high = Q2Mult(num.high, t1);
|
||||
|
||||
return num;
|
||||
}
|
||||
/**
|
||||
* @brief return (num1 * num2);
|
||||
*
|
||||
* @param num1 the first number in Fq12
|
||||
* @param num2 the second number in Fq12
|
||||
*
|
||||
* @return a number in Fq12
|
||||
*
|
||||
*/
|
||||
q12 Q12MultMod(q12 num1, q12 num2)
|
||||
{
|
||||
q12 ret;
|
||||
|
||||
ret.high = Q4Add(
|
||||
Q4Mult(num1.high, num2.low),
|
||||
Q4Mult(num1.mid, num2.mid));
|
||||
|
||||
ret.high = Q4Add(
|
||||
ret.high,
|
||||
Q4Mult(num1.low, num2.high));
|
||||
|
||||
ret.mid = Q4Add(
|
||||
Q4Mult(num1.low, num2.mid),
|
||||
Q4Mult(num1.mid, num2.low));
|
||||
|
||||
ret.mid = Q4Add(
|
||||
ret.mid,
|
||||
Q4MultFlag(num1.high, num2.high));
|
||||
|
||||
ret.low = Q4Add(
|
||||
Q4MultFlag(num1.high, num2.mid),
|
||||
Q4MultFlag(num1.mid, num2.high));
|
||||
|
||||
ret.low = Q4Add(
|
||||
ret.low,
|
||||
Q4Mult(num1.low, num2.low));
|
||||
|
||||
return ret;
|
||||
}
|
||||
/**
|
||||
* @brief return (num1 - num2)
|
||||
*
|
||||
* @param num1 the first number in Fq12
|
||||
* @param num2 the second number in Fq12
|
||||
*
|
||||
* @return ret, a number in Fq12.
|
||||
*
|
||||
*/
|
||||
q12 Q12MinusMod(q12 num1, q12 num2)
|
||||
{
|
||||
q12 ret;
|
||||
|
||||
ret.high = Q4Minus(num1.high, num2.high);
|
||||
ret.mid = Q4Minus(num1.mid, num2.mid);
|
||||
ret.low = Q4Minus(num1.low, num2.low);
|
||||
|
||||
return ret;
|
||||
}
|
||||
/**
|
||||
* @brief return (num1 + num2)
|
||||
*
|
||||
* @param num1 the first number in Fq12
|
||||
* @param num2 the second number in Fq12
|
||||
*
|
||||
* @return ret, a number in Fq12
|
||||
*
|
||||
*/
|
||||
q12 Q12AddMod(q12 num1, q12 num2)
|
||||
{
|
||||
q12 ret;
|
||||
|
||||
ret.high = Q4Add(num1.high, num2.high);
|
||||
ret.mid = Q4Add(num1.mid, num2.mid);
|
||||
ret.low = Q4Add(num1.low, num2.low);
|
||||
|
||||
return ret;
|
||||
}
|
||||
/**
|
||||
* @brief return num^(-1)
|
||||
*
|
||||
* @param num number in Fq12
|
||||
*
|
||||
* @return ret, number in Fq12
|
||||
*
|
||||
*/
|
||||
q12 Q12Reverse(q12 num)
|
||||
{
|
||||
q12 ret;
|
||||
q4 temp1, temp2;
|
||||
|
||||
ret.low = Q4Mult(num.low, num.low);
|
||||
ret.mid = Q4Mult(num.mid, num.high);
|
||||
ret.mid = Q4Txx(ret.mid);
|
||||
ret.low = Q4Minus(ret.low, ret.mid);
|
||||
|
||||
ret.high = Q4Mult(num.high, num.high);
|
||||
ret.high = Q4Txx(ret.high);
|
||||
ret.mid = Q4Mult(num.low, num.mid);
|
||||
ret.mid = Q4Minus(ret.high, ret.mid);
|
||||
|
||||
ret.high = Q4Mult(num.mid, num.mid);
|
||||
temp1 = Q4Mult(num.low, num.high);
|
||||
ret.high = Q4Minus(ret.high, temp1);
|
||||
|
||||
temp1 = Q4Mult(num.mid, ret.high);
|
||||
temp1 = Q4Txx(temp1);
|
||||
|
||||
temp2 = Q4Mult(num.low, ret.low);
|
||||
temp1 = Q4Add(temp1, temp2);
|
||||
|
||||
temp2 = Q4Mult(num.high, ret.mid);
|
||||
temp2 = Q4Txx(temp2);
|
||||
temp1 = Q4Add(temp1, temp2);
|
||||
|
||||
temp1 = Q4Reverse(temp1);
|
||||
|
||||
ret.low = Q4Mult(ret.low, temp1);
|
||||
ret.mid = Q4Mult(ret.mid, temp1);
|
||||
ret.high = Q4Mult(ret.high, temp1);
|
||||
|
||||
return ret;
|
||||
}
|
||||
/**
|
||||
* @brief compute g^r. scan every bit of r
|
||||
*
|
||||
* @param g a number in Fq12
|
||||
* @param r power, a big number, r >= 0
|
||||
*
|
||||
* @return ret, a number in Fq12
|
||||
*
|
||||
*/
|
||||
q12 Q12PowerMod(q12 g, big8w r)
|
||||
{
|
||||
bool flag;
|
||||
int bitindex = Big8wHighestbit(&r);
|
||||
int i = BIGNUMBER_SIZE_8WORD - 1;
|
||||
uint32_t elem;
|
||||
q12 ret = g, temp = g;
|
||||
q12 one;
|
||||
|
||||
memset(&one, 0x00, BIG8W_BYTESIZE * 12);
|
||||
one.low.low.low.word[0] = 1;
|
||||
|
||||
while (i && r.word[i] == 0)
|
||||
i--;
|
||||
if (i < 0)
|
||||
return one;
|
||||
elem = r.word[i];
|
||||
|
||||
bitindex--;
|
||||
while (bitindex >= 0) {
|
||||
flag = (elem >> (bitindex--)) & 1;
|
||||
ret = Q12MultMod(temp, temp);
|
||||
if (flag)
|
||||
ret = Q12MultMod(ret, g);
|
||||
temp = ret;
|
||||
}
|
||||
|
||||
i--;
|
||||
for (; i >= 0; i--) {
|
||||
elem = r.word[i];
|
||||
bitindex = 31;
|
||||
while (bitindex >= 0) {
|
||||
flag = (elem >> (bitindex--)) & 1;
|
||||
ret = Q12MultMod(temp, temp);
|
||||
if (flag)
|
||||
ret = Q12MultMod(ret, g);
|
||||
temp = ret;
|
||||
}
|
||||
}
|
||||
|
||||
return ret;
|
||||
}
|
||||
/**
|
||||
* @brief compute f^(curve.q^(flag)); f = (f11, f10, ... f0), f^(curve.q^(flag)) = (f11*c11, f10*c10, ... f0*c0)
|
||||
*
|
||||
* @param f pointer of a number in Fq12
|
||||
* @param flag 1, 2, 6;
|
||||
*
|
||||
* @return null
|
||||
*/
|
||||
void Q12Frobenius(q12* f, uint8_t flag)
|
||||
{
|
||||
if (flag == 1) {
|
||||
f->high.high.high = Big8wMultMod(f->high.high.high, frobenius_constant_1[11], curve.q);
|
||||
f->high.high.low = Big8wMultMod(f->high.high.low, frobenius_constant_1[10], curve.q);
|
||||
f->high.low.high = Big8wMultMod(f->high.low.high, frobenius_constant_1[9], curve.q);
|
||||
f->high.low.low = Big8wMultMod(f->high.low.low, frobenius_constant_1[8], curve.q);
|
||||
|
||||
f->mid.high.high = Big8wMultMod(f->mid.high.high, frobenius_constant_1[7], curve.q);
|
||||
f->mid.high.low = Big8wMultMod(f->mid.high.low, frobenius_constant_1[6], curve.q);
|
||||
f->mid.low.high = Big8wMultMod(f->mid.low.high, frobenius_constant_1[5], curve.q);
|
||||
f->mid.low.low = Big8wMultMod(f->mid.low.low, frobenius_constant_1[4], curve.q);
|
||||
|
||||
f->low.high.high = Big8wMultMod(f->low.high.high, frobenius_constant_1[3], curve.q);
|
||||
f->low.high.low = Big8wMultMod(f->low.high.low, frobenius_constant_1[2], curve.q);
|
||||
f->low.low.high = Big8wMultMod(f->low.low.high, frobenius_constant_1[1], curve.q);
|
||||
f->low.low.low = Big8wMultMod(f->low.low.low, frobenius_constant_1[0], curve.q);
|
||||
}
|
||||
|
||||
else if (flag == 2) {
|
||||
|
||||
f->high.high.high = Big8wMultMod(f->high.high.high, frobenius_constant_2[11], curve.q);
|
||||
f->high.high.low = Big8wMultMod(f->high.high.low, frobenius_constant_2[10], curve.q);
|
||||
f->high.low.high = Big8wMultMod(f->high.low.high, frobenius_constant_2[9], curve.q);
|
||||
f->high.low.low = Big8wMultMod(f->high.low.low, frobenius_constant_2[8], curve.q);
|
||||
|
||||
f->mid.high.high = Big8wMultMod(f->mid.high.high, frobenius_constant_2[7], curve.q);
|
||||
f->mid.high.low = Big8wMultMod(f->mid.high.low, frobenius_constant_2[6], curve.q);
|
||||
f->mid.low.high = Big8wMultMod(f->mid.low.high, frobenius_constant_2[5], curve.q);
|
||||
f->mid.low.low = Big8wMultMod(f->mid.low.low, frobenius_constant_2[4], curve.q);
|
||||
|
||||
f->low.high.high = Big8wMultMod(f->low.high.high, frobenius_constant_2[3], curve.q);
|
||||
f->low.high.low = Big8wMultMod(f->low.high.low, frobenius_constant_2[2], curve.q);
|
||||
f->low.low.high = Big8wMultMod(f->low.low.high, frobenius_constant_2[1], curve.q);
|
||||
f->low.low.low = Big8wMultMod(f->low.low.low, frobenius_constant_2[0], curve.q);
|
||||
|
||||
}
|
||||
|
||||
else if (flag == 6) {
|
||||
f->high.high.high = Big8wMinusMod(curve.q, f->high.high.high, curve.q);
|
||||
f->high.high.low = Big8wMinusMod(curve.q, f->high.high.low, curve.q);
|
||||
|
||||
f->mid.low.high = Big8wMinusMod(curve.q, f->mid.low.high, curve.q);
|
||||
f->mid.low.low = Big8wMinusMod(curve.q, f->mid.low.low, curve.q);
|
||||
|
||||
f->low.high.high = Big8wMinusMod(curve.q, f->low.high.high, curve.q);
|
||||
f->low.high.low = Big8wMinusMod(curve.q, f->low.high.low, curve.q);
|
||||
}
|
||||
}
|
||||
/**
|
||||
*
|
||||
* @brief compute Frobenius(Q)
|
||||
* Q = Q(x, y), point in group G2;first convert x, y to q12 number:(x*beta^(-1/2), y*beta(-1/3))
|
||||
* then run Q12Frobenius, last convert back to G2point(ret.x*(beta^(1/2)), ret.y*(beta^(1/3)))
|
||||
*
|
||||
* @param Q point in group G2
|
||||
* @param Q1 pointer of a point in group G2, store the result
|
||||
* @param flag power of frobenius
|
||||
*
|
||||
* @result Q1
|
||||
*
|
||||
*/
|
||||
void G2pointFrobenius(G2point Q, G2point* Q1, uint8_t flag)
|
||||
{
|
||||
q12 temp, ret;
|
||||
|
||||
Q12Zero(&temp);
|
||||
Q12Zero(&ret);
|
||||
|
||||
ret.low.low = Q.x;
|
||||
temp.mid.high.high = qnr;
|
||||
ret = Q12MultMod(ret, temp);
|
||||
Q12Frobenius(&ret, flag);
|
||||
memset(temp.mid.high.high.word, 0x00, BIG8W_BYTESIZE);
|
||||
temp.high.low.low.word[0] = 1;
|
||||
ret = Q12MultMod(ret, temp);
|
||||
Q1->x = ret.low.low;
|
||||
|
||||
Q12Zero(&ret);
|
||||
Q12Zero(&temp);
|
||||
|
||||
ret.low.low = Q.y;
|
||||
temp.low.high.high = qnr;
|
||||
ret = Q12MultMod(ret, temp);
|
||||
Q12Frobenius(&ret, flag);
|
||||
memset(temp.low.high.high.word, 0x00, BIG8W_BYTESIZE);
|
||||
temp.low.high.low.word[0] = 1;
|
||||
ret = Q12MultMod(ret, temp);
|
||||
Q1->y = ret.low.low;
|
||||
}
|
||||
/**
|
||||
* @brief line function defined in SM9 and a Q12MultMod
|
||||
*
|
||||
* @param P a point in group G1
|
||||
* @param T a pointer of a point in group G2
|
||||
* @param Q a point in group G2
|
||||
* @param doubleflag if (*T) == Q
|
||||
* @param f a pointer of a number in Fq12, (*f) = (*f) * g(T, Q, P), g(T, Q, P) is the line function defined in SM9
|
||||
*
|
||||
* @return null
|
||||
*
|
||||
*/
|
||||
void Line(G1point P, G2point* T, G2point Q, bool doubleflag, q12* f)
|
||||
{
|
||||
q2 lambda, temp;
|
||||
q12 ret;
|
||||
|
||||
Q12Zero(&ret);
|
||||
Q2Zero(&temp);
|
||||
|
||||
if (doubleflag) {
|
||||
|
||||
if (Q2Equal(&Q.x, &temp) && Q2Equal(&Q.y, &temp)) // Q = T = O
|
||||
return;
|
||||
|
||||
lambda = Q2Mult(Q.x, Q.x);
|
||||
lambda = Q2Add(lambda, Q2Add(lambda, lambda));
|
||||
lambda = Q2Mult(
|
||||
lambda,
|
||||
Q2Reverse(Q2Add(Q.y, Q.y)));
|
||||
}
|
||||
else {
|
||||
if (Q2Equal(&T->x, &Q.x)){
|
||||
// T = -Q => T = T + Q = O
|
||||
Q2Zero(&T->x), Q2Zero(&T->y);
|
||||
// g(T, Q, P) = xP - xQ
|
||||
temp.high = qnr;
|
||||
temp = Q2Mult(temp, Q.x);
|
||||
temp = Q2Negate(temp);
|
||||
ret.mid.high = temp;
|
||||
ret.low.low.low = P.x;
|
||||
|
||||
*f = Q12MultMod(*f, ret);
|
||||
}
|
||||
else if (Q2Equal(&T->x, &temp) && Q2Equal(&T->y, &temp)){ // T = O
|
||||
// g(U, V, O) = 1 => f * g(U, V, O) = f; *T = T + Q = Q
|
||||
*T = Q;
|
||||
return;
|
||||
}
|
||||
else if (Q2Equal(&Q.x, &temp) && Q2Equal(&Q.y, &temp)){ // Q = O
|
||||
// g(U, V, O) = 1 => f * g(U, V, O) = f; *T = T + Q = T
|
||||
return;
|
||||
}
|
||||
|
||||
lambda = Q2Mult(
|
||||
Q2Minus(T->y, Q.y),
|
||||
Q2Reverse(Q2Minus(T->x, Q.x)));
|
||||
}
|
||||
|
||||
temp.high = qnr;
|
||||
|
||||
ret.high.high = lambda;
|
||||
ret.high.high.high = Big8wMultMod(ret.high.high.high, P.x, curve.q);
|
||||
ret.high.high.low = Big8wMultMod(ret.high.high.low, P.x, curve.q);
|
||||
ret.high.high = Q2Mult(ret.high.high, temp);
|
||||
|
||||
ret.low.high = Q2Minus(
|
||||
T->y,
|
||||
Q2Mult(lambda, T->x));
|
||||
ret.low.high = Q2Mult(temp, ret.low.high);
|
||||
|
||||
ret.low.low.low = Big8wMinusMod(curve.q, P.y, curve.q);
|
||||
|
||||
*T = G2PointAdd(Q, *T);
|
||||
*f = Q12MultMod(ret, *f);
|
||||
}
|
||||
/**
|
||||
* @brief compute (f^(curve.q^(12) - 1)), called by BiLinearParing function(in topfunc.h).
|
||||
*
|
||||
* @param f a pointer of a number in Fq12
|
||||
*
|
||||
* @return null, result stored in *f.
|
||||
*
|
||||
*/
|
||||
// t = 0x60000000 0058F98A
|
||||
void LastPower(q12* f)
|
||||
{
|
||||
q12 m, g, s, temp;
|
||||
|
||||
m = Q12Reverse(*f);
|
||||
Q12Frobenius(f, 6);
|
||||
// f = f^(q^6 - 1)
|
||||
*f = Q12MultMod(*f, m);
|
||||
m = *f;
|
||||
Q12Frobenius(f, 2);
|
||||
*f = Q12MultMod(*f, m); // f = f^(q^6 - 1)(q^2+1)
|
||||
s = *f;
|
||||
|
||||
// hard part
|
||||
s = *f;
|
||||
m = s, temp = m;
|
||||
Q12Frobenius(&temp, 1);
|
||||
s = temp;
|
||||
Q12Frobenius(&temp, 1);
|
||||
s = Q12MultMod(s, temp);
|
||||
Q12Frobenius(&temp, 1);
|
||||
s = Q12MultMod(s, temp);
|
||||
|
||||
temp = Q12PowerMod(m, t);
|
||||
temp = Q12PowerMod(temp, t);
|
||||
|
||||
g = Q12MultMod(temp, temp);
|
||||
temp = Q12MultMod(g, g);
|
||||
temp = Q12MultMod(temp, g);
|
||||
Q12Frobenius(&temp, 2);
|
||||
|
||||
s = Q12MultMod(s, temp);
|
||||
|
||||
temp = m;
|
||||
Q12Frobenius(&temp, 6);
|
||||
temp = Q12MultMod(temp, temp);
|
||||
s = Q12MultMod(s, temp);
|
||||
g = temp;
|
||||
|
||||
temp = Q12MultMod(g, g);
|
||||
g = Q12MultMod(temp, g);
|
||||
g = Q12PowerMod(g, t);
|
||||
|
||||
temp = Q12MultMod(g, g);
|
||||
s = Q12MultMod(s, Q12MultMod(temp, g));
|
||||
Q12Frobenius(&temp, 1);
|
||||
s = Q12MultMod(s, temp);
|
||||
|
||||
g = Q12PowerMod(g, t);
|
||||
temp = Q12MultMod(g, g);
|
||||
m = Q12MultMod(g, temp);
|
||||
s = Q12MultMod(s, m);
|
||||
s = Q12MultMod(s, temp);
|
||||
g = m;
|
||||
Q12Frobenius(&m, 1);
|
||||
s = Q12MultMod(s, m);
|
||||
|
||||
g = Q12MultMod(g, g);
|
||||
g = Q12PowerMod(g, t);
|
||||
|
||||
s = Q12MultMod(s, g);
|
||||
Q12Frobenius(&g, 1);
|
||||
s = Q12MultMod(s, g);
|
||||
|
||||
*f = s;;
|
||||
}
|
|
@ -0,0 +1,646 @@
|
|||
/*
|
||||
* Copyright (c) 2020 AIIT Ubiquitous Team
|
||||
* XiUOS is licensed under Mulan PSL v2.
|
||||
* You can use this software according to the terms and conditions of the Mulan PSL v2.
|
||||
* You may obtain a copy of Mulan PSL v2 at:
|
||||
* http://license.coscl.org.cn/MulanPSL2
|
||||
* THIS SOFTWARE IS PROVIDED ON AN "AS IS" BASIS, WITHOUT WARRANTIES OF ANY KIND,
|
||||
* EITHER EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO NON-INFRINGEMENT,
|
||||
* MERCHANTABILITY OR FIT FOR A PARTICULAR PURPOSE.
|
||||
* See the Mulan PSL v2 for more details.
|
||||
*/
|
||||
|
||||
/**
|
||||
* @file sm9.c
|
||||
* @brief API of SM9
|
||||
* @version 1.0
|
||||
* @author AIIT Ubiquitous Team
|
||||
* @date 2021-04-24
|
||||
*/
|
||||
#include <sm9.h>
|
||||
|
||||
#define SM4OUT 16 // 128 / 8
|
||||
|
||||
/**
|
||||
* @brief initialization function, to set value of SM9 curve elements and other essential parameters.
|
||||
*
|
||||
* @param null
|
||||
*
|
||||
* @result null
|
||||
*
|
||||
*/
|
||||
|
||||
void SM9Init()
|
||||
{
|
||||
big8w one;
|
||||
memset(one.word, 0x00, BIG8W_BYTESIZE);
|
||||
one.word[0] = 1;
|
||||
memset(curve.b.word, 0x00, BIG8W_BYTESIZE);
|
||||
curve.b.word[0] = 0x05;
|
||||
memcpy(curve.q.word, sm9_q, BIG8W_BYTESIZE);
|
||||
memcpy(curve.N.word, sm9_N, BIG8W_BYTESIZE);
|
||||
memcpy(P1.x.word, sm9_P1_x, BIG8W_BYTESIZE);
|
||||
memcpy(P1.y.word, sm9_P1_y, BIG8W_BYTESIZE);
|
||||
memcpy(P2.x.high.word, sm9_P2_x_high, BIG8W_BYTESIZE);
|
||||
memcpy(P2.x.low.word, sm9_P2_x_low, BIG8W_BYTESIZE);
|
||||
memcpy(P2.y.high.word, sm9_P2_y_high, BIG8W_BYTESIZE);
|
||||
memcpy(P2.y.low.word, sm9_P2_y_low, BIG8W_BYTESIZE);
|
||||
memset(t.word, 0x00, BIG8W_BYTESIZE);
|
||||
t.word[0] = 0x0058F98A, t.word[1] = 0x60000000;
|
||||
frobenius_constant_1[0] = one;
|
||||
memcpy(frobenius_constant_1[1].word, fc1_1, BIG8W_BYTESIZE);
|
||||
memcpy(frobenius_constant_1[2].word, fc1_2, BIG8W_BYTESIZE);
|
||||
memcpy(frobenius_constant_1[3].word, fc1_3, BIG8W_BYTESIZE);
|
||||
memcpy(frobenius_constant_1[4].word, fc1_4, BIG8W_BYTESIZE);
|
||||
memcpy(frobenius_constant_1[5].word, fc1_5, BIG8W_BYTESIZE);
|
||||
memcpy(frobenius_constant_1[6].word, fc1_6, BIG8W_BYTESIZE);
|
||||
memcpy(frobenius_constant_1[7].word, fc1_7, BIG8W_BYTESIZE);
|
||||
memcpy(frobenius_constant_1[8].word, fc1_8, BIG8W_BYTESIZE);
|
||||
memcpy(frobenius_constant_1[9].word, fc1_9, BIG8W_BYTESIZE);
|
||||
memcpy(frobenius_constant_1[10].word, fc1_10, BIG8W_BYTESIZE);
|
||||
memcpy(frobenius_constant_1[11].word, fc1_11, BIG8W_BYTESIZE);
|
||||
frobenius_constant_2[0] = one;
|
||||
frobenius_constant_2[1] = one;
|
||||
memcpy(frobenius_constant_2[2].word, fc2_2, BIG8W_BYTESIZE);
|
||||
memcpy(frobenius_constant_2[3].word, fc2_3, BIG8W_BYTESIZE);
|
||||
memcpy(frobenius_constant_2[4].word, fc2_4, BIG8W_BYTESIZE);
|
||||
memcpy(frobenius_constant_2[5].word, fc2_5, BIG8W_BYTESIZE);
|
||||
memcpy(frobenius_constant_2[6].word, fc2_6, BIG8W_BYTESIZE);
|
||||
memcpy(frobenius_constant_2[7].word, fc2_7, BIG8W_BYTESIZE);
|
||||
memcpy(frobenius_constant_2[8].word, fc2_8, BIG8W_BYTESIZE);
|
||||
memcpy(frobenius_constant_2[9].word, fc2_9, BIG8W_BYTESIZE);
|
||||
memcpy(frobenius_constant_2[10].word, fc2_10, BIG8W_BYTESIZE);
|
||||
memcpy(frobenius_constant_2[11].word, fc2_11, BIG8W_BYTESIZE);
|
||||
memcpy(qnr.word, sm9_qnr, BIG8W_BYTESIZE);
|
||||
memcpy(q_2k.word, sm9_q_2k, BIG8W_BYTESIZE);
|
||||
memcpy(N_2k.word, sm9_N_2k, BIG8W_BYTESIZE);
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
*
|
||||
* @brief sign algorithm of SM9
|
||||
*
|
||||
* @param message data need to sign with sign_secretkey
|
||||
* @param msgbytelen length of message, byte size
|
||||
* @param ds sign_secretkey
|
||||
* @param Ppub_s sign_publickey
|
||||
*
|
||||
* @return Signature
|
||||
*
|
||||
*/
|
||||
Signature SM9Sign(unsigned char *message, uint32_t msgbytelen, G1point ds, G2point Ppub_s)
|
||||
{
|
||||
uint8_t *msg_w;
|
||||
big8w r, L_temp, zero;
|
||||
q12 g, w;
|
||||
Signature sig;
|
||||
|
||||
msg_w = (uint8_t *)(malloc(msgbytelen + BIG8W_BYTESIZE * 12));
|
||||
|
||||
memset(zero.word, 0x00, BIG8W_BYTESIZE);
|
||||
|
||||
g = BiLinearPairing(P1, Ppub_s); //e(P1, Ppub_s)
|
||||
|
||||
do
|
||||
{
|
||||
r = RandomNumGenerate();
|
||||
|
||||
w = Q12PowerMod(g, r); // w = g^r
|
||||
|
||||
JoinMsgW(message, msgbytelen, &w, msg_w);
|
||||
sig.h = H(msg_w, msgbytelen + BIG8W_BYTESIZE * 12, 0x02);
|
||||
|
||||
L_temp = Big8wMinusMod(r, sig.h, curve.N);
|
||||
} while (Big8wEqual(&L_temp, &zero));
|
||||
|
||||
sig.S = G1pointMult(L_temp, ds);
|
||||
|
||||
free(msg_w);
|
||||
|
||||
return sig;
|
||||
}
|
||||
/**
|
||||
*
|
||||
* @brief signature verify algorithm of SM9
|
||||
*
|
||||
* @param ID id of user who generate the signature
|
||||
* @param IDlen length of ID
|
||||
* @param hid function id defined in SM9
|
||||
* @param message message that received from counterpart
|
||||
* @param msgbytelen length of message, byte size
|
||||
* @param signature signature received from counterpart
|
||||
* @param Ppub_s sign_publickey
|
||||
*
|
||||
* @return true if signature verified successfully, else false
|
||||
*
|
||||
*/
|
||||
bool SM9VerifySignature(
|
||||
unsigned char* ID, unsigned char IDlen, unsigned char hid,
|
||||
unsigned char* message, unsigned int msgbytelen,
|
||||
Signature signature, G2point Ppub_s)
|
||||
{
|
||||
unsigned char *msg_w;
|
||||
big8w zero, h;
|
||||
G2point P;
|
||||
q12 g, t, w;
|
||||
|
||||
msg_w = (unsigned char *)(malloc(msgbytelen + BIG8W_BYTESIZE * 12));
|
||||
memset(zero.word, 0x00, BIG8W_BYTESIZE);
|
||||
|
||||
if (Big8wBigThan(&signature.h, &curve.N)
|
||||
|| Big8wEqual(&signature.h, &zero))
|
||||
return false;
|
||||
|
||||
if (!PointInG1(signature.S))
|
||||
return false;
|
||||
|
||||
g = BiLinearPairing(P1, Ppub_s);
|
||||
|
||||
t = Q12PowerMod(g, signature.h);
|
||||
|
||||
unsigned char* id_hid;
|
||||
id_hid = (unsigned char*)malloc((IDlen + 1));
|
||||
JoinIDhid(ID, IDlen, hid, id_hid);
|
||||
|
||||
h = H(id_hid, IDlen + 1, 0x01);
|
||||
|
||||
P = G2PointMult(h, P2);
|
||||
|
||||
P = G2PointAdd(P, Ppub_s);
|
||||
|
||||
g = BiLinearPairing(signature.S, P);
|
||||
|
||||
w = Q12MultMod(g, t);
|
||||
|
||||
JoinMsgW(message, msgbytelen, &w, msg_w);
|
||||
h = H(msg_w, msgbytelen + BIG8W_BYTESIZE * 12, 0x02);
|
||||
|
||||
free(id_hid);
|
||||
free(msg_w);
|
||||
|
||||
return Big8wEqual(&h, &signature.h);
|
||||
}
|
||||
/**
|
||||
*
|
||||
* @brief the first step of key exchange of SM9, produce R(the data send to the counterpart)
|
||||
*
|
||||
* @param ID ID of counterpart
|
||||
* @param IDlen length of ID
|
||||
* @param r a pointer of a big number, random big number
|
||||
* @param R a pointer of a point in group G1, store the result
|
||||
* @param encrypt_publickey encrypt_publickey
|
||||
*
|
||||
* @result R
|
||||
*
|
||||
*/
|
||||
void SM9KeyExchangeProduceR(unsigned char* ID, unsigned char IDlen, big8w* r, G1point* R, G1point encrypt_publickey)
|
||||
{
|
||||
unsigned char hid = 0x02;
|
||||
unsigned char *id_hid;
|
||||
|
||||
id_hid = (unsigned char *)(malloc(IDlen + 1));
|
||||
|
||||
JoinIDhid(ID, IDlen, hid, id_hid);
|
||||
|
||||
*R = G1pointMult(H(id_hid, IDlen + 1, 0x01), P1);
|
||||
*R = G1pointAdd(*R, encrypt_publickey);
|
||||
*r = RandomNumGenerate();
|
||||
*R = G1pointMult(*r, *R);
|
||||
|
||||
free(id_hid);
|
||||
}
|
||||
/**
|
||||
*
|
||||
* @brief the second step of key exchange of SM9, produce key
|
||||
*
|
||||
* @param RA a pointer of a point in group G1, produced in function SM9KeyExchangeProduceR
|
||||
* @param RB a pointer of a point in group G1, received from counterpart
|
||||
* @param r a pointer of a big number, random big number, produced in function SM9KeyExchangeProduceR.
|
||||
* @param klen_bitsize length of key to be generated, bit size!!!
|
||||
* @param challengerID ID of the challenger of key exchange
|
||||
* @param challengerIDlen length of chalengerID
|
||||
* @param responserID ID of the responser of key exchange
|
||||
* @param responserIDlen length of responserID
|
||||
* @param resultkey unsigned char string, store the key generated in key exchange
|
||||
* @param encrypt_publickey encrypt public key
|
||||
* @param encrypt_secretkey encrypt secret key
|
||||
*
|
||||
* @result resultkey
|
||||
*
|
||||
*/
|
||||
bool SM9KeyExchangeProduceKey(G1point* RA, G1point* RB, big8w* r, uint32_t klen_bitsize,
|
||||
unsigned char* challengerID, unsigned char challengerIDlen,
|
||||
unsigned char* responserID, unsigned char responserIDlen,
|
||||
q12 *g1, q12* g2, q12* g3, char* resultkey, bool sponsor,
|
||||
G1point encrypt_publickey, G2point encrypt_secretkey)
|
||||
{
|
||||
|
||||
unsigned char *string;
|
||||
int i, stringlen;
|
||||
|
||||
stringlen = challengerIDlen + responserIDlen + BIG8W_BYTESIZE * (2 * 2 + 12 * 3);
|
||||
string = (uint8_t *)(malloc(stringlen));
|
||||
|
||||
if (!PointInG1(*RB)){
|
||||
printf("Point error, point is not in G1\n");
|
||||
return false;
|
||||
}
|
||||
|
||||
*g1 = BiLinearPairing(encrypt_publickey, P2);
|
||||
*g1 = Q12PowerMod(*g1, *r);
|
||||
|
||||
*g2 = BiLinearPairing(*RB, encrypt_secretkey);
|
||||
|
||||
if (!sponsor){ // notice that the format of challenger and responser is similar.
|
||||
*g3 = *g1;
|
||||
*g1 = *g2;
|
||||
*g2 = *g3;
|
||||
}
|
||||
|
||||
*g3 = Q12PowerMod(*g2, *r);
|
||||
|
||||
JoinIDAIDBRARBg123(challengerID, challengerIDlen, responserID, responserIDlen, RA, RB, g1, g2, g3, string);
|
||||
|
||||
KDF(string, stringlen, klen_bitsize, (uint8_t*)resultkey);
|
||||
|
||||
free(string);
|
||||
|
||||
return true;
|
||||
}
|
||||
/**
|
||||
* @brief the third step of SM9 key exchange, to verify the key is right.
|
||||
*
|
||||
* @param g1 pointer of the first q12 number
|
||||
* @param g2 pointer of the second q12 number
|
||||
* @param g3 pointer of the second q12 number
|
||||
* @param RA pointer of a G1point of the challenger
|
||||
* @param RB pointer of a G1point of the responser
|
||||
* @param challengerID ID of the challenger of key exchange
|
||||
* @param challengerIDlen length of chalengerID
|
||||
* @param responserID ID of the responser of key exchange
|
||||
* @param responserIDlen length of responserID
|
||||
* @param S1 hash value, function flag = 0x82
|
||||
* @param SA hash value, function flag = 0x83
|
||||
*
|
||||
* @result two hash values: S1, SA
|
||||
*
|
||||
*/
|
||||
bool SM9KeyExchangeVerifyKey(q12* g1, q12 *g2, q12* g3, G1point* RA, G1point* RB,
|
||||
unsigned char* challengerID, unsigned char challengerIDlen,
|
||||
unsigned char* responserID, unsigned char responserIDlen,
|
||||
unsigned char *S1, unsigned char* SA)
|
||||
{
|
||||
HashTwice(challengerID, challengerIDlen, responserID, responserIDlen, RA, RB, g1, g2, g3, 0x82, S1);
|
||||
|
||||
HashTwice(challengerID, challengerIDlen, responserID, responserIDlen, RA, RB, g1, g2, g3, 0x83, SA);
|
||||
}
|
||||
/**
|
||||
*
|
||||
* @brief key encapsulation define in SM9, called by encrypt of SM9.
|
||||
*
|
||||
* @param ID counterpart's ID
|
||||
* @param IDlen length of ID
|
||||
* @param hid function flag defined in SM9,
|
||||
* @param Ppub_e encrypt_publickey
|
||||
* @param klen_bitsize length of key to be generated by KDF(), bit size!!!
|
||||
* @param K key generated by KDF()
|
||||
* @param C packaged K
|
||||
*
|
||||
* @result K, C
|
||||
*
|
||||
*/
|
||||
void SM9KeyPackage(unsigned char* ID, unsigned char IDlen, unsigned char hid, G1point Ppub_e, uint32_t klen_bitsize, unsigned char* K, G1point* C)
|
||||
{
|
||||
unsigned char *c_w_id, * id_hid;
|
||||
big8w r;
|
||||
G1point temp, QB;
|
||||
q12 g;
|
||||
|
||||
c_w_id = (unsigned char*)(malloc(BIG8W_BYTESIZE * 2 + BIG8W_BYTESIZE * 12 + IDlen));
|
||||
id_hid = (unsigned char*)(malloc(IDlen + 1));
|
||||
|
||||
JoinIDhid(ID, IDlen, hid, id_hid);
|
||||
|
||||
QB = G1pointMult(
|
||||
H(id_hid, IDlen + 1, 0x01),
|
||||
P1);
|
||||
QB = G1pointAdd(QB, Ppub_e);
|
||||
|
||||
do {
|
||||
r = RandomNumGenerate();
|
||||
|
||||
temp = G1pointMult(r,QB);
|
||||
|
||||
g = BiLinearPairing(Ppub_e, P2);
|
||||
|
||||
g = Q12PowerMod(g, r);
|
||||
|
||||
JoinCwID(&temp, &g, ID, IDlen, c_w_id);
|
||||
|
||||
KDF(c_w_id, BIG8W_BYTESIZE * 2 + BIG8W_BYTESIZE * 12 + IDlen, klen_bitsize, K);
|
||||
|
||||
} while (StringEqualZero(K, klen_bitsize));
|
||||
|
||||
free(c_w_id);
|
||||
free(id_hid);
|
||||
|
||||
*C = temp;
|
||||
}
|
||||
/**
|
||||
*
|
||||
* @brief key depackage of SM9
|
||||
*
|
||||
* @param C a point in group G1, received from the counterpart
|
||||
* @param de encrypt_secretkey
|
||||
* @param ID ID of self
|
||||
* @param IDlen length of ID
|
||||
* @param klen_bitsize length of key to be generated, bit size!!!
|
||||
* @param K key generated
|
||||
*
|
||||
* @result K
|
||||
*
|
||||
*/
|
||||
bool SM9KeyDepackage(G1point C, G2point de, unsigned char* ID, unsigned char IDlen, unsigned int klen_bitsize, unsigned char* K)
|
||||
{
|
||||
unsigned char* c_w_id;
|
||||
q12 w;
|
||||
|
||||
c_w_id = (unsigned char*)(malloc(BIG8W_BYTESIZE * 2 + BIG8W_BYTESIZE * 12 + IDlen));
|
||||
|
||||
if (!PointInG1(C)){
|
||||
printf("point not in G1\n");
|
||||
free(c_w_id);
|
||||
return false;
|
||||
}
|
||||
|
||||
w = BiLinearPairing(C, de);
|
||||
|
||||
JoinCwID(&C, &w, ID, IDlen, c_w_id);
|
||||
|
||||
|
||||
KDF(c_w_id, BIG8W_BYTESIZE * 2 + BIG8W_BYTESIZE * 12 + IDlen, klen_bitsize, K);
|
||||
|
||||
free(c_w_id);
|
||||
|
||||
if (StringEqualZero(K, klen_bitsize))
|
||||
return false;
|
||||
|
||||
return true;
|
||||
}
|
||||
/**
|
||||
*
|
||||
* @brief Encrypt of SM9 with KDF
|
||||
*
|
||||
* @param message data to be encrypted
|
||||
* @param msglen_bitsieze length of message, bit size!!!
|
||||
* @param K2_len_bitsize K2_len, defined in SM9
|
||||
* @param ID ID of counterpart
|
||||
* @param IDlen length of ID
|
||||
* @param hid function flag defined in SM9
|
||||
* @param Ppub_e encrypt_publickey
|
||||
* @param C ciphertext of message
|
||||
*
|
||||
* @result C
|
||||
*
|
||||
*/
|
||||
bool SM9EncryptWithKDF(unsigned char* message, unsigned int msglen_bitsize, unsigned int K2_len_bitsize,
|
||||
unsigned char* ID, unsigned char IDlen, unsigned char hid, G1point Ppub_e, unsigned char *C)
|
||||
{
|
||||
unsigned int i;
|
||||
unsigned int klen_bitsize = msglen_bitsize + K2_len_bitsize;
|
||||
unsigned char *K, *C2, *C3, *C2K2;
|
||||
G1point C1;
|
||||
|
||||
K = (uint8_t *)(malloc( ((klen_bitsize >> 8) + 1) * (SM3OUT_32BYTES)) );
|
||||
C2 = (uint8_t *)(malloc(msglen_bitsize >> 3)); // msglen_bitsize / 8
|
||||
C3 = (uint8_t *)(malloc(BIG8W_BYTESIZE));
|
||||
C2K2 = (uint8_t *)(malloc((msglen_bitsize >> 3) + (K2_len_bitsize >> 3))); // msglen_bitsize / 8 + K2_len_bitsize / 8
|
||||
|
||||
do{
|
||||
SM9KeyPackage(ID, IDlen, hid, Ppub_e, klen_bitsize, K, &C1);
|
||||
} while (StringEqualZero(K, msglen_bitsize >> 3));
|
||||
|
||||
XOR(message, msglen_bitsize >> 3, K, C2);
|
||||
|
||||
for (i = 0; i < msglen_bitsize >> 3 ; i++)
|
||||
C2K2[i] = C2[i];
|
||||
for (i; i < (klen_bitsize >> 3); i++)
|
||||
C2K2[i] = K[i];
|
||||
|
||||
sm3(C2K2, (msglen_bitsize >> 3) + (K2_len_bitsize >> 3), C3);
|
||||
|
||||
// C = C1||C3||C2
|
||||
i = 0;
|
||||
Big8wIntou8string(&C1.x, C, i);
|
||||
i += BIG8W_BYTESIZE;
|
||||
Big8wIntou8string(&C1.y, C, i);
|
||||
i += BIG8W_BYTESIZE;
|
||||
|
||||
for (i = BIG8W_BYTESIZE * 2; i < BIG8W_BYTESIZE * 2 + (SM3OUT_32BYTES); i++)
|
||||
C[i] = C3[i - BIG8W_BYTESIZE * 2];
|
||||
|
||||
for (; i < BIG8W_BYTESIZE * 2 + (SM3OUT_32BYTES) + (msglen_bitsize >> 3); i++)
|
||||
C[i] = C2[i - (BIG8W_BYTESIZE * 2 + SM3OUT_32BYTES)];
|
||||
|
||||
free(C2);
|
||||
free(C3);
|
||||
free(C2K2);
|
||||
free(K);
|
||||
|
||||
return true;
|
||||
}
|
||||
/**
|
||||
*
|
||||
* @brief Decrypt function of SM9 with KDF
|
||||
*
|
||||
* @param ID ID of self
|
||||
* @param IDlen length of ID
|
||||
* @param message decrypted date
|
||||
* @param msglen_bitsize length of message, bit size!!!
|
||||
* @param K2_len_bitsize K2_len defined in SM9
|
||||
* @param C ciphertext, received from counterpart
|
||||
* @param encrypt_secretkey encrypt_secretkey of self
|
||||
*
|
||||
* @result message
|
||||
*
|
||||
*/
|
||||
bool SM9DecryptWithKDF(unsigned char* ID, unsigned char IDlen,
|
||||
unsigned char* message, unsigned int msglen_bitsize, unsigned int K2_len_bitsize,
|
||||
unsigned char *C, G2point encrypt_secretkey)
|
||||
{
|
||||
G1point C1;
|
||||
|
||||
unsigned char *K;
|
||||
unsigned char *u;
|
||||
unsigned char *C2K2;
|
||||
unsigned int i;
|
||||
unsigned int klen_bitsize = msglen_bitsize + K2_len_bitsize;
|
||||
|
||||
K = (uint8_t *)(malloc( ((klen_bitsize >> 8) + 1) * (SM3OUT_32BYTES)) );
|
||||
u = (unsigned char *)(malloc(SM3OUT_32BYTES));
|
||||
C2K2 = (unsigned char *)(malloc((msglen_bitsize >> 3) + (K2_len_bitsize >> 3)));
|
||||
|
||||
U8stringToG1point(C, &C1);
|
||||
|
||||
SM9KeyDepackage(C1, encrypt_secretkey, ID, IDlen, msglen_bitsize + K2_len_bitsize, K);
|
||||
|
||||
if (StringEqualZero(K, msglen_bitsize >> 3)){
|
||||
free(K);
|
||||
free(u);
|
||||
free(C2K2);
|
||||
return false;
|
||||
}
|
||||
|
||||
XOR(K, msglen_bitsize >> 3, C + BIG8W_BYTESIZE * 2 + BIG8W_BYTESIZE, (unsigned char*)message);
|
||||
|
||||
for (i = 0; i < msglen_bitsize >> 3; i++)
|
||||
C2K2[i] = (C + BIG8W_BYTESIZE * 2 + BIG8W_BYTESIZE)[i];
|
||||
for (; i < (msglen_bitsize >> 3) + (K2_len_bitsize >> 3); i++)
|
||||
C2K2[i] = K[i];
|
||||
|
||||
sm3(C2K2, (msglen_bitsize >> 3) + (K2_len_bitsize >> 3), u);
|
||||
|
||||
free(K);
|
||||
free(C2K2);
|
||||
|
||||
for (i = 0; i < SM3OUT_32BYTES; i++)
|
||||
if (u[i] != (C + BIG8W_BYTESIZE * 2)[i])
|
||||
{
|
||||
printf("hash value error!\n");
|
||||
free(u);;
|
||||
return false;
|
||||
}
|
||||
|
||||
free(u);
|
||||
|
||||
return true;
|
||||
}
|
||||
/**
|
||||
*
|
||||
* @brief Encrypt function of SM9 with SM4
|
||||
*
|
||||
* @param message data to be encrypted
|
||||
* @param msglen_bitsize length of message, bit size !!!
|
||||
* @param K1_len_bitsize K1_len defined in SM9, length of the key of SM4
|
||||
* @param K2_len_bitsize K2_len defined in SM9
|
||||
* @param ID ID of counterpart
|
||||
* @param IDlen length of ID
|
||||
* @param hid function flag defined in SM9
|
||||
* @param Ppub_e encrypt_publickey
|
||||
* @param C ciphertext of message
|
||||
*
|
||||
* @result C
|
||||
*
|
||||
*/
|
||||
bool SM9EncryptWithSM4(unsigned char* message, unsigned int msglen_bitsize,
|
||||
unsigned int K1_len_bitsize, unsigned int K2_len_bitsize,
|
||||
unsigned char* ID, unsigned char IDlen, unsigned char hid, G1point Ppub_e,
|
||||
unsigned char *C)
|
||||
{
|
||||
unsigned int i;
|
||||
unsigned int klen_bitsize = K1_len_bitsize + K2_len_bitsize;
|
||||
unsigned int C2byteslen = ((K1_len_bitsize >> 7) + 1) * (SM4OUT);
|
||||
unsigned char *K, *C2, *C3, *C2K2;
|
||||
G1point C1;
|
||||
|
||||
K = (uint8_t *)(malloc(((klen_bitsize >> 8) + 1) * SM3OUT_32BYTES));
|
||||
C2 = (uint8_t *)(malloc(C2byteslen));
|
||||
C3 = (uint8_t *)(malloc(256 / 8));
|
||||
C2K2 = (uint8_t *)(malloc(C2byteslen + (K2_len_bitsize >> 3)));
|
||||
|
||||
do{
|
||||
SM9KeyPackage(ID, IDlen, hid, Ppub_e, klen_bitsize, K, &C1);
|
||||
} while (StringEqualZero(K, K1_len_bitsize >> 3));
|
||||
|
||||
SM4EncryptWithEcbMode(message, (msglen_bitsize >> 3), K, C2);
|
||||
|
||||
for (i = 0; i < C2byteslen; i++) // join C2
|
||||
C2K2[i] = C2[i];
|
||||
for (; i < C2byteslen + (K2_len_bitsize >> 3); i++) // join K2
|
||||
C2K2[i] = K[i - C2byteslen + (K1_len_bitsize >> 3)];
|
||||
|
||||
sm3(C2K2, C2byteslen + (K2_len_bitsize >> 3), C3);
|
||||
|
||||
// C = C1||C3||C2
|
||||
i = 0;
|
||||
Big8wIntou8string(&C1.x, C, i);
|
||||
i += BIG8W_BYTESIZE;
|
||||
Big8wIntou8string(&C1.y, C, i);
|
||||
i += BIG8W_BYTESIZE;
|
||||
|
||||
for (i = BIG8W_BYTESIZE * 2; i < BIG8W_BYTESIZE * 2 + SM3OUT_32BYTES; i++)
|
||||
C[i] = C3[i - (BIG8W_BYTESIZE * 2)];
|
||||
|
||||
for (i = BIG8W_BYTESIZE * 2 + SM3OUT_32BYTES; i < BIG8W_BYTESIZE * 2 + SM3OUT_32BYTES + C2byteslen; i++)
|
||||
C[i] = C2[i - (BIG8W_BYTESIZE * 2 + SM3OUT_32BYTES)];
|
||||
|
||||
free(C2);
|
||||
free(C3);
|
||||
free(C2K2);
|
||||
free(K);
|
||||
|
||||
return true;
|
||||
}
|
||||
/**
|
||||
*
|
||||
* @brief Decrypt of SM9 with SM4
|
||||
*
|
||||
* @param ID ID of self
|
||||
* @param IDlen length of ID
|
||||
* @param message message to be decrypted, store the result
|
||||
* @param msglen length of message, byte size
|
||||
* @param K1_len_bitsize K1_len defined in SM9, bit size, length of key of SM4
|
||||
* @param K2_len_bitsize K2_len defined in SM9, bit size
|
||||
* @param C ciphertext received from counterpart
|
||||
* @param Cbyteslen length of C, byte size
|
||||
* @param encrypt_secretkey encrypt_secretkey of self
|
||||
*
|
||||
* @result message
|
||||
*
|
||||
*/
|
||||
bool SM9DecryptWithSM4(unsigned char* ID, unsigned char IDlen,
|
||||
unsigned char* message, unsigned int msglen, unsigned int K1_len_bitsize, unsigned int K2_len_bitsize,
|
||||
unsigned char *C, unsigned int Cbyteslen, G2point encrypt_secretkey)
|
||||
{
|
||||
G1point C1;
|
||||
unsigned int i;
|
||||
unsigned char *K;
|
||||
unsigned char *u;
|
||||
unsigned char *C2K2;
|
||||
unsigned int c_w_id_len;
|
||||
unsigned int C2byteslen = Cbyteslen - (BIG8W_BYTESIZE * 2 + SM3OUT_32BYTES);
|
||||
unsigned int klen_bitsize = K1_len_bitsize + K2_len_bitsize;
|
||||
|
||||
K = (uint8_t *)(malloc(((klen_bitsize >> 8) + 1) * SM3OUT_32BYTES));
|
||||
u = (unsigned char *)(malloc(SM3OUT_32BYTES));
|
||||
C2K2 = (unsigned char *)(malloc(C2byteslen + (K2_len_bitsize >> 3)));
|
||||
|
||||
U8stringToG1point(C, &C1);
|
||||
|
||||
if (!SM9KeyDepackage(C1, encrypt_secretkey, ID, IDlen, (K1_len_bitsize + K2_len_bitsize), K))
|
||||
return false;
|
||||
|
||||
SM4DecryptWithEcbMode((C + BIG8W_BYTESIZE * 2 + SM3OUT_32BYTES), C2byteslen, message, msglen, K);
|
||||
|
||||
for (i = 0; i < C2byteslen; i++)
|
||||
C2K2[i] = (C + BIG8W_BYTESIZE * 2 + SM3OUT_32BYTES)[i];
|
||||
for (i = C2byteslen; i < C2byteslen + (K2_len_bitsize >> 3); i++)
|
||||
C2K2[i] = K[i - C2byteslen + (K1_len_bitsize >> 3)];
|
||||
|
||||
sm3(C2K2, C2byteslen + (K2_len_bitsize >> 3), u);
|
||||
|
||||
free(K);
|
||||
free(C2K2);
|
||||
|
||||
for (i = 0; i < SM3OUT_32BYTES; i++)
|
||||
if (u[i] != (C + BIG8W_BYTESIZE * 2)[i]){
|
||||
printf("u != C3, decrypt failed\n");
|
||||
free(u);
|
||||
return false;
|
||||
}
|
||||
|
||||
free(u);
|
||||
|
||||
return true;
|
||||
}
|
|
@ -0,0 +1,194 @@
|
|||
/*
|
||||
* Copyright (c) 2020 AIIT Ubiquitous Team
|
||||
* XiUOS is licensed under Mulan PSL v2.
|
||||
* You can use this software according to the terms and conditions of the Mulan PSL v2.
|
||||
* You may obtain a copy of Mulan PSL v2 at:
|
||||
* http://license.coscl.org.cn/MulanPSL2
|
||||
* THIS SOFTWARE IS PROVIDED ON AN "AS IS" BASIS, WITHOUT WARRANTIES OF ANY KIND,
|
||||
* EITHER EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO NON-INFRINGEMENT,
|
||||
* MERCHANTABILITY OR FIT FOR A PARTICULAR PURPOSE.
|
||||
* See the Mulan PSL v2 for more details.
|
||||
*/
|
||||
|
||||
/**
|
||||
* @file sm9_para.c
|
||||
* @brief SM9 parameters
|
||||
* @version 1.0
|
||||
* @author AIIT Ubiquitous Team
|
||||
* @date 2021-04-24
|
||||
*/
|
||||
|
||||
#include <stdint.h>
|
||||
#include <ecc.h>
|
||||
#include <qn.h>
|
||||
|
||||
//extern char *device_id;
|
||||
//extern char *platform_id;
|
||||
|
||||
G1point P1;
|
||||
G2point P2;
|
||||
//G2point sign_publickey, encrypt_secretkey;
|
||||
//G1point sign_secretkey, encrypt_publickey;
|
||||
|
||||
|
||||
const uint32_t sm9_q[BIGNUMBER_SIZE_8WORD] = {
|
||||
0xE351457D, 0xE56F9B27, 0x1A7AEEDB, 0x21F2934B,
|
||||
0xF58EC745, 0xD603AB4F, 0x02A3A6F1, 0xB6400000,
|
||||
};
|
||||
|
||||
const uint32_t sm9_N[BIGNUMBER_SIZE_8WORD] = {
|
||||
0xD69ECF25, 0xE56EE19C, 0x18EA8BEE, 0x49F2934B,
|
||||
0xF58EC744, 0xD603AB4F, 0x02A3A6F1, 0xB6400000,
|
||||
};
|
||||
|
||||
const uint32_t sm9_P1_x[BIGNUMBER_SIZE_8WORD] = {
|
||||
0x7C66DDDD, 0xE8C4E481, 0x09DC3280, 0xE1E40869,
|
||||
0x487D01D6, 0xF5ED0704, 0x62BF718F, 0x93DE051D,
|
||||
};
|
||||
|
||||
const uint32_t sm9_P1_y[BIGNUMBER_SIZE_8WORD] = {
|
||||
0x0A3EA616, 0x0C464CD7, 0xFA602435, 0x1C1C00CB,
|
||||
0x5C395BBC, 0x63106512, 0x4F21E607, 0x21FE8DDA,
|
||||
};
|
||||
|
||||
const uint32_t sm9_P2_x_high[BIGNUMBER_SIZE_8WORD] = {
|
||||
0xD8806141, 0x54806C11, 0x0F5E93C4, 0xF1DD2C19,
|
||||
0xB441A01F, 0x597B6027, 0x78640C98, 0x85AEF3D0,
|
||||
};
|
||||
|
||||
const uint32_t sm9_P2_x_low[BIGNUMBER_SIZE_8WORD] = {
|
||||
0xAF82D65B, 0xF9B7213B, 0xD19C17AB, 0xEE265948,
|
||||
0xD34EC120, 0xD2AAB97F, 0x92130B08, 0x37227552,
|
||||
};
|
||||
|
||||
const uint32_t sm9_P2_y_high[BIGNUMBER_SIZE_8WORD] = {
|
||||
0x84EBEB96, 0x856DC76B, 0xA347C8BD, 0x0736A96F,
|
||||
0x2CBEE6ED, 0x66BA0D26, 0x2E845C12, 0x17509B09,
|
||||
};
|
||||
|
||||
const uint32_t sm9_P2_y_low[BIGNUMBER_SIZE_8WORD] = {
|
||||
0xC999A7C7, 0x6215BBA5, 0xA71A0811, 0x47EFBA98,
|
||||
0x3D278FF2, 0x5F317015, 0x19BE3DA6, 0xA7CF28D5,
|
||||
};
|
||||
|
||||
const uint32_t fc1_1[BIGNUMBER_SIZE_8WORD] = {
|
||||
0xE351457C, 0xE56F9B27, 0x1A7AEEDB, 0x21F2934B,
|
||||
0xF58EC745, 0xD603AB4F, 0x02A3A6F1, 0xB6400000,
|
||||
};
|
||||
|
||||
const uint32_t fc1_2[BIGNUMBER_SIZE_8WORD] = {
|
||||
0xDA24D011, 0xF5B21FD3, 0x06DC5177, 0x9F9D4118,
|
||||
0xEE0BAF15, 0xF55ACC93, 0xDC0A3F2C, 0x6C648DE5,
|
||||
};
|
||||
|
||||
const uint32_t fc1_3[BIGNUMBER_SIZE_8WORD] = {
|
||||
0x092c756c, 0xefbd7b54, 0x139e9d63, 0x82555233,
|
||||
0x0783182f, 0xe0a8debc, 0x269967c4, 0x49db721a,
|
||||
};
|
||||
|
||||
const uint32_t fc1_4[BIGNUMBER_SIZE_8WORD] = {
|
||||
0x377b698b, 0xa91d8354, 0x0ddd04ed, 0x47c5c86e,
|
||||
0x9c086749, 0x843c6cfa, 0xe5720bdb, 0x3f23ea58,
|
||||
};
|
||||
|
||||
const uint32_t fc1_5[BIGNUMBER_SIZE_8WORD] = {
|
||||
0xabd5dbf2, 0x3c5217d3, 0x0c9de9ee, 0xda2ccadd,
|
||||
0x59865ffb, 0x51c73e55, 0x1d319b16, 0x771c15a7,
|
||||
};
|
||||
|
||||
const uint32_t fc1_6[BIGNUMBER_SIZE_8WORD] = {
|
||||
0x7be65333, 0xd5fc1196, 0x4f8b78f4, 0x78027235,
|
||||
0x02a3a6f2, 0xf3000000, 0x0, 0x0,
|
||||
};
|
||||
|
||||
const uint32_t fc1_7[BIGNUMBER_SIZE_8WORD] = {
|
||||
0x676af24a, 0x0f738991, 0xcaef75e7, 0xa9f02115,
|
||||
0xf2eb2052, 0xe303ab4f, 0x02a3a6f0, 0xb6400000,
|
||||
};
|
||||
|
||||
const uint32_t fc1_8[BIGNUMBER_SIZE_8WORD] = {
|
||||
0x7be65334, 0xd5fc1196, 0x4f8b78f4, 0x78027235,
|
||||
0x02a3a6f2, 0xf3000000, 0x0, 0x0,
|
||||
};
|
||||
|
||||
const uint32_t fc1_9[BIGNUMBER_SIZE_8WORD] = {
|
||||
0x676af249, 0x0f738991, 0xcaef75e7, 0xa9f02115,
|
||||
0xf2eb2052, 0xe303ab4f, 0x02a3a6f0, 0xb6400000,
|
||||
};
|
||||
|
||||
const uint32_t fc1_10[BIGNUMBER_SIZE_8WORD] = {
|
||||
0xa2a96686, 0x4c949c7f, 0xf8ff4c8a, 0x57d778a9,
|
||||
0x520347cc, 0x711e5f99, 0xf6983351, 0x2d40a38c,
|
||||
};
|
||||
|
||||
const uint32_t fc1_11[BIGNUMBER_SIZE_8WORD] = {
|
||||
0x40a7def7, 0x98dafea8, 0x217ba251, 0xca1b1aa1,
|
||||
0xa38b7f78, 0x64e54bb6, 0x0c0b73a0, 0x88ff5c73,
|
||||
};
|
||||
|
||||
|
||||
const uint32_t fc2_2[BIGNUMBER_SIZE_8WORD] = {
|
||||
0xE351457C, 0xE56F9B27, 0x1A7AEEDB, 0x21F2934B,
|
||||
0xF58EC745, 0xD603AB4F, 0x02A3A6F1, 0xB6400000,
|
||||
};
|
||||
|
||||
const uint32_t fc2_3[BIGNUMBER_SIZE_8WORD] = {
|
||||
0xE351457C, 0xE56F9B27, 0x1A7AEEDB, 0x21F2934B,
|
||||
0xF58EC745, 0xD603AB4F, 0x02A3A6F1, 0xB6400000,
|
||||
};
|
||||
|
||||
const uint32_t fc2_4[BIGNUMBER_SIZE_8WORD] = {
|
||||
0x7BE65334, 0xD5FC1196, 0x4F8B78F4, 0x78027235,
|
||||
0x02A3A6F2, 0xF3000000, 0x0, 0x0,
|
||||
};
|
||||
|
||||
const uint32_t fc2_5[BIGNUMBER_SIZE_8WORD] = {
|
||||
0x7BE65334, 0xD5FC1196, 0x4F8B78F4, 0x78027235,
|
||||
0x02A3A6F2, 0xF3000000, 0x0, 0x0,
|
||||
};
|
||||
|
||||
const uint32_t fc2_6[BIGNUMBER_SIZE_8WORD] = {
|
||||
0x676AF249, 0x0F738991, 0xCAEF75E7, 0xA9F02115,
|
||||
0xF2EB2052, 0xE303AB4F, 0x02A3A6F0, 0xB6400000,
|
||||
};
|
||||
|
||||
const uint32_t fc2_7[BIGNUMBER_SIZE_8WORD] = {
|
||||
0x676AF249, 0x0F738991, 0xCAEF75E7, 0xA9F02115,
|
||||
0xF2EB2052, 0xE303AB4F, 0x02A3A6F0, 0xB6400000,
|
||||
};
|
||||
|
||||
const uint32_t fc2_8[BIGNUMBER_SIZE_8WORD] = {
|
||||
0x7BE65333, 0xD5FC1196, 0x4F8B78F4, 0x78027235,
|
||||
0x02A3A6F2, 0xF3000000, 0x0, 0x0,
|
||||
};
|
||||
|
||||
const uint32_t fc2_9[BIGNUMBER_SIZE_8WORD] = {
|
||||
0x7BE65333, 0xD5FC1196, 0x4F8B78F4, 0x78027235,
|
||||
0x02A3A6F2, 0xF3000000, 0x0, 0x0,
|
||||
};
|
||||
|
||||
const uint32_t fc2_10[BIGNUMBER_SIZE_8WORD] = {
|
||||
0x676AF24A, 0x0F738991, 0xCAEF75E7, 0xA9F02115,
|
||||
0xF2EB2052, 0xE303AB4F, 0x02A3A6F0, 0xB6400000,
|
||||
};
|
||||
|
||||
const uint32_t fc2_11[BIGNUMBER_SIZE_8WORD] = {
|
||||
0x676AF24A, 0x0F738991, 0xCAEF75E7, 0xA9F02115,
|
||||
0xF2EB2052, 0xE303AB4F, 0x02A3A6F0, 0xB6400000,
|
||||
};
|
||||
|
||||
const uint32_t sm9_qnr[BIGNUMBER_SIZE_8WORD] = {
|
||||
0xf1a8a2be, 0xf2b7cd93, 0x8d3d776d, 0x90f949a5,
|
||||
0xfac763a2, 0xeb01d5a7, 0x0151d378, 0x5b200000,
|
||||
};
|
||||
|
||||
const uint32_t sm9_q_2k[BIGNUMBER_SIZE_8WORD] = {
|
||||
0xb417e2d2, 0x27dea312, 0xae1a5d3f, 0x88f8105f,
|
||||
0xd6706e7b, 0xe479b522, 0x56f62fbd, 0x2ea795a6,
|
||||
};
|
||||
|
||||
const uint32_t sm9_N_2k[BIGNUMBER_SIZE_8WORD] = {
|
||||
0xcd750c35, 0x7598cd79, 0xbb6daeab, 0xe4a08110,
|
||||
0x7d78a1f9, 0xbfee4bae, 0x63695d0e, 0x8894f5d1,
|
||||
};
|
||||
|
|
@ -0,0 +1,382 @@
|
|||
/*
|
||||
* Copyright (c) 2020 AIIT Ubiquitous Team
|
||||
* XiUOS is licensed under Mulan PSL v2.
|
||||
* You can use this software according to the terms and conditions of the Mulan PSL v2.
|
||||
* You may obtain a copy of Mulan PSL v2 at:
|
||||
* http://license.coscl.org.cn/MulanPSL2
|
||||
* THIS SOFTWARE IS PROVIDED ON AN "AS IS" BASIS, WITHOUT WARRANTIES OF ANY KIND,
|
||||
* EITHER EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO NON-INFRINGEMENT,
|
||||
* MERCHANTABILITY OR FIT FOR A PARTICULAR PURPOSE.
|
||||
* See the Mulan PSL v2 for more details.
|
||||
*/
|
||||
|
||||
/**
|
||||
* @file sm9_util.c
|
||||
* @brief the function called by SM9 function, including hash, KDF, produce random number, encrypt and decrypt algorithm, BiLinearPairing
|
||||
* @version 1.0
|
||||
* @author AIIT Ubiquitous Team
|
||||
* @date 2021-04-24
|
||||
*/
|
||||
|
||||
#include <sm9_util.h>
|
||||
#include <sm4.h>
|
||||
|
||||
/**
|
||||
*
|
||||
* @brief generate random bytes
|
||||
*
|
||||
* @param null
|
||||
*
|
||||
* @return uint8_t
|
||||
*
|
||||
*/
|
||||
uint8_t hw_get_random_byte(void)
|
||||
{
|
||||
static uint32_t lcg_state;
|
||||
static uint32_t nb_soft = 9876543;
|
||||
#define MAX_SOFT_RNG 1024
|
||||
static const uint32_t a = 1664525;
|
||||
static const uint32_t c = 1013904223;
|
||||
|
||||
nb_soft = (nb_soft + 1) % MAX_SOFT_RNG;
|
||||
lcg_state = (a * lcg_state + c);
|
||||
return (uint8_t) (lcg_state >> 24);
|
||||
}
|
||||
/**
|
||||
*
|
||||
* @brief generate random bytes stream
|
||||
*
|
||||
* @param buf buffer to store the random bytes
|
||||
* @param blen buffer length
|
||||
*
|
||||
* @return 1 if produce random bytes stream; 0 if buffer is null
|
||||
*/
|
||||
int crypto_rng_read(uint8_t *buf, size_t blen)
|
||||
{
|
||||
uint8_t *b = buf;
|
||||
size_t n;
|
||||
|
||||
if (!b)
|
||||
return -1;
|
||||
|
||||
for (n = 0; n < blen; n++)
|
||||
b[n] = hw_get_random_byte();
|
||||
|
||||
return 1;
|
||||
}
|
||||
/**
|
||||
*
|
||||
* @brief generate random big number based on crypto_rng_read, bad prng version , only for test.
|
||||
* TODO: replace next version
|
||||
*
|
||||
* @param null
|
||||
*
|
||||
* @return ret, big number r
|
||||
*
|
||||
*/
|
||||
big8w RandomNumGenerate()
|
||||
{
|
||||
char i = 0, j = 0;
|
||||
unsigned char random_byte[4];
|
||||
big8w ret;
|
||||
|
||||
memset(ret.word, 0x00, BIG8W_BYTESIZE);
|
||||
|
||||
for (i = 0; i < BIGNUMBER_SIZE_8WORD; i++){
|
||||
for (j = 0; j < 4; j++)
|
||||
random_byte[j] = hw_get_random_byte();
|
||||
ret.word[i] = GETU32(random_byte);
|
||||
}
|
||||
|
||||
if (Big8wBigThan(&ret, &curve.N))
|
||||
ret = Big8wMinusMod(ret, curve.N, curve.N);
|
||||
|
||||
return ret;
|
||||
}
|
||||
/**
|
||||
*
|
||||
* @brief HashTwice = Hash(funcflag||g1||(Hash(g2||g3||ID_A||ID_B||RA||RB)))
|
||||
* t1 = (g2||g3||ID_A||ID_B||RA||RB), t2 = (funcflag||g1||hashvalue)
|
||||
*
|
||||
* @param ID_A id of challenger
|
||||
* @param ID_A_len length of ID_A, byte size
|
||||
* @param ID_B id of responser
|
||||
* @param ID_B_len length of ID_B, byte size
|
||||
* @param RA a pointer of a point in group G1
|
||||
* @param RB a pointer of a point in group G1
|
||||
* @param g1 a pointer of a number in Fq12
|
||||
* @param g2 a pointer of a number in Fq12
|
||||
* @param g3 a pointer of a number in Fq12
|
||||
* @param funcflag defined in SM9, funcflag = 0x82 or 0x83
|
||||
* @param ret unsigned char string, store the result
|
||||
*
|
||||
* @result ret
|
||||
*
|
||||
*/
|
||||
void HashTwice(uint8_t* ID_A, uint8_t ID_A_len, uint8_t* ID_B, uint8_t ID_B_len,
|
||||
G1point* RA, G1point* RB,
|
||||
q12* g1, q12* g2, q12* g3, uint8_t funcflag, uint8_t* ret)
|
||||
{
|
||||
uint8_t* t1, *t2;
|
||||
uint32_t i, temp, msglen;
|
||||
|
||||
t1 = (uint8_t*)(malloc(ID_A_len + ID_B_len + BIG8W_BYTESIZE * 12 * 2 + BIG8W_BYTESIZE * 2 * 2));
|
||||
t2 = (uint8_t*)(malloc(1 + BIG8W_BYTESIZE * 12 + SM3OUT_32BYTES));
|
||||
|
||||
i = 0;
|
||||
Q12Intou8string(g2, t1, i);
|
||||
i += BIG8W_BYTESIZE * 12;
|
||||
Q12Intou8string(g3, t1, i);
|
||||
i += BIG8W_BYTESIZE * 12;
|
||||
|
||||
for (temp = 0; temp < ID_A_len; temp++)
|
||||
t1[i + temp] = ID_A[temp];
|
||||
|
||||
i += temp;
|
||||
|
||||
for (temp = 0; temp < ID_B_len; temp++)
|
||||
t1[i + temp] = ID_B[temp];
|
||||
i += temp;
|
||||
|
||||
Big8wIntou8string(&RA->x, t1, i); // join RA and t1
|
||||
i += BIG8W_BYTESIZE;
|
||||
|
||||
Big8wIntou8string(&RA->y, t1, i);
|
||||
i += BIG8W_BYTESIZE;
|
||||
|
||||
Big8wIntou8string(&RB->x, t1, i); // join RB and t1
|
||||
i += BIG8W_BYTESIZE;
|
||||
|
||||
Big8wIntou8string(&RB->y, t1, i);
|
||||
i += BIG8W_BYTESIZE;
|
||||
msglen = i;
|
||||
|
||||
t2[0] = funcflag;
|
||||
i = 1;
|
||||
|
||||
Q12Intou8string(g1, t2, i);
|
||||
i += BIG8W_BYTESIZE * 12;
|
||||
|
||||
sm3(t1, msglen, t2 + i);
|
||||
sm3(t2, 1 + BIG8W_BYTESIZE * 12 + SM3OUT_32BYTES, ret);
|
||||
|
||||
free(t1);
|
||||
free(t2);
|
||||
}
|
||||
/**
|
||||
* @brief judge if elements in string are zero
|
||||
*
|
||||
* @param string unsigned char string to be checked
|
||||
* @param stringlen length of string
|
||||
*
|
||||
* @return true if all elements in string is zero; else false
|
||||
*
|
||||
*/
|
||||
bool StringEqualZero(uint8_t* string, uint32_t stringlen)
|
||||
{
|
||||
uint32_t length = 0;
|
||||
|
||||
while (length < stringlen)
|
||||
if (string[length++])
|
||||
return false;
|
||||
|
||||
return true;
|
||||
}
|
||||
/**
|
||||
*
|
||||
* @brief defined in SM9:H(Z, n); n = curve.N, 255 bits, hlen = 2(therefore temp[i] = 0x01, 0x02)
|
||||
*
|
||||
* @param Z unsigned char string
|
||||
* @param Zlen length of Z
|
||||
* @param funcflag defined in SM9, funcflag = 0x01 or 0x02; H1() or H2()
|
||||
*
|
||||
* @return ret big number
|
||||
*
|
||||
*/
|
||||
big8w H(uint8_t* Z, uint32_t Zlen, uint8_t funcflag)
|
||||
{
|
||||
uint8_t* temp;
|
||||
uint8_t Ha[40];
|
||||
uint8_t Ha2[32];
|
||||
uint32_t ctr = 0x01, i = 0;
|
||||
uint32_t datalen;
|
||||
big8w tmp = curve.N;
|
||||
big16w ret;
|
||||
|
||||
tmp.word[0] -= 1; // tmp = curve.N - 1
|
||||
|
||||
datalen = 1 + Zlen + 4;
|
||||
temp = (uint8_t *)malloc(datalen);
|
||||
memset(temp, 0x00, datalen);
|
||||
memset(ret.word, 0x00, BIG8W_BYTESIZE * 2);
|
||||
|
||||
temp[0] = funcflag; // temp = funcfalg||Z||ctr
|
||||
|
||||
for (i = 0; i < Zlen; i++)
|
||||
temp[i + 1] = Z[i];
|
||||
|
||||
temp[++i] = 0;
|
||||
temp[++i] = 0;
|
||||
temp[++i] = 0;
|
||||
|
||||
temp[++i] = 0x01;
|
||||
sm3(temp, datalen, Ha);
|
||||
|
||||
temp[i] = 0x02;
|
||||
sm3(temp, datalen, Ha2);
|
||||
free(temp);
|
||||
|
||||
for (i = 32; i < 40; i++)
|
||||
Ha[i] = Ha2[i - 32];
|
||||
|
||||
for (i = 0; i < 10; i++)
|
||||
ret.word[9 - i] = GETU32(Ha + i * 4);
|
||||
|
||||
while (ret.word[i] == 0)
|
||||
i--;
|
||||
ret.length = i;
|
||||
|
||||
tmp = Big16wmod8w(ret, tmp); // tmp = Ha mod (N-1)
|
||||
|
||||
i = 0; // tmp += 1
|
||||
while (tmp.word[0] == 0xffffffff) // if overflow after plus one
|
||||
i++;
|
||||
tmp.word[i]++;
|
||||
if (i) while (i) { // if overflow
|
||||
i--;
|
||||
tmp.word[i] = 0;
|
||||
}
|
||||
|
||||
return tmp;
|
||||
}
|
||||
/**
|
||||
*
|
||||
* @brief key derive function defined in SM9, baseed of hash function(SM3).
|
||||
*
|
||||
* @param Z unsigned char string
|
||||
* @param Zlen length of Z
|
||||
* @param klen length of key to be derived, bitsize!!!
|
||||
* @param ret unsigned char string to store the key derived.
|
||||
*
|
||||
* @result ret
|
||||
*
|
||||
*/
|
||||
void KDF(uint8_t* Z, uint32_t Zlen, uint32_t klen, uint8_t* ret)
|
||||
{
|
||||
uint8_t* tmp, Ha[32];
|
||||
uint32_t i, round;
|
||||
uint32_t ctr = 0x00000001;
|
||||
|
||||
round = klen >> 8;
|
||||
if (klen & 0xff)
|
||||
round++;
|
||||
|
||||
tmp = (uint8_t*)(malloc(Zlen + sizeof(uint32_t))); // tmp = Z||ctr
|
||||
|
||||
for (i = 0; i < Zlen; i++)
|
||||
tmp[i] = Z[i];
|
||||
|
||||
for (ctr = 1; ctr <= round; ctr++) {
|
||||
tmp[i] = (ctr >> 24) & 0xff;
|
||||
tmp[i+1] = (ctr >> 16) & 0xff;
|
||||
tmp[i+2] = (ctr >> 8) & 0xff;
|
||||
tmp[i+3] = ctr & 0xff;
|
||||
sm3(tmp, Zlen + sizeof(uint32_t), ret + 32 * (ctr - 1));
|
||||
}
|
||||
}
|
||||
/**
|
||||
* @brief SM4 Encrypt Function With ecb mode
|
||||
*
|
||||
* @param message data to be encrypted
|
||||
* @param msglen length of message, byte size
|
||||
* @param key key of SM4 algorithm
|
||||
* @param ciphertext unsigned char string to store the encrypted message
|
||||
*
|
||||
* @result ciphertext
|
||||
*
|
||||
*/
|
||||
void SM4EncryptWithEcbMode(uint8_t* message, uint32_t msglen, uint8_t* key, uint8_t* ciphertext)
|
||||
{
|
||||
sms4_key_t renckey;
|
||||
uint32_t ciphertextlen;
|
||||
sms4_set_encrypt_key(&renckey, key);
|
||||
Sms4EcbEncryptPkcs7Padding(message, msglen, ciphertext, &ciphertextlen, &renckey);
|
||||
}
|
||||
/**
|
||||
* @brief SM4 Decrypt Function
|
||||
*
|
||||
* @param ciphertext encrypted message to be decrypted
|
||||
* @param ciphertextlen length of ciphertext, % 128 == 0
|
||||
* @param message unsigned char string to store decrypted data
|
||||
* @param msglen length of message
|
||||
* @param key key of SM4 algorithm
|
||||
*
|
||||
* @result message
|
||||
*
|
||||
*/
|
||||
void SM4DecryptWithEcbMode(uint8_t* ciphertext, uint32_t ciphertextlen, uint8_t* message, int msglen, uint8_t* key)
|
||||
{
|
||||
uint32_t i;
|
||||
|
||||
sms4_key_t rdeckey;
|
||||
sms4_set_decrypt_key(&rdeckey, key);
|
||||
Sms4EcbDecryptPkcs7Padding(ciphertext, ciphertextlen, message, &msglen, &rdeckey);
|
||||
}
|
||||
/**
|
||||
* @brief function defined in SM9, e(P, Q)
|
||||
*
|
||||
* @param P a point in group G1
|
||||
* @param Q a point in group G2
|
||||
*
|
||||
* @return a number in Fq12
|
||||
*
|
||||
*/
|
||||
q12 BiLinearPairing(G1point P, G2point Q)
|
||||
{
|
||||
bool flag;
|
||||
uint32_t elem = 0x215d93e, i; // a = 6*t+2 = 0x2400000000215d93e, used in Miller round
|
||||
int bitindex = 25; // index of elem's hightest bit
|
||||
G2point T = Q, Q1, Q2;
|
||||
q12 f;
|
||||
|
||||
// Miller round
|
||||
Q12Zero(&f);
|
||||
f.low.low.low.word[0] = 1;
|
||||
|
||||
f = Q12MultMod(f, f); // 0
|
||||
Line(P, &T, T, 1, &f);
|
||||
|
||||
f = Q12MultMod(f, f); // 0
|
||||
Line(P, &T, T, 1, &f);
|
||||
|
||||
f = Q12MultMod(f, f); // 1
|
||||
Line(P, &T, T, 1, &f);
|
||||
Line(P, &T, Q, 0, &f);
|
||||
|
||||
for (i = 0; i < 36; i++) { // 36 continuous 0
|
||||
f = Q12MultMod(f, f);
|
||||
Line(P, &T, T, 1, &f);
|
||||
}
|
||||
|
||||
for (; bitindex >= 0; bitindex--) { // scan 0x215d93e
|
||||
flag = (elem >> bitindex) & 1;
|
||||
f = Q12MultMod(f, f);
|
||||
Line(P, &T, T, 1, &f);
|
||||
if (flag)
|
||||
Line(P, &T, Q, 0, &f);
|
||||
}
|
||||
|
||||
// Frobenius of Q
|
||||
G2pointFrobenius(Q, &Q1, 1);
|
||||
G2pointFrobenius(Q, &Q2, 2);
|
||||
|
||||
Line(P, &T, Q1, 0, &f);
|
||||
|
||||
Q2.y.high = Big8wMinusMod(curve.q, Q2.y.high, curve.q);
|
||||
Q2.y.low = Big8wMinusMod(curve.q, Q2.y.low, curve.q);
|
||||
Line(P, &T, Q2, 0, &f);
|
||||
|
||||
LastPower(&f);
|
||||
|
||||
return f;
|
||||
}
|
|
@ -0,0 +1,53 @@
|
|||
/*
|
||||
* Copyright (c) 2020 AIIT Ubiquitous Team
|
||||
* XiUOS is licensed under Mulan PSL v2.
|
||||
* You can use this software according to the terms and conditions of the Mulan PSL v2.
|
||||
* You may obtain a copy of Mulan PSL v2 at:
|
||||
* http://license.coscl.org.cn/MulanPSL2
|
||||
* THIS SOFTWARE IS PROVIDED ON AN "AS IS" BASIS, WITHOUT WARRANTIES OF ANY KIND,
|
||||
* EITHER EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO NON-INFRINGEMENT,
|
||||
* MERCHANTABILITY OR FIT FOR A PARTICULAR PURPOSE.
|
||||
* See the Mulan PSL v2 for more details.
|
||||
*/
|
||||
|
||||
/**
|
||||
* @file sm3_test.c
|
||||
* @brief tests of SM3
|
||||
* @version 1.0
|
||||
* @author AIIT Ubiquitous Team
|
||||
* @date 2021-04-24
|
||||
*/
|
||||
|
||||
#include <sm3.h>
|
||||
#include <xiuos.h>
|
||||
|
||||
void sm3_test_case(){
|
||||
uint8_t result[SM3_DIGEST_LENGTH] = { 0 };
|
||||
//test case 1
|
||||
KPrintf("\n#################### sm3 test ##########################\n");
|
||||
char *msg = "abc";
|
||||
KPrintf("\n####sm3 test case 1:\n");
|
||||
KPrintf( "%-15s %s\n", "digest message1:",msg);
|
||||
sm3(msg,3,result);
|
||||
KPrintf("%-15s ","digest result1: ");
|
||||
for ( int i = 0 ; i < SM3_DIGEST_LENGTH ; i++){
|
||||
KPrintf("%02x",result[i]);
|
||||
}
|
||||
KPrintf("\n");
|
||||
//test case 2
|
||||
KPrintf("\n####sm3 test case 2:\n");
|
||||
//msg = "abcdabcdabcdabcdabcdabcdabcdabcdabcdabcdabcdabcdabcdabcdabcdabcd"
|
||||
char msg1[64] = { 0x61, 0x62, 0x63, 0x64 ,0x61, 0x62, 0x63, 0x64 ,0x61, 0x62, 0x63, 0x64 ,0x61, 0x62, 0x63, 0x64 ,0x61, 0x62, 0x63, 0x64 ,0x61, 0x62, 0x63, 0x64 ,0x61, 0x62, 0x63, 0x64 ,0x61, 0x62, 0x63, 0x64 ,0x61, 0x62, 0x63, 0x64 ,0x61, 0x62, 0x63, 0x64 ,0x61, 0x62, 0x63, 0x64 ,0x61, 0x62, 0x63, 0x64 ,0x61, 0x62, 0x63, 0x64 ,0x61, 0x62, 0x63, 0x64 ,0x61, 0x62, 0x63, 0x64 ,0x61, 0x62, 0x63, 0x64 };
|
||||
KPrintf("digest message2: ");
|
||||
for ( int i = 0 ; i < 64 ; i++){
|
||||
KPrintf("%02x",msg1[i]);
|
||||
}
|
||||
KPrintf("\n");
|
||||
sm3(msg1, 64,result);
|
||||
KPrintf("digest result2: ");
|
||||
for ( int i = 0 ; i < SM3_DIGEST_LENGTH ; i++){
|
||||
KPrintf("%02x",result[i]);
|
||||
}
|
||||
KPrintf("\n");
|
||||
KPrintf("\n########################################################\n");
|
||||
}
|
|
@ -0,0 +1,93 @@
|
|||
/*
|
||||
* Copyright (c) 2020 AIIT Ubiquitous Team
|
||||
* XiUOS is licensed under Mulan PSL v2.
|
||||
* You can use this software according to the terms and conditions of the Mulan PSL v2.
|
||||
* You may obtain a copy of Mulan PSL v2 at:
|
||||
* http://license.coscl.org.cn/MulanPSL2
|
||||
* THIS SOFTWARE IS PROVIDED ON AN "AS IS" BASIS, WITHOUT WARRANTIES OF ANY KIND,
|
||||
* EITHER EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO NON-INFRINGEMENT,
|
||||
* MERCHANTABILITY OR FIT FOR A PARTICULAR PURPOSE.
|
||||
* See the Mulan PSL v2 for more details.
|
||||
*/
|
||||
|
||||
/**
|
||||
* @file sm4_test.c
|
||||
* @brief test for SM4
|
||||
* @version 1.0
|
||||
* @author AIIT Ubiquitous Team
|
||||
* @date 2021-04-24
|
||||
*/
|
||||
|
||||
#include <sm4.h>
|
||||
#include <xiuos.h>
|
||||
|
||||
void sm4_test_case(){
|
||||
unsigned char ukey[16] = { 0x01, 0x23, 0x45, 0x67, 0x89, 0xab, 0xcd, 0xef, 0xfe ,0xdc, 0xba, 0x98, 0x76, 0x54, 0x32, 0x10 };
|
||||
unsigned char input[16] = { 0x01, 0x23, 0x45, 0x67, 0x89, 0xab, 0xcd, 0xef, 0xfe ,0xdc, 0xba, 0x98, 0x76, 0x54, 0x32, 0x10 };
|
||||
uint8_t res[16] = {0} ;
|
||||
uint8_t plaintext[16] = {1};
|
||||
uint8_t ciphertext[16] = {2};
|
||||
int olen = 0;
|
||||
sms4_key_t key;
|
||||
|
||||
//test case 1
|
||||
KPrintf("\n#################### sm4 test ##########################\n");
|
||||
KPrintf("\n####sm4 test case1:\n");
|
||||
KPrintf("plaintext: ");
|
||||
for (int i = 0; i< 16; i++){
|
||||
KPrintf("%02x ",input[i]);
|
||||
}
|
||||
KPrintf("\n");
|
||||
KPrintf("key: ");
|
||||
for (int i = 0; i< 16; i++){
|
||||
KPrintf("%02x",ukey[i]);
|
||||
}
|
||||
KPrintf("\n");
|
||||
|
||||
KPrintf("encryption:\n");
|
||||
sms4_set_encrypt_key(&key, ukey);
|
||||
Sms4EcbEncryptNoPadding(input,16,res,&olen,&key);
|
||||
KPrintf("ciphertext: ");
|
||||
for (int i = 0; i< 16; i++){
|
||||
KPrintf("%02x",res[i]);
|
||||
}
|
||||
KPrintf("\n");
|
||||
KPrintf("decryption:\n");
|
||||
sms4_set_decrypt_key(&key, ukey);
|
||||
KPrintf("round key in sms4_set_decrypt_key:\n");
|
||||
for (int i = 0; i < 32; i++){
|
||||
KPrintf("rk%d:%08x\n", i, key.rk[i]);
|
||||
}
|
||||
Sms4EcbDecryptNoPadding(res,16,res,&olen,&key);
|
||||
printf("plaintext: ");
|
||||
for (int i = 0; i< 16; i++){
|
||||
KPrintf("%02x",res[i]);
|
||||
}
|
||||
printf("\n");
|
||||
|
||||
////test case 2
|
||||
KPrintf("\n####sm4 test case2:\n");
|
||||
KPrintf("plaintext: ");
|
||||
for (int i = 0; i< 16; i++){
|
||||
KPrintf("%02x",input[i]);
|
||||
}
|
||||
KPrintf("\n");
|
||||
KPrintf("key: ");
|
||||
for (int i = 0; i< 16; i++){
|
||||
KPrintf("%02x",ukey[i]);
|
||||
}
|
||||
KPrintf("\n");
|
||||
KPrintf("encrypt 1000000 times:\n");
|
||||
sms4_set_encrypt_key(&key, ukey);
|
||||
memcpy(plaintext, input, 16);
|
||||
for (int i = 0;i< 1000000; i++){
|
||||
Sms4EcbEncryptNoPadding(plaintext,16,ciphertext,&olen,&key);
|
||||
memcpy(plaintext, ciphertext, 16);
|
||||
}
|
||||
KPrintf("ciphertext: ");
|
||||
for (int i = 0; i< 16; i++){
|
||||
KPrintf("%02x",ciphertext[i]);
|
||||
}
|
||||
KPrintf("\n");
|
||||
KPrintf("\n########################################################\n");
|
||||
}
|
|
@ -0,0 +1,875 @@
|
|||
/*
|
||||
* Copyright (c) 2020 AIIT Ubiquitous Team
|
||||
* XiUOS is licensed under Mulan PSL v2.
|
||||
* You can use this software according to the terms and conditions of the Mulan PSL v2.
|
||||
* You may obtain a copy of Mulan PSL v2 at:
|
||||
* http://license.coscl.org.cn/MulanPSL2
|
||||
* THIS SOFTWARE IS PROVIDED ON AN "AS IS" BASIS, WITHOUT WARRANTIES OF ANY KIND,
|
||||
* EITHER EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO NON-INFRINGEMENT,
|
||||
* MERCHANTABILITY OR FIT FOR A PARTICULAR PURPOSE.
|
||||
* See the Mulan PSL v2 for more details.
|
||||
*/
|
||||
|
||||
/**
|
||||
* @file sm9_test.c
|
||||
* @brief tests of SM9
|
||||
* @version 1.0
|
||||
* @author AIIT Ubiquitous Team
|
||||
* @date 2021-04-24
|
||||
*/
|
||||
|
||||
#include <sm9_test.h>
|
||||
|
||||
/**
|
||||
* @brief test of sign and signature verify, data comes from SM9
|
||||
*
|
||||
*/
|
||||
void SignAndVerifyTest()
|
||||
{
|
||||
uint8_t ID_Alice[] = "Alice";
|
||||
uint8_t message[] = "Chinese IBS standard";
|
||||
uint8_t hid = 0x01, msglen = strlen((char*)message);
|
||||
uint8_t *Id_Alice_hid, *msg_w;
|
||||
|
||||
big8w ks, t1, t2, r, h, h1, h2;
|
||||
G1point dsA;
|
||||
G2point Ppub_s, P;
|
||||
q12 t, g, w, u;
|
||||
|
||||
Signature sig;
|
||||
|
||||
//clock_t start, end, end_start;
|
||||
|
||||
Id_Alice_hid = (unsigned char*)(malloc(5 + 1));
|
||||
|
||||
ks.word[0] = 0x1F2DC5F4;
|
||||
ks.word[1] = 0x348A1D5B;
|
||||
ks.word[2] = 0x340F319F;
|
||||
ks.word[3] = 0x80CE0B66;
|
||||
ks.word[4] = 0x87E02CF4;
|
||||
ks.word[5] = 0x45CB54C5;
|
||||
ks.word[6] = 0x8459D785;
|
||||
ks.word[7] = 0x000130E7;
|
||||
|
||||
r.word[0] = 0xDC4B1CBE;
|
||||
r.word[1] = 0xED648835;
|
||||
r.word[2] = 0xC662337A;
|
||||
r.word[3] = 0x2ED15975;
|
||||
r.word[4] = 0xD0096502;
|
||||
r.word[5] = 0x813203DF;
|
||||
r.word[6] = 0x16B06704;
|
||||
r.word[7] = 0x033C86;
|
||||
|
||||
SM9Init();
|
||||
|
||||
KPrintf("------------------------------below is ks---------------------------------\n");
|
||||
Big8wPrint(&ks);
|
||||
|
||||
Ppub_s = G2PointMult(ks, P2);
|
||||
KPrintf("------------------------------below is Ppub_s-----------------------------\n");
|
||||
Big8wPrint(&Ppub_s.x.high);
|
||||
Big8wPrint(&Ppub_s.x.low);
|
||||
Big8wPrint(&Ppub_s.y.high);
|
||||
Big8wPrint(&Ppub_s.y.low);
|
||||
|
||||
JoinIDhid(ID_Alice, 5, hid, Id_Alice_hid);
|
||||
|
||||
t1 = Big8wAddMod(H(Id_Alice_hid, 5 + 1, 0x01), ks, curve.N);
|
||||
KPrintf("------------------------------below is t1---------------------------------\n");
|
||||
Big8wPrint(&t1);
|
||||
|
||||
t2 = Big8wMultMod(ks, Big8wReverse(t1, curve.N), curve.N);
|
||||
KPrintf("------------------------------below is t2---------------------------------\n");
|
||||
Big8wPrint(&t2);
|
||||
|
||||
dsA = G1pointMult(t2, P1);
|
||||
KPrintf("------------------------------below is dsA--------------------------------\n");
|
||||
Big8wPrint(&dsA.x);
|
||||
Big8wPrint(&dsA.y);
|
||||
|
||||
g = BiLinearPairing(P1, Ppub_s);
|
||||
KPrintf("------------------------below is bilineapairing---------------------------\n");
|
||||
Q12Print(&g);
|
||||
|
||||
w = Q12PowerMod(g, r);
|
||||
KPrintf("------------------------------below is w----------------------------------\n");
|
||||
Q12Print(&w);
|
||||
|
||||
msg_w = (uint8_t*)(malloc(msglen + BIG8W_BYTESIZE * 12));
|
||||
JoinMsgW(message, msglen, &w, msg_w);
|
||||
h = H(msg_w, msglen + BIG8W_BYTESIZE * 12, 0x02);
|
||||
KPrintf("------------------------------below is h----------------------------------\n");
|
||||
Big8wPrint(&h);
|
||||
|
||||
big8w L = Big8wMinusMod(r, h, curve.N);
|
||||
KPrintf("------------------------------below is L----------------------------------\n");
|
||||
Big8wPrint(&L);
|
||||
|
||||
G1point S = G1pointMult(L, dsA);
|
||||
KPrintf("------------------------------below is S----------------------------------\n");
|
||||
Big8wPrint(&S.x);
|
||||
Big8wPrint(&S.y);
|
||||
KPrintf("\n");
|
||||
|
||||
// verify the signature
|
||||
g = BiLinearPairing(P1, Ppub_s);
|
||||
KPrintf("------------------------below is bilineapairing---------------------------\n");
|
||||
Q12Print(&g);
|
||||
|
||||
t = Q12PowerMod(g, h);
|
||||
KPrintf("-----------------------------below is t-----------------------------------\n");
|
||||
Q12Print(&t);
|
||||
|
||||
h1 = H(Id_Alice_hid, 5 + 1, 0x01);
|
||||
KPrintf("-----------------------------below is h1----------------------------------\n");
|
||||
Big8wPrint(&h1);
|
||||
|
||||
P = G2PointAdd(Ppub_s, G2PointMult(h1, P2));
|
||||
KPrintf("------------------------------below is P----------------------------------\n");
|
||||
G2pointPrint(&P);
|
||||
|
||||
u = BiLinearPairing(S, P);
|
||||
KPrintf("------------------------------below is u----------------------------------\n");
|
||||
Q12Print(&u);
|
||||
|
||||
w = Q12MultMod(u, t);
|
||||
KPrintf("------------------------------below is w----------------------------------\n");
|
||||
Q12Print(&w);
|
||||
|
||||
h2 = H(msg_w, msglen + BIG8W_BYTESIZE * 12, 0x02);
|
||||
KPrintf("------------------------------below is h2---------------------------------\n");
|
||||
Big8wPrint(&h2);
|
||||
KPrintf("------------------------------below is h----------------------------------\n");
|
||||
Big8wPrint(&h);
|
||||
|
||||
if (Big8wEqual(&h2, &h))
|
||||
KPrintf("\nh2 = h, test verify success!\n");
|
||||
|
||||
sig = SM9Sign(message, msglen, dsA, Ppub_s);
|
||||
if (SM9VerifySignature(ID_Alice, 5, hid, message, msglen, sig, Ppub_s))
|
||||
KPrintf("SM9 Sign and VerifySignature API run success!\n");
|
||||
|
||||
|
||||
/*
|
||||
start = clock();
|
||||
Ppub_s = G2PointMult(ks, P2);
|
||||
|
||||
t1 = Big8wAddMod(H(Id_Alice_hid, 5 + 1, 0x01), ks, curve.N);
|
||||
|
||||
t2 = Big8wMultMod(ks, Big8wReverse(t1, curve.N), curve.N);
|
||||
|
||||
dsA = G1pointMult(t2, P1);
|
||||
|
||||
g = BiLinearPairing(P1, Ppub_s);
|
||||
w = Q12PowerMod(g, r);
|
||||
|
||||
JoinMsgW(message, msglen, &w, msg_w);
|
||||
h = H(msg_w, msglen + BIG8W_BYTESIZE * k, 0x02);
|
||||
|
||||
L = Big8wMinusMod(r, h, curve.N);
|
||||
|
||||
S = G1pointMult(L, dsA);
|
||||
|
||||
end = clock();
|
||||
end_start = end - start;
|
||||
KPrintf("\n");
|
||||
KPrintf("runtime of sign in: %d ms\n", end_start);
|
||||
*/
|
||||
|
||||
free(Id_Alice_hid);
|
||||
free(msg_w);
|
||||
|
||||
}
|
||||
/**
|
||||
* @brief test Key exchange, data comes from SM9
|
||||
*
|
||||
*/
|
||||
void SM9KeyExchangeTest()
|
||||
{
|
||||
uint8_t ID_Alice[] = "Alice", ID_Bob[] = "Bob";
|
||||
uint8_t hid = 0x02;
|
||||
uint8_t Id_Alice_hid[5+1], ID_Bob_hid[3+1], message[100];
|
||||
|
||||
uint32_t klen = 0x80, i;
|
||||
|
||||
big8w ke, t1, t2, t3, t4, h1, rA, rB;
|
||||
G1point Ppub_e, RA, RB, QA, QB;
|
||||
G2point deA, deB;
|
||||
q12 g1, g2, g3;
|
||||
|
||||
uint8_t *strA, *strB, *SKA, *SKB, *SA, *SB, *S1, *S2;
|
||||
strA = (uint8_t*)(malloc(5 + 3 + BIG8W_BYTESIZE * 2 * 2 + BIG8W_BYTESIZE * 12 * 3));
|
||||
strB = (uint8_t*)(malloc(5 + 3 + BIG8W_BYTESIZE * 2 * 2 + BIG8W_BYTESIZE * 12 * 3));
|
||||
SKA = (uint8_t*)(malloc(klen));
|
||||
SKB = (uint8_t*)(malloc(klen));
|
||||
SA = (uint8_t*)(malloc(256/8));
|
||||
SB = (uint8_t*)(malloc(256/8));
|
||||
S1 = (uint8_t*)(malloc(256/8));
|
||||
S2 = (uint8_t*)(malloc(256/8));
|
||||
|
||||
memset(message, 0x00, 100);
|
||||
|
||||
ke.word[7] = 0x02E65B;
|
||||
ke.word[6] = 0x0762D042;
|
||||
ke.word[5] = 0xF51F0D23;
|
||||
ke.word[4] = 0x542B13ED;
|
||||
ke.word[3] = 0x8CFA2E9A;
|
||||
ke.word[2] = 0x0E720636;
|
||||
ke.word[1] = 0x1E013A28;
|
||||
ke.word[0] = 0x3905E31F;
|
||||
|
||||
rA.word[7] = 0x5879;
|
||||
rA.word[6] = 0xDD1D51E1;
|
||||
rA.word[5] = 0x75946F23;
|
||||
rA.word[4] = 0xB1B41E93;
|
||||
rA.word[3] = 0xBA31C584;
|
||||
rA.word[2] = 0xAE59A426;
|
||||
rA.word[1] = 0xEC1046A4;
|
||||
rA.word[0] = 0xD03B06C8;
|
||||
|
||||
rB.word[7] = 0x018B98;
|
||||
rB.word[6] = 0xC44BEF9F;
|
||||
rB.word[5] = 0x8537FB7D;
|
||||
rB.word[4] = 0x071B2C92;
|
||||
rB.word[3] = 0x8B3BC65B;
|
||||
rB.word[2] = 0xD3D69E1E;
|
||||
rB.word[1] = 0xEE213564;
|
||||
rB.word[0] = 0x905634FE;
|
||||
|
||||
SM9Init();
|
||||
|
||||
Ppub_e = G1pointMult(ke, P1);
|
||||
KPrintf("------------------------------below is Ppub_e-----------------------------\n");
|
||||
Big8wPrint(&Ppub_e.x);
|
||||
Big8wPrint(&Ppub_e.y);
|
||||
|
||||
JoinIDhid(ID_Alice, 5, hid, Id_Alice_hid);
|
||||
t1 = Big8wAddMod(H(Id_Alice_hid, 5 + 1, 0x01), ke, curve.N);
|
||||
KPrintf("-----------------------------below is t1----------------------------------\n");
|
||||
Big8wPrint(&t1);
|
||||
|
||||
t2 = Big8wMultMod(ke, Big8wReverse(t1, curve.N), curve.N);
|
||||
KPrintf("-----------------------------below is t2----------------------------------\n");
|
||||
Big8wPrint(&t2);
|
||||
|
||||
deA = G2PointMult(t2, P2);
|
||||
KPrintf("------------------------------below is deA--------------------------------\n");
|
||||
Big8wPrint(&deA.x.high);
|
||||
Big8wPrint(&deA.x.low);
|
||||
Big8wPrint(&deA.y.high);
|
||||
Big8wPrint(&deA.y.low);
|
||||
|
||||
JoinIDhid(ID_Bob, 3, hid, ID_Bob_hid);
|
||||
|
||||
t3 = Big8wAddMod(H(ID_Bob_hid, 3 + 1, 0x01), ke, curve.N);
|
||||
KPrintf("-----------------------------below is t3----------------------------------\n");
|
||||
Big8wPrint(&t3);
|
||||
|
||||
t4 = Big8wMultMod(ke, Big8wReverse(t3, curve.N), curve.N);
|
||||
KPrintf("-----------------------------below is t4----------------------------------\n");
|
||||
Big8wPrint(&t4);
|
||||
|
||||
deB = G2PointMult(t4, P2);
|
||||
KPrintf("------------------------------below is deB--------------------------------\n");
|
||||
Big8wPrint(&deB.x.high);
|
||||
Big8wPrint(&deB.x.low);
|
||||
Big8wPrint(&deB.y.high);
|
||||
Big8wPrint(&deB.y.low);
|
||||
|
||||
JoinIDhid(ID_Bob, 3, hid, ID_Bob_hid);
|
||||
|
||||
h1 = H(ID_Bob_hid, 3 + 1, 0x01);
|
||||
KPrintf("-----------------------------below is h1----------------------------------\n");
|
||||
Big8wPrint(&h1);
|
||||
|
||||
QB = G1pointAdd(Ppub_e, G1pointMult(h1, P1));
|
||||
KPrintf("-----------------------------below is QB----------------------------------\n");
|
||||
Big8wPrint(&QB.x);
|
||||
Big8wPrint(&QB.y);
|
||||
|
||||
RA = G1pointMult(rA, QB);
|
||||
KPrintf("-----------------------------below is RA----------------------------------\n");
|
||||
Big8wPrint(&RA.x);
|
||||
Big8wPrint(&RA.y);
|
||||
|
||||
JoinIDhid(ID_Alice, 5, hid, Id_Alice_hid);
|
||||
h1 = H(Id_Alice_hid, 5 + 1, 0x01);
|
||||
KPrintf("-----------------------------below is h1----------------------------------\n");
|
||||
Big8wPrint(&h1);
|
||||
|
||||
QA = G1pointAdd(Ppub_e, G1pointMult(h1, P1));
|
||||
KPrintf("-----------------------------below is QA----------------------------------\n");
|
||||
Big8wPrint(&QA.x);
|
||||
Big8wPrint(&QA.y);
|
||||
|
||||
RB = G1pointMult(rB, QA);
|
||||
KPrintf("-----------------------------below is RB----------------------------------\n");
|
||||
Big8wPrint(&RB.x);
|
||||
Big8wPrint(&RB.y);
|
||||
|
||||
g1 = BiLinearPairing(RA, deB);
|
||||
KPrintf("-----------------------------below is g1----------------------------------\n");
|
||||
Q12Print(&g1);
|
||||
|
||||
g2 = BiLinearPairing(Ppub_e, P2);
|
||||
g2 = Q12PowerMod(g2, rB);
|
||||
KPrintf("-----------------------------below is g2----------------------------------\n");
|
||||
Q12Print(&g2);
|
||||
|
||||
g3 = Q12PowerMod(g1, rB);
|
||||
KPrintf("-----------------------------below is g3----------------------------------\n");
|
||||
Q12Print(&g3);
|
||||
|
||||
JoinIDAIDBRARBg123(ID_Alice, 5, ID_Bob, 3, &RA, &RB, &g1, &g2, &g3, strA);
|
||||
|
||||
KDF(strA, 5 + 3 + BIG8W_BYTESIZE * 2 * 2 + BIG8W_BYTESIZE * 12 * 3, klen, SKB);
|
||||
KPrintf("-----------------------------below is SKB---------------------------------\n");
|
||||
for (i = 0; i < klen/8; i++){
|
||||
KPrintf("%02x", SKB[i]);
|
||||
if (((i+1)&0x3) == 0)
|
||||
KPrintf(" ");
|
||||
if (((i + 1) % 32) == 0)
|
||||
KPrintf("\n");
|
||||
}
|
||||
KPrintf("\n");
|
||||
|
||||
KPrintf("-----------------------------below is SB----------------------------------\n");
|
||||
HashTwice(ID_Alice, 5, ID_Bob, 3, &RA, &RB, &g1, &g2, &g3, 0x82, SB);
|
||||
HashTwice(ID_Alice, 5, ID_Bob, 3, &RA, &RB, &g1, &g2, &g3, 0x83, S2);
|
||||
for (i = 0; i < 256/8; i++){
|
||||
KPrintf("%02x", SB[i]);
|
||||
if (((i+1)&0x3) == 0)
|
||||
KPrintf(" ");
|
||||
if (((i + 1) % 32) == 0)
|
||||
KPrintf("\n");
|
||||
}
|
||||
KPrintf("\n");
|
||||
|
||||
g1 = BiLinearPairing(Ppub_e, P2);
|
||||
g1 = Q12PowerMod(g1, rA);
|
||||
KPrintf("-----------------------------below is g1----------------------------------\n");
|
||||
Q12Print(&g1);
|
||||
|
||||
g2 = BiLinearPairing(RB, deA);
|
||||
KPrintf("-----------------------------below is g2----------------------------------\n");
|
||||
Q12Print(&g2);
|
||||
|
||||
g3 = Q12PowerMod(g2, rA);
|
||||
KPrintf("-----------------------------below is g3----------------------------------\n");
|
||||
Q12Print(&g3);
|
||||
|
||||
KPrintf("-----------------------------below is S1----------------------------------\n");
|
||||
HashTwice(ID_Alice, 5, ID_Bob, 3, &RA, &RB, &g1, &g2, &g3, 0x82, S1);
|
||||
|
||||
for (i = 0; i < 256/8; i++){
|
||||
KPrintf("%02x", S1[i]);
|
||||
if (((i+1)&0x3) == 0)
|
||||
KPrintf(" ");
|
||||
if (((i + 1) % 32) == 0)
|
||||
KPrintf("\n");
|
||||
}
|
||||
KPrintf("\n");
|
||||
|
||||
KDF(strA, 5 + 3 + BIG8W_BYTESIZE * 2 * 2 + BIG8W_BYTESIZE * 12 * 3, klen, SKA);
|
||||
KPrintf("-----------------------------below is SKA---------------------------------\n");
|
||||
for (i = 0; i < klen/8; i++){
|
||||
KPrintf("%02x", SKA[i]);
|
||||
if (((i+1)&0x3) == 0)
|
||||
KPrintf(" ");
|
||||
if (((i + 1) % 32) == 0)
|
||||
KPrintf("\n");
|
||||
}
|
||||
printf("\n");
|
||||
|
||||
KPrintf("-----------------------------below is SA----------------------------------\n");
|
||||
HashTwice(ID_Alice, 5, ID_Bob, 3, &RA, &RB, &g1, &g2, &g3, 0x83, SA);
|
||||
for (i = 0; i < 256/8; i++){
|
||||
KPrintf("%02x", SA[i]);
|
||||
if (((i+1)&0x3) == 0)
|
||||
KPrintf(" ");
|
||||
if (((i + 1) % 32) == 0)
|
||||
KPrintf("\n");
|
||||
}
|
||||
KPrintf("\n");
|
||||
|
||||
KPrintf("-----------------------------below is S2----------------------------------\n");
|
||||
for (i = 0; i < 256/8; i++){
|
||||
KPrintf("%02x", S2[i]);
|
||||
if (((i+1)&0x3) == 0)
|
||||
KPrintf(" ");
|
||||
if (((i + 1) % 32) == 0)
|
||||
KPrintf("\n");
|
||||
}
|
||||
KPrintf("\n");
|
||||
|
||||
// Following is test of API, random big number generated in SM9KeyExchangeProduceR, so result is different from the former.
|
||||
// To get the same result, you should delete the line "*r = RandomNumGenerate();" in function SM9KeyExchangeR. (or set as note)
|
||||
|
||||
KPrintf("---------------------------SM9 key exchange API test----------------------\n");
|
||||
|
||||
SM9KeyExchangeProduceR(ID_Bob, 3, &rA, &RA, Ppub_e);
|
||||
KPrintf("-----------------------------below is RA----------------------------------\n");
|
||||
Big8wPrint(&RA.x);
|
||||
Big8wPrint(&RA.y);
|
||||
|
||||
SM9KeyExchangeProduceR(ID_Alice, 5, &rB, &RB, Ppub_e);
|
||||
KPrintf("-----------------------------below is RB----------------------------------\n");
|
||||
Big8wPrint(&RB.x);
|
||||
Big8wPrint(&RB.y);
|
||||
|
||||
SM9KeyExchangeProduceKey(&RA, &RB, &rA, klen, ID_Alice, 5, ID_Bob, 3, &g1, &g2, &g3, SKA, true, Ppub_e, deA);
|
||||
KPrintf("-----------------------------below is g1----------------------------------\n");
|
||||
Q12Print(&g1);
|
||||
|
||||
KPrintf("-----------------------------below is g2----------------------------------\n");
|
||||
Q12Print(&g2);
|
||||
|
||||
KPrintf("-----------------------------below is g3----------------------------------\n");
|
||||
Q12Print(&g3);
|
||||
|
||||
KPrintf("-----------------------------below is SKA---------------------------------\n");
|
||||
for (i = 0; i < klen/8; i++){
|
||||
KPrintf("%02x", SKA[i]);
|
||||
if (((i+1)&0x3) == 0)
|
||||
KPrintf(" ");
|
||||
if (((i + 1) % 32) == 0)
|
||||
KPrintf("\n");
|
||||
}
|
||||
KPrintf("\n");
|
||||
|
||||
// g1,g2,g3 changed
|
||||
// SM9KeyExchangeProduceKey(&RA, &RB, &rB, klen, ID_Alice, 5, ID_Bob, 3, &g1, &g2, &g3, SKB, false, Ppub_e, deB);
|
||||
|
||||
SM9KeyExchangeVerifyKey(&g1, &g2, &g3, &RA, &RB, ID_Alice, 5, ID_Bob, 3, S1, SA);
|
||||
KPrintf("-----------------------------below is SA----------------------------------\n");
|
||||
for (i = 0; i < 256/8; i++){
|
||||
KPrintf("%02x", SA[i]);
|
||||
if (((i+1)&0x3) == 0)
|
||||
KPrintf(" ");
|
||||
if (((i + 1) % 32) == 0)
|
||||
KPrintf("\n");
|
||||
}
|
||||
KPrintf("\n");
|
||||
|
||||
KPrintf("-----------------------------below is S1----------------------------------\n");
|
||||
for (i = 0; i < 256/8; i++){
|
||||
KPrintf("%02x", S1[i]);
|
||||
if (((i+1)&0x3) == 0)
|
||||
KPrintf(" ");
|
||||
if (((i + 1) % 32) == 0)
|
||||
KPrintf("\n");
|
||||
}
|
||||
KPrintf("\n");
|
||||
|
||||
SM9KeyExchangeVerifyKey(&g1, &g2, &g3, &RA, &RB, ID_Alice, 5, ID_Bob, 3, SB, S2);
|
||||
KPrintf("-----------------------------below is SB----------------------------------\n");
|
||||
for (i = 0; i < 256/8; i++){
|
||||
KPrintf("%02x", SB[i]);
|
||||
if (((i+1)&0x3) == 0)
|
||||
KPrintf(" ");
|
||||
if (((i + 1) % 32) == 0)
|
||||
KPrintf("\n");
|
||||
}
|
||||
KPrintf("\n");
|
||||
|
||||
KPrintf("-----------------------------below is S2----------------------------------\n");
|
||||
for (i = 0; i < 256/8; i++){
|
||||
KPrintf("%02x", S2[i]);
|
||||
if (((i+1)&0x3) == 0)
|
||||
KPrintf(" ");
|
||||
if (((i + 1) % 32) == 0)
|
||||
KPrintf("\n");
|
||||
}
|
||||
KPrintf("\n");
|
||||
|
||||
free(strA);
|
||||
free(strB);
|
||||
free(SKA);
|
||||
free(SKB);
|
||||
free(SA);
|
||||
free(SB);
|
||||
free(S1);
|
||||
free(S2);
|
||||
}
|
||||
/**
|
||||
* @brief test of key package and depackage, data comes from SM9
|
||||
*
|
||||
*/
|
||||
void SM9PackDepackTest()
|
||||
{
|
||||
uint32_t i, c_w_id_len, klen = 0x100;
|
||||
big8w ke, t1, t2, r;
|
||||
G1point Ppub_e, QB, C;
|
||||
G2point deB;
|
||||
q12 g, w;
|
||||
|
||||
uint8_t hid = 0x03;
|
||||
uint8_t ID_Bob[] = "Bob";
|
||||
uint8_t* ID_Bob_hid;
|
||||
uint8_t* K_encap, * c_w_id;
|
||||
|
||||
c_w_id_len = BIG8W_BYTESIZE * 2 + BIG8W_BYTESIZE * 12 + 3;
|
||||
|
||||
ID_Bob_hid= (unsigned char*)(malloc(sizeof(char) * (3 + 1)));
|
||||
K_encap = (unsigned char*)(malloc(32));
|
||||
c_w_id = (unsigned char*)(malloc(c_w_id_len));
|
||||
|
||||
ke.word[7] = 0x01EDEE;
|
||||
ke.word[6] = 0x3778F441;
|
||||
ke.word[5] = 0xF8DEA3D9;
|
||||
ke.word[4] = 0xFA0ACC4E;
|
||||
ke.word[3] = 0x07EE36C9;
|
||||
ke.word[2] = 0x3F9A0861;
|
||||
ke.word[1] = 0x8AF4AD85;
|
||||
ke.word[0] = 0xCEDE1C22;
|
||||
|
||||
r.word[7] = 0x7401;
|
||||
r.word[6] = 0x5F8489C0;
|
||||
r.word[5] = 0x1EF42704;
|
||||
r.word[4] = 0x56F9E647;
|
||||
r.word[3] = 0x5BFB602B;
|
||||
r.word[2] = 0xDE7F33FD;
|
||||
r.word[1] = 0x482AB4E3;
|
||||
r.word[0] = 0x684A6722;
|
||||
|
||||
SM9Init();
|
||||
|
||||
Ppub_e = G1pointMult(ke, P1);
|
||||
KPrintf("-----------------------------below is Ppub_e------------------------------\n");
|
||||
Big8wPrint(&Ppub_e.x);
|
||||
Big8wPrint(&Ppub_e.y);
|
||||
|
||||
JoinIDhid(ID_Bob, 3, hid, ID_Bob_hid);
|
||||
t1 = H(ID_Bob_hid, 3 + 1, 0x01);
|
||||
KPrintf("-----------------------------below is H1()--------------------------------\n");
|
||||
Big8wPrint(&t1);
|
||||
t1 = Big8wAddMod(t1, ke, curve.N);
|
||||
KPrintf("-----------------------------below is t1----------------------------------\n");
|
||||
Big8wPrint(&t1);
|
||||
|
||||
t1 = Big8wReverse(t1, curve.N);
|
||||
t2 = Big8wMultMod(ke, t1, curve.N);
|
||||
KPrintf("-----------------------------below is t2----------------------------------\n");
|
||||
Big8wPrint(&t2);
|
||||
|
||||
deB = G2PointMult(t2, P2);
|
||||
KPrintf("------------------------------below is deB--------------------------------\n");
|
||||
Big8wPrint(&deB.x.high);
|
||||
Big8wPrint(&deB.x.low);
|
||||
Big8wPrint(&deB.y.high);
|
||||
Big8wPrint(&deB.y.low);
|
||||
|
||||
QB = G1pointAdd(
|
||||
G1pointMult(H(ID_Bob_hid, 3 + 1, 0x01), P1),
|
||||
Ppub_e);
|
||||
KPrintf("-----------------------------below is QB----------------------------------\n");
|
||||
Big8wPrint(&QB.x);
|
||||
Big8wPrint(&QB.y);
|
||||
|
||||
C = G1pointMult(r, QB);
|
||||
KPrintf("-----------------------------below is C----------------------------------\n");
|
||||
Big8wPrint(&C.x);
|
||||
Big8wPrint(&C.y);
|
||||
|
||||
g = BiLinearPairing(Ppub_e, P2);
|
||||
KPrintf("-----------------------------below is g----------------------------------\n");
|
||||
Q12Print(&g);
|
||||
|
||||
w = Q12PowerMod(g, r);
|
||||
KPrintf("-----------------------------below is w----------------------------------\n");
|
||||
Q12Print(&w);
|
||||
|
||||
JoinCwID(&C, &w, ID_Bob, 3, c_w_id);
|
||||
|
||||
KDF(c_w_id, c_w_id_len, klen, K_encap);
|
||||
KPrintf("-----------------------------below is K-----------------------------------\n");
|
||||
for (i = 0; i < klen / 8; i++){
|
||||
KPrintf("%02x", K_encap[i]);
|
||||
if (((i+1)&0x3) == 0)
|
||||
KPrintf(" ");
|
||||
if (((i + 1) % 32) == 0)
|
||||
KPrintf("\n");
|
||||
}
|
||||
KPrintf("\n");
|
||||
|
||||
w = BiLinearPairing(C, deB);
|
||||
KPrintf("-----------------------------below is w'----------------------------------\n");
|
||||
Q12Print(&w);
|
||||
|
||||
JoinCwID(&C, &w, ID_Bob, 3, c_w_id);
|
||||
|
||||
KDF(c_w_id, c_w_id_len, klen, K_encap);
|
||||
KPrintf("-----------------------------below is K'----------------------------------\n");
|
||||
for (i = 0; i < klen / 8; i++){
|
||||
KPrintf("%02x", K_encap[i]);
|
||||
if (((i+1)&0x3) == 0)
|
||||
KPrintf(" ");
|
||||
if (((i + 1) % 32) == 0)
|
||||
KPrintf("\n");
|
||||
}
|
||||
KPrintf("\n");
|
||||
KPrintf("pack and depack done\n");
|
||||
|
||||
free(ID_Bob_hid);
|
||||
free(K_encap);
|
||||
free(c_w_id);
|
||||
}
|
||||
/**
|
||||
* @brief test of encrypt and decrypt with KDF and SM4, data comes from SM9
|
||||
*
|
||||
*/
|
||||
void SM9EncryptDecryptTest()
|
||||
{
|
||||
big8w r, ke, t1, t2;
|
||||
G1point Ppub_e, QB, C1;
|
||||
G2point deB;
|
||||
uint32_t i;
|
||||
uint32_t K1_len = 0x80, K2_len = 0x100, mlen = 0xA0;
|
||||
uint32_t klen = mlen + K2_len;
|
||||
uint32_t c_w_id_len = BIG8W_BYTESIZE * 2 + BIG8W_BYTESIZE * 12 + 3; // len(ID_Bob) = 3;
|
||||
q12 g, w;
|
||||
|
||||
unsigned char hid = 0x03;
|
||||
unsigned char ID_Bob[] = "Bob";
|
||||
unsigned char ID_Bob_hid[4];
|
||||
unsigned char message[] = "Chinese IBE standard";
|
||||
unsigned char *C_w_id;
|
||||
unsigned char *K, *C2, *C3, *C2K2, *C, *C_SM4;
|
||||
unsigned char sm4msg[32];
|
||||
|
||||
memset(sm4msg, 0x00, 32);
|
||||
|
||||
unsigned int Cbyteslen_KDF = (BIG8W_BYTESIZE * 2) + (256 / 8) + (mlen / 8);
|
||||
unsigned int Cbyteslen_SM4 = (BIG8W_BYTESIZE * 2) + (256 / 8) + ((mlen / 128) + 1) * (128 / 8);
|
||||
|
||||
C_w_id = (uint8_t*)(malloc(c_w_id_len));
|
||||
K = (uint8_t*)(malloc(((klen >> 8) + 1) * (256 / 8)));
|
||||
C2 = (uint8_t*)(malloc(mlen / 8));
|
||||
C3 = (uint8_t*)(malloc(256 / 8));
|
||||
C2K2 = (uint8_t*)(malloc(mlen/8 + K2_len/8));
|
||||
C = (uint8_t*)(malloc(Cbyteslen_KDF));
|
||||
C_SM4 = (uint8_t *)(malloc(Cbyteslen_SM4));
|
||||
|
||||
r.word[7] = 0xAAC0;
|
||||
r.word[6] = 0x541779C8;
|
||||
r.word[5] = 0xFC45E3E2;
|
||||
r.word[4] = 0xCB25C12B;
|
||||
r.word[3] = 0x5D2576B2;
|
||||
r.word[2] = 0x129AE8BB;
|
||||
r.word[1] = 0x5EE2CBE5;
|
||||
r.word[0] = 0xEC9E785C;
|
||||
|
||||
ke.word[7] = 0x01EDEE;
|
||||
ke.word[6] = 0x3778F441;
|
||||
ke.word[5] = 0xF8DEA3D9;
|
||||
ke.word[4] = 0xFA0ACC4E;
|
||||
ke.word[3] = 0x07EE36C9;
|
||||
ke.word[2] = 0x3F9A0861;
|
||||
ke.word[1] = 0x8AF4AD85;
|
||||
ke.word[0] = 0xCEDE1C22;
|
||||
|
||||
SM9Init();
|
||||
|
||||
Ppub_e = G1pointMult(ke, P1);
|
||||
KPrintf("-----------------------------below is Ppub_e------------------------------\n");
|
||||
Big8wPrint(&Ppub_e.x);
|
||||
Big8wPrint(&Ppub_e.y);
|
||||
|
||||
JoinIDhid(ID_Bob, 3, hid, ID_Bob_hid);
|
||||
t1 = Big8wAddMod(H(ID_Bob_hid, 3 + 1, 0x01), ke, curve.N);
|
||||
KPrintf("-----------------------------below is t1----------------------------------\n");
|
||||
Big8wPrint(&t1);
|
||||
|
||||
t1 = Big8wReverse(t1, curve.N);
|
||||
t2 = Big8wMultMod(ke, t1, curve.N);
|
||||
KPrintf("-----------------------------below is t2----------------------------------\n");
|
||||
Big8wPrint(&t2);
|
||||
|
||||
deB = G2PointMult(t2, P2);
|
||||
KPrintf("------------------------------below is deB--------------------------------\n");
|
||||
Big8wPrint(&deB.x.high);
|
||||
Big8wPrint(&deB.x.low);
|
||||
Big8wPrint(&deB.y.high);
|
||||
Big8wPrint(&deB.y.low);
|
||||
|
||||
QB = G1pointAdd(
|
||||
G1pointMult(H(ID_Bob_hid, 3 + 1, 0x01), P1),
|
||||
Ppub_e);
|
||||
KPrintf("-----------------------------below is QB----------------------------------\n");
|
||||
Big8wPrint(&QB.x);
|
||||
Big8wPrint(&QB.y);
|
||||
|
||||
C1 = G1pointMult(r, QB);
|
||||
KPrintf("-----------------------------below is C1----------------------------------\n");
|
||||
Big8wPrint(&C1.x);
|
||||
Big8wPrint(&C1.y);
|
||||
|
||||
g = BiLinearPairing(Ppub_e, P2);
|
||||
KPrintf("-----------------------------below is g-----------------------------------\n");
|
||||
Q12Print(&g);
|
||||
|
||||
w = Q12PowerMod(g, r);
|
||||
KPrintf("-----------------------------below is w-----------------------------------\n");
|
||||
Q12Print(&w);
|
||||
|
||||
JoinCwID(&C1, &w, ID_Bob, 3, C_w_id);
|
||||
KDF(C_w_id, c_w_id_len, klen, K);
|
||||
KPrintf("-----------------------------below is K-----------------------------------\n");
|
||||
for (i = 0; i < klen / 8; i++) {
|
||||
KPrintf("%02x", K[i]);
|
||||
if (((i+1)&0x3) == 0)
|
||||
KPrintf(" ");
|
||||
if (((i + 1) % 32) == 0)
|
||||
KPrintf("\n");
|
||||
}
|
||||
KPrintf("\n");
|
||||
|
||||
XOR(message, mlen / 8, K, C2);
|
||||
|
||||
KPrintf("-----------------------------below is C2----------------------------------\n");
|
||||
for (i = 0; i < mlen / 8; i++) {
|
||||
KPrintf("%02x", C2[i]);
|
||||
if (((i + 1) & 0x3) == 0)
|
||||
KPrintf(" ");
|
||||
if (((i + 1) % 32) == 0)
|
||||
KPrintf("\n");
|
||||
}
|
||||
KPrintf("\n");
|
||||
|
||||
for (i = 0; i < mlen / 8; i++)
|
||||
C2K2[i] = C2[i];
|
||||
for (; i < (mlen / 8) + (K2_len / 8); i++)
|
||||
C2K2[i] = K[i];
|
||||
|
||||
sm3(C2K2, (mlen / 8) + (K2_len / 8), C3);
|
||||
KPrintf("----------------------------below is C3-----------------------------------\n");
|
||||
for (i = 0; i < 256/8; i++) {
|
||||
KPrintf("%02x", C3[i]);
|
||||
if (((i + 1) & 0x3) == 0)
|
||||
KPrintf(" ");
|
||||
if (((i + 1) % 32) == 0)
|
||||
KPrintf("\n");
|
||||
}
|
||||
KPrintf("\n");
|
||||
|
||||
i = 0;
|
||||
Big8wIntou8string(&C1.x, C, i);
|
||||
i += BIG8W_BYTESIZE;
|
||||
Big8wIntou8string(&C1.y, C, i);
|
||||
i += BIG8W_BYTESIZE;
|
||||
|
||||
for (; i < BIG8W_BYTESIZE * 2 + (256 / 8); i++)
|
||||
C[i] = C3[i - BIG8W_BYTESIZE * 2];
|
||||
|
||||
for (; i < BIG8W_BYTESIZE * 2 + (256 / 8) + (mlen / 8); i++)
|
||||
C[i] = C2[i - (BIG8W_BYTESIZE * 2 + 256 / 8)];
|
||||
|
||||
KPrintf("----------------------------below is C------------------------------------\n");
|
||||
for (i = 0; i < BIG8W_BYTESIZE * 2 + (256 / 8) + (mlen / 8); i++) {
|
||||
KPrintf("%02x", C[i]);
|
||||
if (((i + 1) & 0x3) == 0)
|
||||
KPrintf(" ");
|
||||
if (((i + 1) % 32) == 0)
|
||||
KPrintf("\n");
|
||||
}
|
||||
KPrintf("\n");
|
||||
|
||||
// decrypt
|
||||
w = BiLinearPairing(C1, deB);
|
||||
KPrintf("----------------------------below is w'-----------------------------------\n");
|
||||
Q12Print(&w);
|
||||
|
||||
JoinCwID(&C1, &w, ID_Bob, 3, C_w_id);
|
||||
KDF(C_w_id, c_w_id_len, klen, K);
|
||||
KPrintf("----------------------------below is K'----------------------------------\n");
|
||||
for (i = 0; i < (klen / 8); i++) {
|
||||
KPrintf("%02x", K[i]);
|
||||
if (((i + 1) & 0x3) == 0)
|
||||
KPrintf(" ");
|
||||
if (((i + 1) % 32) == 0)
|
||||
KPrintf("\n");
|
||||
}
|
||||
KPrintf("\n");
|
||||
|
||||
XOR(C2, mlen / 8, K, message);
|
||||
|
||||
KPrintf("----------------------------below is M'----------------------------------\n");
|
||||
for (i = 0; i < mlen / 8; i++) {
|
||||
KPrintf("%02x", message[i]);
|
||||
if (((i + 1) & 0x3) == 0)
|
||||
KPrintf(" ");
|
||||
if (((i + 1) % 32) == 0)
|
||||
KPrintf("\n");
|
||||
}
|
||||
KPrintf("\n");
|
||||
|
||||
for (i = 0; i < mlen / 8; i++)
|
||||
C2K2[i] = C2[i];
|
||||
for (; i < (mlen / 8) + (K2_len / 8); i++)
|
||||
C2K2[i] = K[i];
|
||||
|
||||
sm3(C2K2, (mlen / 8) + (K2_len / 8), C3);
|
||||
KPrintf("----------------------------below is u-----------------------------------\n");
|
||||
for (i = 0; i < 256 / 8; i++) {
|
||||
KPrintf("%02x", C3[i]);
|
||||
if (((i + 1) & 0x3) == 0)
|
||||
KPrintf(" ");
|
||||
if (((i + 1) % 32) == 0)
|
||||
KPrintf("\n");
|
||||
}
|
||||
KPrintf("\n");
|
||||
|
||||
KPrintf("decrypted message:\n%s\n", message);
|
||||
|
||||
|
||||
KPrintf("-------------SM9EncryptWithKDF and SM9DecryptWithKDF test----------------\n");
|
||||
SM9EncryptWithKDF(message, mlen, K2_len, ID_Bob, 3, hid, Ppub_e, C);
|
||||
KPrintf("------------------below is C, encrypted message--------------------------\n");
|
||||
for (i = 0; i < Cbyteslen_KDF; i++) {
|
||||
KPrintf("%02x", C[i]);
|
||||
if (((i + 1) & 0x3) == 0)
|
||||
KPrintf(" ");
|
||||
if (((i + 1) % 32) == 0)
|
||||
KPrintf("\n");
|
||||
}
|
||||
KPrintf("\n");
|
||||
|
||||
SM9DecryptWithKDF(ID_Bob, 3, message, 20 * 8, K2_len, C, deB);
|
||||
KPrintf("---------------below is M, decrypted message in test.c-------------------\n");
|
||||
KPrintf("message:\n%s\n", message);
|
||||
|
||||
KPrintf("-------------SM9EncryptWithSM4 and SM9DecryptWithSM4 test----------------\n");
|
||||
SM9EncryptWithSM4(message, mlen, K1_len, K2_len, ID_Bob, 3, hid, Ppub_e, C_SM4);
|
||||
KPrintf("---------------below is C_SM4 in test.c, encrypted message---------------\n");
|
||||
for (i = 0; i < Cbyteslen_SM4; i++) {
|
||||
KPrintf("%02x", C_SM4[i]);
|
||||
if (((i + 1) & 0x3) == 0)
|
||||
KPrintf(" ");
|
||||
if (((i + 1) % 32) == 0)
|
||||
KPrintf("\n");
|
||||
}
|
||||
KPrintf("\n");
|
||||
|
||||
if (!SM9DecryptWithSM4(ID_Bob, 3, sm4msg, (mlen / 8), K1_len, K2_len, C_SM4, Cbyteslen_SM4, deB))
|
||||
KPrintf("SM9DecryptWithSM4 failed\n");
|
||||
KPrintf("---------------------below is M, decrypted message-----------------------\n");
|
||||
for (i = 0; i < (mlen / 8); i++)
|
||||
KPrintf("%c", sm4msg[i]);
|
||||
KPrintf("\n");
|
||||
|
||||
free(C_w_id);
|
||||
free(K);
|
||||
free(C2);
|
||||
free(C2K2);
|
||||
free(C3);
|
||||
free(C);
|
||||
free(C_SM4);
|
||||
}
|
||||
|
||||
// int main()
|
||||
// {
|
||||
// //SignAndVerifyTest();
|
||||
// SM9KeyExchangeTest();
|
||||
// //SM9PackDepackTest();
|
||||
// //SM9EncryptDecryptTest();
|
||||
// }
|
|
@ -26,6 +26,7 @@ endif
|
|||
|
||||
ifeq ($(BSP_ROOT),$(KERNEL_ROOT)/board/stm32f407-st-discovery)
|
||||
KERNELPATHS :=-I$(BSP_ROOT) \
|
||||
-I$(KERNEL_ROOT)/arch/arm/cortex-m4 \
|
||||
-I$(BSP_ROOT)/third_party_driver \
|
||||
-I$(BSP_ROOT)/third_party_driver/sdio \
|
||||
-I$(BSP_ROOT)/include \
|
||||
|
@ -37,6 +38,7 @@ endif
|
|||
|
||||
ifeq ($(BSP_ROOT),$(KERNEL_ROOT)/board/aiit-arm32-board)
|
||||
KERNELPATHS :=-I$(BSP_ROOT) \
|
||||
-I$(KERNEL_ROOT)/arch/arm/cortex-m4 \
|
||||
-I$(BSP_ROOT)/third_party_driver \
|
||||
-I$(BSP_ROOT)/third_party_driver \
|
||||
-I$(BSP_ROOT)/include \
|
||||
|
@ -52,6 +54,7 @@ endif
|
|||
|
||||
ifeq ($(BSP_ROOT),$(KERNEL_ROOT)/board/stm32f407zgt6)
|
||||
KERNELPATHS :=-I$(BSP_ROOT) \
|
||||
-I$(KERNEL_ROOT)/arch/arm/cortex-m4 \
|
||||
-I$(BSP_ROOT)/third_party_driver \
|
||||
-I$(BSP_ROOT)/third_party_driver/sdio\
|
||||
-I$(BSP_ROOT)/include \
|
||||
|
@ -109,6 +112,17 @@ KERNELPATHS :=-I$(BSP_ROOT) \
|
|||
-I$(KERNEL_ROOT)/include #
|
||||
endif
|
||||
|
||||
ifeq ($(BSP_ROOT),$(KERNEL_ROOT)/board/cortex-m3-emulator)
|
||||
KERNELPATHS :=-I$(BSP_ROOT) \
|
||||
-I$(KERNEL_ROOT)/arch/arm/cortex-m3 \
|
||||
-I$(BSP_ROOT)/third_party_driver \
|
||||
-I$(BSP_ROOT)/third_party_driver/Libraries/driverlib \
|
||||
-I$(BSP_ROOT)/third_party_driver/Libraries/ \
|
||||
-I$(BSP_ROOT)/third_party_driver/Libraries/inc \
|
||||
-I$(KERNEL_ROOT)/include \
|
||||
-I$(BSP_ROOT)/include #
|
||||
endif
|
||||
|
||||
KERNELPATHS += -I$(KERNEL_ROOT)/arch \
|
||||
-I$(KERNEL_ROOT)/arch/risc-v/shared/kernel_service #
|
||||
|
||||
|
@ -130,6 +144,10 @@ ifeq ($(CONFIG_CONNECTION_ADAPTER), y)
|
|||
KERNELPATHS += -I$(KERNEL_ROOT)/framework/connection/Adapter/include #
|
||||
endif
|
||||
|
||||
ifeq ($(CONFIG_CRYPTO), y)
|
||||
KERNELPATHS += -I$(KERNEL_ROOT)/framework/security/crypto/include #
|
||||
endif
|
||||
|
||||
KERNELPATHS += -I$(KERNEL_ROOT)/resources/include #
|
||||
|
||||
ifeq ($(CONFIG_RESOURCES_SPI), y)
|
||||
|
@ -147,7 +165,6 @@ KERNELPATHS +=-I$(KERNEL_ROOT)/tool/shell/letter-shell \
|
|||
endif
|
||||
|
||||
|
||||
|
||||
ifeq ($(CONFIG_LIB_NEWLIB),y)
|
||||
KERNELPATHS += -I$(KERNEL_ROOT)/lib/newlib/include #
|
||||
endif
|
||||
|
@ -166,7 +183,6 @@ endif
|
|||
|
||||
ifeq ($(ARCH), arm)
|
||||
KERNELPATHS +=-I$(KERNEL_ROOT)/arch/arm/shared \
|
||||
-I$(KERNEL_ROOT)/arch/arm/cortex-m4 \
|
||||
-I$(KERNEL_ROOT)/lib/comlibc/common #
|
||||
endif
|
||||
|
||||
|
|
Loading…
Reference in New Issue