1
0
forked from me/IronOS

Pinecil V2 (#1341)

* Add SDK

* fork

* massaging makefile

* Drop git module

* Bring in sdk as its broken

Far, Far to much crap to fix with regex now

* Remove bl706

* rf_para_flash_t is missing defs

* Remove crapton of junk

* Remove yet more

* Poking I2C

* Update peripheral_config.h

* Update pinmux_config.h

* Update preRTOS.cpp

* Update main.hpp

* Setup template

* Verbose boot

* I2C ish

* Update I2C_Wrapper.cpp

* Update main.cpp

* Turn off I2C reading for now

* Display running

* Roughing out scheduling timer0

* Starting ADC setup

* Working scheduling of ADC 🎉

* Format adc headers

* Update IRQ.cpp

* Buttons working

* Slow down I2C

* Poking IRQ

* Larger stack required

* Accel on

* Trying to chase down why __libc_init_array isnt working yet

* Working c++

* Cleanup

* Bump stacks

* I2C wake part workaround

* Cleanup

* Working PWM init

* qc draft

* Hookup PWM

* Stable enough ADC

* ADC timing faster + timer without HAL

* Silence

* Remove boot banner

* Tuning in ADC

* Wake PID after ADC

* Remove unused hal

* Draft flash settings

* Working settings save & restore

* Update to prod model

* Cleanup

* NTC thermistor

* Correct adc gain

* Rough tip resistance progress

* Scratch out resistance awareness of the tip

* better adc settings

* Tweaking ADC

* ADC tweaking

* Make adc range scalable

* Update Dockerfile

* Update configuration.h

* Can read same ADC twice in a row

* ADC Setup

* Update PIDThread.cpp

* Lesser adc backoff

* Update USBPD.h

* Add device ID

* Update BSP_Power.h

* Update BSP.cpp

* DrawHex dynamicLength

* Shorter ID padding

* Show validation code

* tip measurement

* Create access for w0w1

* Expose w0 w1

* Enable debug

* crc32

* Device validation

* wip starting epr

* Logic refactor

* Safer PWM Init

* PD cleanups

* Update bl702_pwm.c

* Update power.cpp

* Update usb-pd

* io

* EPR decode

* Better gui for showing pd specs

* Rough handler for capabilities

* EPR

* Fix > 25V input

* Perform pow step after PPS

* Update BSP.cpp

* Fix timer output

* QC3

* Add tip resistance view

* Hold PD negotiation until detection is done for tip res

* Get Thermal mass

* Tip res =0 protection

* Update PIDThread.cpp

* Update GUIThread.cpp

* Rewrite tip resistance measurement

* Update GUIThread.cpp

* Fix fallback

* Far better tip resistance measurement

* Fix QC 0.6V D-

* Convert the interpolator to int32

* Correct the NTC lookup

* Update BSP.cpp

* Update Setup.cpp

* .

Update configuration #defines

More backported functions

* Update usb-pd

* More missed updates

* Refactor BSP

Magic BSP -> PinecilV2
Pine64 BSP -> Pinecil

Update Makefile

* Add Pinecilv2 to CI

* Pinecil v2 multi-lang

Update push.yml

* Update HallSensor.md

* Update README.md

* Fix wrong prestartcheck default

* Fix logo mapping

* Update Makefile

* Remove unused font block

* Style

* Style

* Remove unused timer funcs

* More culling TS80P

* Revert "More culling TS80P"

This reverts commit 2078b89be7.

* Revert "Remove unused timer funcs"

This reverts commit 0c693a89cc.

* Make VBus check maskable

* Remove DMA half transfer

* Drop using brightness and invert icons and go back to text

Saves flash space

* Refactor settings UI drawing descriptions

* Shorten setting function names

* Store bin file assets

* Fix MHP prestart
This commit is contained in:
Ben V. Brown
2022-08-19 15:39:37 +10:00
committed by GitHub
parent 61a679115d
commit 1fbcdcdf98
428 changed files with 165913 additions and 1380 deletions

View File

@@ -0,0 +1,277 @@
// BSP mapping functions
#include "BSP.h"
#include "I2C_Wrapper.hpp"
#include "IRQ.h"
#include "Pins.h"
#include "Setup.h"
#include "TipThermoModel.h"
#include "USBPD.h"
#include "Utils.h"
#include "configuration.h"
#include "crc32.h"
#include "history.hpp"
#include "main.hpp"
// These control the period's of time used for the PWM
const uint16_t powerPWM = 255;
const uint8_t holdoffTicks = 25; // This is the tick delay before temp measure starts (i.e. time for op-amp recovery)
const uint8_t tempMeasureTicks = 25;
uint16_t totalPWM = 255; // Total length of the cycle's ticks
void resetWatchdog() {
//#TODO
}
#ifdef TEMP_NTC
// Lookup table for the NTC
// Stored as ADCReading,Temp in degC
static const int32_t NTCHandleLookup[] = {
// ADC Reading , Temp in C x10
3221, -400, //
4144, -350, //
5271, -300, //
6622, -250, //
8219, -200, //
10075, -150, //
12190, -100, //
14554, -50, //
17151, 0, //
19937, 50, //
22867, 100, //
25886, 150, //
28944, 200, //
29546, 210, //
30159, 220, //
30769, 230, //
31373, 240, //
31969, 250, //
32566, 260, //
33159, 270, //
33749, 280, //
34334, 290, //
34916, 300, //
35491, 310, //
36062, 320, //
36628, 330, //
37186, 340, //
37739, 350, //
38286, 360, //
38825, 370, //
39358, 380, //
39884, 390, //
40400, 400, //
42879, 450, //
45160, 500, //
47235, 550, //
49111, 600, //
50792, 650, //
52292, 700, //
53621, 750, //
54797, 800, //
55836, 850, //
56748, 900, //
57550, 950, //
58257, 1000, //
};
#endif
uint16_t getHandleTemperature(uint8_t sample) {
int32_t result = getADCHandleTemp(sample);
// Tip is wired up with an NTC thermistor
// 10K NTC balanced with a 10K pulldown
// NTCG163JF103FTDS
return Utils::InterpolateLookupTable(NTCHandleLookup, sizeof(NTCHandleLookup) / (2 * sizeof(int32_t)), result);
}
uint16_t getInputVoltageX10(uint16_t divisor, uint8_t sample) {
uint32_t res = getADCVin(sample);
res *= 4;
res /= divisor;
return res;
}
void unstick_I2C() {
/* configure SDA/SCL for GPIO */
// GPIO_BC(GPIOB) |= SDA_Pin | SCL_Pin;
// gpio_init(SDA_GPIO_Port, GPIO_MODE_OUT_OD, GPIO_OSPEED_50MHZ, SDA_Pin | SCL_Pin);
// for (int i = 0; i < 8; i++) {
// asm("nop");
// asm("nop");
// asm("nop");
// asm("nop");
// asm("nop");
// GPIO_BOP(GPIOB) |= SCL_Pin;
// asm("nop");
// asm("nop");
// asm("nop");
// asm("nop");
// asm("nop");
// GPIO_BOP(GPIOB) &= SCL_Pin;
// }
// /* connect PB6 to I2C0_SCL */
// /* connect PB7 to I2C0_SDA */
// gpio_init(SDA_GPIO_Port, GPIO_MODE_AF_OD, GPIO_OSPEED_50MHZ, SDA_Pin | SCL_Pin);
}
uint8_t getButtonA() {
uint8_t val = gpio_read(KEY_A_Pin);
return val;
}
uint8_t getButtonB() {
uint8_t val = gpio_read(KEY_B_Pin);
return val;
}
void reboot() {
// Spin for watchdog
for (;;) {}
}
void delay_ms(uint16_t count) {
// delay_1ms(count);
BL702_Delay_MS(count);
}
uint32_t __get_IPSR(void) {
return 0; // To shut-up CMSIS
}
bool isTipDisconnected() {
uint16_t tipDisconnectedThres = TipThermoModel::getTipMaxInC() - 5;
uint32_t tipTemp = TipThermoModel::getTipInC();
return tipTemp > tipDisconnectedThres;
}
void setStatusLED(const enum StatusLED state) {
// Dont have one
}
uint8_t lastTipResistance = 0; // default to unknown
const uint8_t numTipResistanceReadings = 3;
uint32_t tipResistanceReadings[3] = {0, 0, 0};
uint8_t tipResistanceReadingSlot = 0;
uint8_t getTipResistanceX10() {
// Return tip resistance in x10 ohms
// We can measure this using the op-amp
return lastTipResistance;
}
uint8_t getTipThermalMass() {
if (lastTipResistance >= 80) {
return TIP_THERMAL_MASS;
}
return (TIP_THERMAL_MASS * 25) / 10;
}
// We want to calculate lastTipResistance
// If tip is connected, and the tip is cold and the tip is not being heated
// We can use the GPIO to inject a small current into the tip and measure this
// The gpio is 5.1k -> diode -> tip -> gnd
// Source is 3.3V-0.5V
// Which is around 0.54mA this will induce:
// 6 ohm tip -> 3.24mV (Real world ~= 3320)
// 8 ohm tip -> 4.32mV (Real world ~= 4500)
// Which is definitely measureable
// Taking shortcuts here as we know we only really have to pick apart 6 and 8 ohm tips
// These are reported as 60 and 75 respectively
void performTipResistanceSampleReading() {
// 0 = read then turn on pullup, 1 = read then turn off pullup, 2 = read then turn on pullup, 3 = final read + turn off pullup
tipResistanceReadings[tipResistanceReadingSlot] = TipThermoModel::convertTipRawADCTouV(getTipRawTemp(0));
gpio_write(TIP_RESISTANCE_SENSE, tipResistanceReadingSlot == 0);
tipResistanceReadingSlot++;
}
void FinishMeasureTipResistance() {
// Otherwise we now have the 4 samples;
// _^_ order, 2 delta's, combine these
int32_t calculatedSkew = tipResistanceReadings[0] - tipResistanceReadings[2]; // If positive tip is cooling
calculatedSkew /= 2; // divide by two to get offset per time constant
int32_t reading = (((tipResistanceReadings[1] - tipResistanceReadings[0]) + calculatedSkew) // jump 1 - skew
+ // +
((tipResistanceReadings[1] - tipResistanceReadings[2]) + calculatedSkew) // jump 2 - skew
) //
/ 2; // Take average
// lastTipResistance = reading / 100;
// // As we are only detecting two resistances; we can split the difference for now
uint8_t newRes = 0;
if (reading > 8000) {
// return; // Change nothing as probably disconnected tip
} else if (reading < 5000) {
newRes = 62;
} else {
newRes = 80;
}
lastTipResistance = newRes;
}
volatile bool tipMeasurementOccuring = true;
volatile TickType_t nextTipMeasurement = 100;
void performTipMeasurementStep() {
// Wait 100ms for settle time
if (xTaskGetTickCount() < (nextTipMeasurement)) {
return;
}
nextTipMeasurement = xTaskGetTickCount() + TICKS_100MS;
if (tipResistanceReadingSlot < numTipResistanceReadings) {
performTipResistanceSampleReading();
return;
}
// We are sensing the resistance
FinishMeasureTipResistance();
tipMeasurementOccuring = false;
}
uint8_t preStartChecks() {
performTipMeasurementStep();
return preStartChecksDone();
}
uint8_t preStartChecksDone() { return (lastTipResistance == 0 || tipResistanceReadingSlot < numTipResistanceReadings || tipMeasurementOccuring) ? 0 : 1; }
// Return hardware unique ID if possible
uint64_t getDeviceID() {
// uint32_t tmp = 0;
// uint32_t tmp2 = 0;
// EF_Ctrl_Read_Sw_Usage(0, &tmp);
// EF_Ctrl_Read_Sw_Usage(1, &tmp2);
// return tmp | (((uint64_t)tmp2) << 32);
uint64_t tmp = 0;
EF_Ctrl_Read_Chip_ID((uint8_t *)&tmp);
return __builtin_bswap64(tmp);
}
auto crc32Table = CRC32Table<>();
uint32_t gethash() {
static uint32_t computedHash = 0;
if (computedHash != 0) {
return computedHash;
}
uint32_t deviceKey = EF_Ctrl_Get_Key_Slot_w0();
const uint32_t crcInitialVector = 0xCAFEF00D;
uint8_t crcPayload[] = {(uint8_t)(deviceKey), (uint8_t)(deviceKey >> 8), (uint8_t)(deviceKey >> 16), (uint8_t)(deviceKey >> 24), 0, 0, 0, 0, 0, 0, 0, 0};
EF_Ctrl_Read_Chip_ID(crcPayload + sizeof(deviceKey)); // Load device key into second half
computedHash = crc32Table.computeCRC32(crcInitialVector, crcPayload, sizeof(crcPayload));
return computedHash;
}
uint32_t getDeviceValidation() {
// 4 byte user data burned in at factory
return EF_Ctrl_Get_Key_Slot_w1();
}
uint8_t getDeviceValidationStatus() {
uint32_t programmedHash = EF_Ctrl_Get_Key_Slot_w1();
uint32_t computedHash = gethash();
return programmedHash == computedHash ? 0 : 1;
}

View File

@@ -0,0 +1,35 @@
/*
* Debug.cpp
*
* Created on: 26 Jan. 2021
* Author: Ralim
*/
#include "Debug.h"
#include "FreeRTOS.h"
#include "Pins.h"
char uartOutputBuffer[uartOutputBufferLength];
volatile uint32_t currentOutputPos = 0xFF;
volatile uint32_t outputLength = 0;
extern volatile uint8_t pendingPWM;
void log_system_state(int32_t PWMWattsx10) {
if (currentOutputPos == 0xFF) {
// Want to print a CSV log out the uart
// Tip_Temp_C,Handle_Temp_C,Output_Power_Wattx10,PWM,Tip_Raw\r\n
// 3+1+3+1+3+1+3+1+5+2 = 23, so sizing at 32 for now
outputLength = snprintf(uartOutputBuffer, uartOutputBufferLength, "%lu,%u,%li,%u,%lu\r\n", //
TipThermoModel::getTipInC(false), // Tip temp in C
getHandleTemperature(0), // Handle temp in C X10
PWMWattsx10, // Output Wattage
pendingPWM, // PWM
TipThermoModel::convertTipRawADCTouV(getTipRawTemp(0), true) // Tip temp in uV
);
// Now print this out the uart via IRQ (DMA cant be used as oled has it)
currentOutputPos = 0;
/* enable USART1 Transmit Buffer Empty interrupt */
// usart_interrupt_enable(UART_PERIF, USART_INT_TBE);
}
}

View File

@@ -0,0 +1,22 @@
/*
* Debug.h
*
* Created on: 26 Jan. 2021
* Author: Ralim
*/
#ifndef CORE_BSP_PINE64_DEBUG_H_
#define CORE_BSP_PINE64_DEBUG_H_
#include "BSP.h"
#include "TipThermoModel.h"
#include <stdio.h>
#include <string.h>
const unsigned int uartOutputBufferLength = 32;
extern char uartOutputBuffer[uartOutputBufferLength];
extern "C" {
ssize_t _write(int fd, const void *ptr, size_t len);
void USART1_IRQHandler(void);
}
#endif /* CORE_BSP_PINE64_DEBUG_H_ */

View File

@@ -0,0 +1,83 @@
#ifndef FREERTOS_CONFIG_H
#define FREERTOS_CONFIG_H
#include <stdint.h>
#define portCHAR char
#define configSUPPORT_STATIC_ALLOCATION 1
#define configSUPPORT_DYNAMIC_ALLOCATION 0
#define CLINT_CTRL_ADDR (0x02000000UL)
#define configCLINT_BASE_ADDRESS CLINT_CTRL_ADDR
#define configUSE_PREEMPTION 1
#define configUSE_IDLE_HOOK 0
#define configUSE_TICK_HOOK 0
#define configCPU_CLOCK_HZ (1000000UL)
#define configTICK_RATE_HZ ((TickType_t)1000)
#define configMAX_PRIORITIES (7)
#define configMINIMAL_STACK_SIZE ((unsigned short)160) /* Only needs to be this high as some demo tasks also use this constant. In production only the idle task would use this. */
#define configTOTAL_HEAP_SIZE ((size_t)0)
#define configMAX_TASK_NAME_LEN (24)
#define configUSE_TRACE_FACILITY 0
#define configUSE_16_BIT_TICKS 0
#define configIDLE_SHOULD_YIELD 0
#define configUSE_MUTEXES 1
#define configQUEUE_REGISTRY_SIZE 8
#define configCHECK_FOR_STACK_OVERFLOW 2
#define configUSE_RECURSIVE_MUTEXES 1
#define configUSE_MALLOC_FAILED_HOOK 1
#define configUSE_APPLICATION_TASK_TAG 0
#define configUSE_COUNTING_SEMAPHORES 1
#define configGENERATE_RUN_TIME_STATS 0
#define configUSE_PORT_OPTIMISED_TASK_SELECTION 1
#define configUSE_STATS_FORMATTING_FUNCTIONS 0
#define configUSE_TICKLESS_IDLE 0
/* Co-routine definitions. */
#define configUSE_CO_ROUTINES 0
/* Software timer definitions. */
#define configUSE_TIMERS 0
/* Task priorities. Allow these to be overridden. */
#ifndef uartPRIMARY_PRIORITY
#define uartPRIMARY_PRIORITY (configMAX_PRIORITIES - 3)
#endif
#ifdef __cplusplus
extern "C" {
#endif
/* Normal assert() semantics without relying on the provision of an assert.h
header file. */
void vAssertCalled(void);
#define configASSERT(x) \
if ((x) == 0) \
vAssertCalled()
#ifdef __cplusplus
}
#endif
#if (configUSE_TICKLESS_IDLE != 0)
void vApplicationSleep(uint32_t xExpectedIdleTime);
#define portSUPPRESS_TICKS_AND_SLEEP(xExpectedIdleTime) vApplicationSleep(xExpectedIdleTime)
#endif
#define INCLUDE_vTaskPrioritySet 0
#define INCLUDE_uxTaskPriorityGet 0
#define INCLUDE_vTaskDelete 0
#define INCLUDE_vTaskSuspend 1
#define INCLUDE_xResumeFromISR 1
#define INCLUDE_vTaskDelayUntil 1
#define INCLUDE_vTaskDelay 1
#define INCLUDE_xTaskGetSchedulerState 1
#define INCLUDE_xTaskGetCurrentTaskHandle 1
#define INCLUDE_uxTaskGetStackHighWaterMark 1
#define INCLUDE_xTaskGetIdleTaskHandle 1
#define INCLUDE_eTaskGetState 0
#define INCLUDE_xEventGroupSetBitFromISR 1
#define INCLUDE_xTimerPendFunctionCall 0
#define INCLUDE_xTaskAbortDelay 0
#define INCLUDE_xTaskGetHandle 1
#define INCLUDE_xTaskResumeFromISR 1
/////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
#endif /* FREERTOS_CONFIG_H */

View File

@@ -0,0 +1,127 @@
/*
* FRToSI2C.cpp
*
* Created on: 14Apr.,2018
* Author: Ralim
*/
#include "BSP.h"
#include "IRQ.h"
#include "Setup.h"
extern "C" {
#include "bflb_platform.h"
#include "bl702_glb.h"
#include "bl702_i2c.h"
}
#include <I2C_Wrapper.hpp>
SemaphoreHandle_t FRToSI2C::I2CSemaphore = nullptr;
StaticSemaphore_t FRToSI2C::xSemaphoreBuffer;
#define I2C_TIME_OUT (uint16_t)(12000)
void FRToSI2C::CpltCallback() {} // Not used
bool FRToSI2C::I2C_RegisterWrite(uint8_t address, uint8_t reg, uint8_t data) { return Mem_Write(address, reg, &data, 1); }
uint8_t FRToSI2C::I2C_RegisterRead(uint8_t add, uint8_t reg) {
uint8_t temp = 0;
Mem_Read(add, reg, &temp, 1);
return temp;
}
bool FRToSI2C::Mem_Read(uint16_t DevAddress, uint16_t read_address, uint8_t *p_buffer, uint16_t number_of_byte) {
if (!lock()) {
return false;
}
I2C_Transfer_Cfg i2cCfg = {0, DISABLE, 0, 0, 0, 0};
BL_Err_Type err = ERROR;
i2cCfg.slaveAddr = DevAddress >> 1;
i2cCfg.stopEveryByte = DISABLE;
i2cCfg.subAddr = read_address;
i2cCfg.dataSize = number_of_byte;
i2cCfg.data = p_buffer;
i2cCfg.subAddrSize = 1; // one byte address
err = I2C_MasterReceiveBlocking(I2C0_ID, &i2cCfg);
bool res = err == SUCCESS;
if (!res) {
I2C_Unstick();
}
unlock();
return res;
}
bool FRToSI2C::Mem_Write(uint16_t DevAddress, uint16_t MemAddress, uint8_t *p_buffer, uint16_t number_of_byte) {
if (!lock()) {
return false;
}
I2C_Transfer_Cfg i2cCfg = {0, DISABLE, 0, 0, 0, 0};
BL_Err_Type err = ERROR;
i2cCfg.slaveAddr = DevAddress >> 1;
i2cCfg.stopEveryByte = DISABLE;
i2cCfg.subAddr = MemAddress;
i2cCfg.dataSize = number_of_byte;
i2cCfg.data = p_buffer;
i2cCfg.subAddrSize = 1; // one byte address
err = I2C_MasterSendBlocking(I2C0_ID, &i2cCfg);
bool res = err == SUCCESS;
if (!res) {
I2C_Unstick();
}
unlock();
return res;
}
bool FRToSI2C::Transmit(uint16_t DevAddress, uint8_t *pData, uint16_t Size) { return Mem_Write(DevAddress, pData[0], pData + 1, Size - 1); }
bool FRToSI2C::probe(uint16_t DevAddress) {
uint8_t temp[1];
return Mem_Read(DevAddress, 0x00, temp, sizeof(temp));
}
void FRToSI2C::I2C_Unstick() { unstick_I2C(); }
bool FRToSI2C::lock() {
if (I2CSemaphore == nullptr) {
return false;
}
return xSemaphoreTake(I2CSemaphore, TICKS_SECOND) == pdTRUE;
}
void FRToSI2C::unlock() { xSemaphoreGive(I2CSemaphore); }
bool FRToSI2C::writeRegistersBulk(const uint8_t address, const I2C_REG *registers, const uint8_t registersLength) {
for (int index = 0; index < registersLength; index++) {
if (!I2C_RegisterWrite(address, registers[index].reg, registers[index].val)) {
return false;
}
if (registers[index].pause_ms) {
delay_ms(registers[index].pause_ms);
}
}
return true;
}
bool FRToSI2C::wakePart(uint16_t DevAddress) {
// wakepart is a special case where only the device address is sent
if (!lock()) {
return false;
}
uint8_t temp[1] = {0};
I2C_Transfer_Cfg i2cCfg = {0, DISABLE, 0, 0, 0, 0};
BL_Err_Type err = ERROR;
i2cCfg.slaveAddr = DevAddress >> 1;
i2cCfg.stopEveryByte = DISABLE;
i2cCfg.subAddr = 0;
i2cCfg.dataSize = 1;
i2cCfg.data = temp;
i2cCfg.subAddrSize = 0;
err = I2C_MasterReceiveBlocking(I2C0_ID, &i2cCfg);
bool res = err == SUCCESS;
if (!res) {
I2C_Unstick();
}
unlock();
return res;
}

View File

@@ -0,0 +1,178 @@
/*
* IRQ.c
*
* Created on: 30 May 2020
* Author: Ralim
*/
#include "IRQ.h"
#include "Pins.h"
#include "configuration.h"
#include "history.hpp"
extern "C" {
#include "bflb_platform.h"
#include "bl702_adc.h"
#include "bl702_glb.h"
#include "bl702_pwm.h"
#include "bl702_timer.h"
}
#define ADC_Filter_Smooth 4
history<uint16_t, ADC_Filter_Smooth> ADC_Vin;
history<uint16_t, ADC_Filter_Smooth> ADC_Temp;
history<uint16_t, ADC_Filter_Smooth> ADC_Tip;
void adc_fifo_irq(void) {
if (ADC_GetIntStatus(ADC_INT_FIFO_READY) == SET) {
// Read out all entries in the fifo
while (ADC_Get_FIFO_Count()) {
volatile uint32_t reading = ADC_Read_FIFO();
// As per manual, 26 bit reading; lowest 16 are the ADC
uint16_t sample = reading & 0xFFFF;
uint8_t source = (reading >> 21) & 0b11111;
switch (source) {
case TMP36_ADC_CHANNEL:
ADC_Temp.update(sample);
break;
case TIP_TEMP_ADC_CHANNEL:
ADC_Tip.update(sample);
break;
case VIN_ADC_CHANNEL:
ADC_Vin.update(sample);
break;
default:
break;
}
}
// unblock the PID controller thread
if (xTaskGetSchedulerState() != taskSCHEDULER_NOT_STARTED) {
BaseType_t xHigherPriorityTaskWoken = pdFALSE;
if (pidTaskNotification) {
vTaskNotifyGiveFromISR(pidTaskNotification, &xHigherPriorityTaskWoken);
portYIELD_FROM_ISR(xHigherPriorityTaskWoken);
}
}
}
// Clear IRQ
ADC_IntClr(ADC_INT_ALL);
}
static bool fastPWM = false;
static void switchToFastPWM(void);
volatile uint16_t PWMSafetyTimer = 0;
volatile uint8_t pendingPWM = 0;
volatile bool lastPeriodWasFast = false;
// Timer 0 is used to co-ordinate the ADC and the output PWM
void timer0_comp0_callback(void) { ADC_Start(); }
void timer0_comp1_callback(void) { PWM_Channel_Disable(PWM_Channel); }
void timer0_comp2_callback(void) {
// This occurs at timer rollover, so if we want to turn on the output PWM; we do so
if (PWMSafetyTimer) {
PWMSafetyTimer--;
if (lastPeriodWasFast != fastPWM) {
if (fastPWM) {
switchToFastPWM();
} else {
switchToSlowPWM();
}
}
// Update trigger for the end point of the PWM cycle
if (pendingPWM > 0) {
TIMER_SetCompValue(TIMER_CH0, TIMER_COMP_ID_1, pendingPWM - 1);
// Turn on output
PWM_Channel_Enable(PWM_Channel);
} else {
// Leave output off
PWM_Channel_Disable(PWM_Channel);
}
} else {
PWM_Channel_Disable(PWM_Channel);
}
}
void switchToFastPWM(void) {
fastPWM = true;
totalPWM = powerPWM + tempMeasureTicks + holdoffTicks;
TIMER_SetCompValue(TIMER_CH0, TIMER_COMP_ID_2, totalPWM);
// ~10Hz
TIMER_SetCompValue(TIMER_CH0, TIMER_COMP_ID_0, powerPWM + holdoffTicks);
// Set divider to 11
uint32_t tmpVal = BL_RD_REG(TIMER_BASE, TIMER_TCDR);
tmpVal = BL_SET_REG_BITS_VAL(tmpVal, TIMER_TCDR2, 11);
BL_WR_REG(TIMER_BASE, TIMER_TCDR, tmpVal);
}
void switchToSlowPWM(void) {
// 5Hz
fastPWM = false;
totalPWM = powerPWM + tempMeasureTicks / 2 + holdoffTicks / 2;
TIMER_SetCompValue(TIMER_CH0, TIMER_COMP_ID_2, totalPWM);
// Adjust ADC
TIMER_SetCompValue(TIMER_CH0, TIMER_COMP_ID_0, powerPWM + (holdoffTicks / 2));
// Set divider to 22
uint32_t tmpVal = BL_RD_REG(TIMER_BASE, TIMER_TCDR);
tmpVal = BL_SET_REG_BITS_VAL(tmpVal, TIMER_TCDR2, 22);
BL_WR_REG(TIMER_BASE, TIMER_TCDR, tmpVal);
}
void setTipPWM(const uint8_t pulse, const bool shouldUseFastModePWM) {
PWMSafetyTimer = 10; // This is decremented in the handler for PWM so that the tip pwm is
// disabled if the PID task is not scheduled often enough.
pendingPWM = pulse;
fastPWM = shouldUseFastModePWM;
}
extern osThreadId POWTaskHandle;
void GPIO_IRQHandler(void) {
if (SET == GLB_Get_GPIO_IntStatus(FUSB302_IRQ_GLB_Pin)) {
GLB_GPIO_IntClear(FUSB302_IRQ_GLB_Pin, SET);
#if POW_PD
if (POWTaskHandle != nullptr) {
BaseType_t xHigherPriorityTaskWoken = pdFALSE;
xTaskNotifyFromISR(POWTaskHandle, 1, eSetBits, &xHigherPriorityTaskWoken);
/* Force a context switch if xHigherPriorityTaskWoken is now set to pdTRUE.
The macro used to do this is dependent on the port and may be called
portEND_SWITCHING_ISR. */
portYIELD_FROM_ISR(xHigherPriorityTaskWoken);
}
#endif
/* timeout check */
uint32_t timeOut = 32;
do {
timeOut--;
} while ((SET == GLB_Get_GPIO_IntStatus(FUSB302_IRQ_GLB_Pin)) && timeOut);
if (!timeOut) {
// MSG("WARNING: Clear GPIO interrupt status fail.\r\n");
}
GLB_GPIO_IntClear(FUSB302_IRQ_GLB_Pin, RESET);
}
}
bool getFUS302IRQLow() {
// Return true if the IRQ line is still held low
return !gpio_read(FUSB302_IRQ_Pin);
}
uint16_t getADCHandleTemp(uint8_t sample) { return ADC_Temp.average(); }
uint16_t getADCVin(uint8_t sample) { return ADC_Vin.average(); }
// Returns either average or instant value. When sample is set the samples from the injected ADC are copied to the filter and then the raw reading is returned
uint16_t getTipRawTemp(uint8_t sample) { return ADC_Tip.average() >> 1; }

View File

@@ -0,0 +1,28 @@
/*
* Irqs.h
*
* Created on: 30 May 2020
* Author: Ralim
*/
#ifndef BSP_PINE64_IRQ_H_
#define BSP_PINE64_IRQ_H_
#include "BSP.h"
#include "I2C_Wrapper.hpp"
#include "Setup.h"
#include "main.hpp"
#ifdef __cplusplus
extern "C" {
#endif
void timer0_comp0_callback(void);
void timer0_comp1_callback(void);
void timer0_comp2_callback(void);
void adc_fifo_irq(void);
void GPIO_IRQHandler(void);
void switchToSlowPWM(void);
#ifdef __cplusplus
}
#endif
#endif /* BSP_PINE64_IRQ_H_ */

View File

@@ -0,0 +1,38 @@
# Notes on RISC-V
## Pinmap
| Pin Number | Name | Function | Notes |
| ---------- | ---- | ---------------- | ----------- |
| 17 | PB2 | BOOT2 | Pulldown |
| 32 | | IMU INT 1 | N/A |
| 30 | | IMU INT 2 | N/A |
| | PA4 | Handle Temp | ADC Input ? |
| | PA1 | Tip Temp | ADC Input ? |
| | PB1 | B Button | Active High |
| | PB0 | A Button | Active High |
| | PA11 | USB D- | - |
| | PA12 | USB D+ | - |
| | PA6 | Tip PWM Out | - |
| | PA0 | Input DC V Sense | ADC Input ? |
| | PA9 | OLED Reset | |
| | PB7 | SDA | I2C0_SDA |
| | PB6 | SCL | I2C0_SCL |
## ADC Configuration
For now running in matching mode for TS100
- X channels DMA in background
- Sample tip using "Intereted" channels using TIMER 0,1,3 TRGO or timer0,1,2 channels
- Using just 12 bit mode for now and move to hardware oversampling later
- use DMA for normal samples and 4x16 bit regs for tip temp
- It has dual ADC's so run them in pair mode
## Timers
### Timer 2
Timer 2 CH0 is tip drive PWM out.
This is fixed at 50% duty cycle and used via the cap to turn on the heater tip.
This should toggle relatively quickly.

View File

@@ -0,0 +1,43 @@
/*
* Pins.h
*
* Created on: 29 May 2020
* Author: Ralim
*/
#ifndef BSP_PINE64_PINS_H_
#define BSP_PINE64_PINS_H_
#include "bl702_adc.h"
#include "hal_gpio.h"
#define KEY_B_Pin GPIO_PIN_28
#define TMP36_INPUT_Pin GPIO_PIN_20
#define TMP36_ADC_CHANNEL ADC_CHAN10
#define TIP_TEMP_Pin GPIO_PIN_19
#define TIP_TEMP_ADC_CHANNEL ADC_CHAN9
#define TIP_RESISTANCE_SENSE GPIO_PIN_24
#define VIN_Pin GPIO_PIN_18
#define VIN_ADC_CHANNEL ADC_CHAN8
#define OLED_RESET_Pin GPIO_PIN_3
#define KEY_A_Pin GPIO_PIN_25
#define PWM_Out_Pin GPIO_PIN_21
#define PWM_Channel PWM_CH1
#define SCL_Pin GPIO_PIN_11
#define SDA_Pin GPIO_PIN_10
#define USB_DM_Pin GPIO_PIN_8
#define QC_DP_LOW_Pin GPIO_PIN_5
// LOW = low resistance, HIGH = high resistance
#define QC_DM_LOW_Pin GPIO_PIN_4
#define QC_DM_HIGH_Pin GPIO_PIN_6
#define FUSB302_IRQ_Pin GPIO_PIN_16
#define FUSB302_IRQ_GLB_Pin GLB_GPIO_PIN_16
// uart
#define UART_TX_Pin GPIO_PIN_22
#define UART_RX_Pin GPIO_PIN_23
#endif /* BSP_PINE64_PINS_H_ */

View File

@@ -0,0 +1,40 @@
#include "BSP.h"
#include "BSP_Power.h"
#include "Pins.h"
#include "QC3.h"
#include "Settings.h"
#include "USBPD.h"
#include "configuration.h"
void power_check() {
#if POW_PD
// Cant start QC until either PD works or fails
if (!USBPowerDelivery::negotiationComplete()) {
return;
}
if (USBPowerDelivery::negotiationHasWorked()) {
return; // We are using PD
}
#endif
#ifdef POW_QC
QC_resync();
#endif
}
bool getIsPoweredByDCIN() {
#if POW_PD
if (!USBPowerDelivery::negotiationComplete()) {
return false; // We are assuming not dc while negotiating
}
if (USBPowerDelivery::negotiationHasWorked()) {
return false; // We are using PD
}
#endif
#ifdef POW_QC
if (hasQCNegotiated()) {
return false; // We are using QC
}
#endif
return true;
}

View File

@@ -0,0 +1,61 @@
/*
* QC.c
*
* Created on: 29 May 2020
* Author: Ralim
*/
#include "BSP.h"
#include "Pins.h"
#include "QC3.h"
#include "Settings.h"
#ifdef POW_QC
void QC_DPlusZero_Six() {
// pull down D+
gpio_write(QC_DP_LOW_Pin, 0);
}
void QC_DNegZero_Six() {
gpio_write(QC_DM_HIGH_Pin, 0);
gpio_write(QC_DM_LOW_Pin, 1);
}
void QC_DPlusThree_Three() {
// pull up D+
gpio_write(QC_DP_LOW_Pin, 1);
}
void QC_DNegThree_Three() {
gpio_write(QC_DM_LOW_Pin, 1);
gpio_write(QC_DM_HIGH_Pin, 1);
}
void QC_DM_PullDown() {
// Turn on pulldown on D-
gpio_set_mode(USB_DM_Pin, GPIO_INPUT_PD_MODE);
gpio_set_mode(QC_DM_LOW_Pin, GPIO_INPUT_PD_MODE);
gpio_set_mode(QC_DM_HIGH_Pin, GPIO_INPUT_PD_MODE);
}
void QC_DM_No_PullDown() {
// Turn off pulldown on d-
gpio_set_mode(USB_DM_Pin, GPIO_INPUT_MODE);
}
void QC_Init_GPIO() {
// Setup any GPIO into the right states for QC
// D+ pulldown as output
gpio_set_mode(QC_DP_LOW_Pin, GPIO_OUTPUT_MODE);
gpio_write(QC_DP_LOW_Pin, 0);
// Make two D- pins floating
gpio_set_mode(USB_DM_Pin, GPIO_INPUT_MODE);
gpio_set_mode(QC_DM_LOW_Pin, GPIO_INPUT_MODE);
gpio_set_mode(QC_DM_HIGH_Pin, GPIO_INPUT_MODE);
}
void QC_Post_Probe_En() {
// Make two D- pins outputs
gpio_set_mode(QC_DM_LOW_Pin, GPIO_OUTPUT_MODE);
gpio_set_mode(QC_DM_HIGH_Pin, GPIO_OUTPUT_MODE);
}
uint8_t QC_DM_PulledDown() { return gpio_read(USB_DM_Pin) == 0; }
#endif
void QC_resync() {
#ifdef POW_QC
seekQC(getSettingValue(SettingsOptions::QCIdealVoltage), getSettingValue(SettingsOptions::VoltageDiv)); // Run the QC seek again if we have drifted too much
#endif
}

View File

@@ -0,0 +1,3 @@
# BSP section for Pinecil v2
This folder contains the hardware abstractions required for the Pinecil V2. A RISC-V based soldering iron.

View File

@@ -0,0 +1,157 @@
/*
* Setup.c
*
* Created on: 29Aug.,2017
* Author: Ben V. Brown
*/
#include "Setup.h"
#include "BSP.h"
#include "Debug.h"
#include "FreeRTOSConfig.h"
#include "Pins.h"
#include "IRQ.h"
#include "history.hpp"
#include <string.h>
#define ADC_NORM_SAMPLES 16
#define ADC_FILTER_LEN 4
uint16_t ADCReadings[ADC_NORM_SAMPLES]; // room for 32 lots of the pair of readings
// Functions
void setup_timer_scheduler(void);
void setup_pwm(void);
void setup_adc(void);
void hardware_init() {
gpio_set_mode(OLED_RESET_Pin, GPIO_OUTPUT_MODE);
gpio_set_mode(KEY_A_Pin, GPIO_INPUT_PD_MODE);
gpio_set_mode(KEY_B_Pin, GPIO_INPUT_PD_MODE);
gpio_set_mode(TMP36_INPUT_Pin, GPIO_INPUT_MODE);
gpio_set_mode(TIP_TEMP_Pin, GPIO_INPUT_MODE);
gpio_set_mode(VIN_Pin, GPIO_INPUT_MODE);
gpio_set_mode(TIP_RESISTANCE_SENSE, GPIO_OUTPUT_MODE);
gpio_write(TIP_RESISTANCE_SENSE, 0);
MSG((char *)"Pine64 Pinecilv2 Starting\r\n");
setup_timer_scheduler();
setup_adc();
setup_pwm();
I2C_ClockSet(I2C0_ID, 200000); // Sets clock to around 175kHz
TIMER_SetCompValue(TIMER_CH0, TIMER_COMP_ID_1, 0);
}
void setup_pwm(void) {
// Setup PWM we use for driving the tip
PWM_CH_CFG_Type cfg = {
PWM_Channel, // channel
PWM_CLK_XCLK, // Clock
PWM_STOP_ABRUPT, // Stop mode
PWM_POL_NORMAL, // Normal Polarity
60, // Clock Div
100, // Period
0, // Thres 1 - start at beginng
50, // Thres 2 - turn off at 50%
0, // Interrupt pulse count
};
PWM_Channel_Init(&cfg);
PWM_Channel_Disable(PWM_Channel);
}
const ADC_Chan_Type adc_tip_pos_chans[]
= {TIP_TEMP_ADC_CHANNEL, TMP36_ADC_CHANNEL, TIP_TEMP_ADC_CHANNEL, VIN_ADC_CHANNEL, TIP_TEMP_ADC_CHANNEL, TMP36_ADC_CHANNEL, TIP_TEMP_ADC_CHANNEL, VIN_ADC_CHANNEL};
const ADC_Chan_Type adc_tip_neg_chans[] = {ADC_CHAN_GND, ADC_CHAN_GND, ADC_CHAN_GND, ADC_CHAN_GND, ADC_CHAN_GND, ADC_CHAN_GND, ADC_CHAN_GND, ADC_CHAN_GND};
static_assert(sizeof(adc_tip_pos_chans) == sizeof(adc_tip_neg_chans));
void setup_adc(void) {
//
ADC_CFG_Type adc_cfg = {};
ADC_FIFO_Cfg_Type adc_fifo_cfg = {};
CPU_Interrupt_Disable(GPADC_DMA_IRQn);
ADC_IntMask(ADC_INT_ALL, MASK);
adc_cfg.clkDiv = ADC_CLK_DIV_4;
adc_cfg.vref = ADC_VREF_3P2V;
adc_cfg.resWidth = ADC_DATA_WIDTH_14_WITH_64_AVERAGE;
adc_cfg.inputMode = ADC_INPUT_SINGLE_END;
adc_cfg.v18Sel = ADC_V18_SEL_1P72V;
adc_cfg.v11Sel = ADC_V11_SEL_1P1V;
adc_cfg.gain1 = ADC_PGA_GAIN_NONE;
adc_cfg.gain2 = ADC_PGA_GAIN_NONE;
adc_cfg.chopMode = ADC_CHOP_MOD_AZ_ON;
adc_cfg.biasSel = ADC_BIAS_SEL_MAIN_BANDGAP;
adc_cfg.vcm = ADC_PGA_VCM_1P6V;
adc_cfg.offsetCalibEn = ENABLE;
adc_cfg.offsetCalibVal = 0;
ADC_Disable();
ADC_Enable();
ADC_Reset();
ADC_Init(&adc_cfg);
adc_fifo_cfg.dmaEn = DISABLE;
adc_fifo_cfg.fifoThreshold = ADC_FIFO_THRESHOLD_8;
ADC_FIFO_Cfg(&adc_fifo_cfg);
ADC_MIC_Bias_Disable();
ADC_Tsen_Disable();
// Enable FiFo IRQ
Interrupt_Handler_Register(GPADC_DMA_IRQn, adc_fifo_irq);
ADC_IntMask(ADC_INT_FIFO_READY, UNMASK);
CPU_Interrupt_Enable(GPADC_DMA_IRQn);
ADC_Stop();
ADC_FIFO_Clear();
ADC_Scan_Channel_Config(adc_tip_pos_chans, adc_tip_neg_chans, sizeof(adc_tip_pos_chans) / sizeof(ADC_Chan_Type), DISABLE);
}
void setup_timer_scheduler() {
TIMER_Disable(TIMER_CH0);
TIMER_CFG_Type cfg = {
TIMER_CH0, // Channel
TIMER_CLKSRC_32K, // Clock source
TIMER_PRELOAD_TRIG_COMP2, // Trigger
TIMER_COUNT_PRELOAD, // Counter mode
22, // Clock div
(uint16_t)(powerPWM + holdoffTicks), // CH0 compare (adc)
0, // CH1 compare (pwm out)
(uint16_t)(powerPWM + tempMeasureTicks + holdoffTicks), // CH2 comapre (total period)
0, // Preload
};
TIMER_Init(&cfg);
Timer_Int_Callback_Install(TIMER_CH0, TIMER_INT_COMP_0, timer0_comp0_callback);
Timer_Int_Callback_Install(TIMER_CH0, TIMER_INT_COMP_1, timer0_comp1_callback);
Timer_Int_Callback_Install(TIMER_CH0, TIMER_INT_COMP_2, timer0_comp2_callback);
TIMER_ClearIntStatus(TIMER_CH0, TIMER_COMP_ID_0);
TIMER_ClearIntStatus(TIMER_CH0, TIMER_COMP_ID_1);
TIMER_ClearIntStatus(TIMER_CH0, TIMER_COMP_ID_2);
TIMER_IntMask(TIMER_CH0, TIMER_INT_COMP_0, UNMASK);
TIMER_IntMask(TIMER_CH0, TIMER_INT_COMP_1, UNMASK);
TIMER_IntMask(TIMER_CH0, TIMER_INT_COMP_2, UNMASK);
CPU_Interrupt_Enable(TIMER_CH0_IRQn);
TIMER_Enable(TIMER_CH0);
// switchToSlowPWM();
}
void setupFUSBIRQ() {
gpio_set_mode(FUSB302_IRQ_Pin, GPIO_SYNC_FALLING_TRIGER_INT_MODE);
CPU_Interrupt_Disable(GPIO_INT0_IRQn);
Interrupt_Handler_Register(GPIO_INT0_IRQn, GPIO_IRQHandler);
CPU_Interrupt_Enable(GPIO_INT0_IRQn);
gpio_irq_enable(FUSB302_IRQ_Pin, ENABLE);
}
void vAssertCalled(void) {
MSG((char *)"vAssertCalled\r\n");
PWM_Channel_Disable(PWM_Channel);
gpio_set_mode(PWM_Out_Pin, GPIO_INPUT_PD_MODE);
while (1)
;
}

View File

@@ -0,0 +1,35 @@
/*
* Setup.h
*
* Created on: 29Aug.,2017
* Author: Ben V. Brown
*/
#ifndef PINE_SETUP_H_
#define PINE_SETUP_H_
#include <stdint.h>
extern "C" {
#include "bflb_platform.h"
#include "bl702_adc.h"
#include "bl702_common.h"
#include "bl702_glb.h"
#include "bl702_i2c.h"
#include "bl702_pwm.h"
#include "bl702_timer.h"
#include "hal_adc.h"
}
#ifdef __cplusplus
extern "C" {
#endif
uint16_t getADC(uint8_t channel);
void hardware_init();
uint16_t getADCHandleTemp(uint8_t sample);
uint16_t getADCVin(uint8_t sample);
#ifdef __cplusplus
}
#endif
void setupFUSBIRQ();
extern const uint8_t holdoffTicks;
extern const uint8_t tempMeasureTicks;
#endif /* PINE_SETUP_H_ */

View File

@@ -0,0 +1,72 @@
/*
* ThermoModel.cpp
*
* Created on: 1 May 2021
* Author: Ralim
*/
#include "TipThermoModel.h"
#include "Utils.h"
#include "configuration.h"
#ifdef TEMP_uV_LOOKUP_HAKKO
const int32_t uVtoDegC[] = {
//
// uv -> temp in C
0, 0, //
266, 10, //
522, 20, //
770, 30, //
1010, 40, //
1244, 50, //
1473, 60, //
1697, 70, //
1917, 80, //
2135, 90, //
2351, 100, //
2566, 110, //
2780, 120, //
2994, 130, //
3209, 140, //
3426, 150, //
3644, 160, //
3865, 170, //
4088, 180, //
4314, 190, //
4544, 200, //
4777, 210, //
5014, 220, //
5255, 230, //
5500, 240, //
5750, 250, //
6003, 260, //
6261, 270, //
6523, 280, //
6789, 290, //
7059, 300, //
7332, 310, //
7609, 320, //
7889, 330, //
8171, 340, //
8456, 350, //
8742, 360, //
9030, 370, //
9319, 380, //
9607, 390, //
9896, 400, //
10183, 410, //
10468, 420, //
10750, 430, //
11029, 440, //
11304, 450, //
11573, 460, //
11835, 470, //
12091, 480, //
12337, 490, //
12575, 500, //
};
#endif
const int uVtoDegCItems = sizeof(uVtoDegC) / (2 * sizeof(int32_t));
uint32_t TipThermoModel::convertuVToDegC(uint32_t tipuVDelta) { return Utils::InterpolateLookupTable(uVtoDegC, uVtoDegCItems, tipuVDelta); }

View File

@@ -0,0 +1,11 @@
/*
* UnitSettings.h
*
* Created on: 29 May 2020
* Author: Ralim
*/
#ifndef BSP_MAGIC_UNITSETTINGS_H_
#define BSP_MAGIC_UNITSETTINGS_H_
#endif /* BSP_MAGIC_UNITSETTINGS_H_ */

View File

@@ -0,0 +1,31 @@
/**
* @file bl602_config.h
* @brief
*
* Copyright (c) 2021 Bouffalolab team
*
* Licensed to the Apache Software Foundation (ASF) under one or more
* contributor license agreements. See the NOTICE file distributed with
* this work for additional information regarding copyright ownership. The
* ASF licenses this file to you under the Apache License, Version 2.0 (the
* "License"); you may not use this file except in compliance with the
* License. You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
* License for the specific language governing permissions and limitations
* under the License.
*
*/
#ifndef __BL702_CONFIG_H__
#define __BL702_CONFIG_H__
#include "clock_config.h"
#include "peripheral_config.h"
#include "pinmux_config.h"
#endif

View File

@@ -0,0 +1,202 @@
Apache License
Version 2.0, January 2004
http://www.apache.org/licenses/
TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION
1. Definitions.
"License" shall mean the terms and conditions for use, reproduction,
and distribution as defined by Sections 1 through 9 of this document.
"Licensor" shall mean the copyright owner or entity authorized by
the copyright owner that is granting the License.
"Legal Entity" shall mean the union of the acting entity and all
other entities that control, are controlled by, or are under common
control with that entity. For the purposes of this definition,
"control" means (i) the power, direct or indirect, to cause the
direction or management of such entity, whether by contract or
otherwise, or (ii) ownership of fifty percent (50%) or more of the
outstanding shares, or (iii) beneficial ownership of such entity.
"You" (or "Your") shall mean an individual or Legal Entity
exercising permissions granted by this License.
"Source" form shall mean the preferred form for making modifications,
including but not limited to software source code, documentation
source, and configuration files.
"Object" form shall mean any form resulting from mechanical
transformation or translation of a Source form, including but
not limited to compiled object code, generated documentation,
and conversions to other media types.
"Work" shall mean the work of authorship, whether in Source or
Object form, made available under the License, as indicated by a
copyright notice that is included in or attached to the work
(an example is provided in the Appendix below).
"Derivative Works" shall mean any work, whether in Source or Object
form, that is based on (or derived from) the Work and for which the
editorial revisions, annotations, elaborations, or other modifications
represent, as a whole, an original work of authorship. For the purposes
of this License, Derivative Works shall not include works that remain
separable from, or merely link (or bind by name) to the interfaces of,
the Work and Derivative Works thereof.
"Contribution" shall mean any work of authorship, including
the original version of the Work and any modifications or additions
to that Work or Derivative Works thereof, that is intentionally
submitted to Licensor for inclusion in the Work by the copyright owner
or by an individual or Legal Entity authorized to submit on behalf of
the copyright owner. For the purposes of this definition, "submitted"
means any form of electronic, verbal, or written communication sent
to the Licensor or its representatives, including but not limited to
communication on electronic mailing lists, source code control systems,
and issue tracking systems that are managed by, or on behalf of, the
Licensor for the purpose of discussing and improving the Work, but
excluding communication that is conspicuously marked or otherwise
designated in writing by the copyright owner as "Not a Contribution."
"Contributor" shall mean Licensor and any individual or Legal Entity
on behalf of whom a Contribution has been received by Licensor and
subsequently incorporated within the Work.
2. Grant of Copyright License. Subject to the terms and conditions of
this License, each Contributor hereby grants to You a perpetual,
worldwide, non-exclusive, no-charge, royalty-free, irrevocable
copyright license to reproduce, prepare Derivative Works of,
publicly display, publicly perform, sublicense, and distribute the
Work and such Derivative Works in Source or Object form.
3. Grant of Patent License. Subject to the terms and conditions of
this License, each Contributor hereby grants to You a perpetual,
worldwide, non-exclusive, no-charge, royalty-free, irrevocable
(except as stated in this section) patent license to make, have made,
use, offer to sell, sell, import, and otherwise transfer the Work,
where such license applies only to those patent claims licensable
by such Contributor that are necessarily infringed by their
Contribution(s) alone or by combination of their Contribution(s)
with the Work to which such Contribution(s) was submitted. If You
institute patent litigation against any entity (including a
cross-claim or counterclaim in a lawsuit) alleging that the Work
or a Contribution incorporated within the Work constitutes direct
or contributory patent infringement, then any patent licenses
granted to You under this License for that Work shall terminate
as of the date such litigation is filed.
4. Redistribution. You may reproduce and distribute copies of the
Work or Derivative Works thereof in any medium, with or without
modifications, and in Source or Object form, provided that You
meet the following conditions:
(a) You must give any other recipients of the Work or
Derivative Works a copy of this License; and
(b) You must cause any modified files to carry prominent notices
stating that You changed the files; and
(c) You must retain, in the Source form of any Derivative Works
that You distribute, all copyright, patent, trademark, and
attribution notices from the Source form of the Work,
excluding those notices that do not pertain to any part of
the Derivative Works; and
(d) If the Work includes a "NOTICE" text file as part of its
distribution, then any Derivative Works that You distribute must
include a readable copy of the attribution notices contained
within such NOTICE file, excluding those notices that do not
pertain to any part of the Derivative Works, in at least one
of the following places: within a NOTICE text file distributed
as part of the Derivative Works; within the Source form or
documentation, if provided along with the Derivative Works; or,
within a display generated by the Derivative Works, if and
wherever such third-party notices normally appear. The contents
of the NOTICE file are for informational purposes only and
do not modify the License. You may add Your own attribution
notices within Derivative Works that You distribute, alongside
or as an addendum to the NOTICE text from the Work, provided
that such additional attribution notices cannot be construed
as modifying the License.
You may add Your own copyright statement to Your modifications and
may provide additional or different license terms and conditions
for use, reproduction, or distribution of Your modifications, or
for any such Derivative Works as a whole, provided Your use,
reproduction, and distribution of the Work otherwise complies with
the conditions stated in this License.
5. Submission of Contributions. Unless You explicitly state otherwise,
any Contribution intentionally submitted for inclusion in the Work
by You to the Licensor shall be under the terms and conditions of
this License, without any additional terms or conditions.
Notwithstanding the above, nothing herein shall supersede or modify
the terms of any separate license agreement you may have executed
with Licensor regarding such Contributions.
6. Trademarks. This License does not grant permission to use the trade
names, trademarks, service marks, or product names of the Licensor,
except as required for reasonable and customary use in describing the
origin of the Work and reproducing the content of the NOTICE file.
7. Disclaimer of Warranty. Unless required by applicable law or
agreed to in writing, Licensor provides the Work (and each
Contributor provides its Contributions) on an "AS IS" BASIS,
WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or
implied, including, without limitation, any warranties or conditions
of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A
PARTICULAR PURPOSE. You are solely responsible for determining the
appropriateness of using or redistributing the Work and assume any
risks associated with Your exercise of permissions under this License.
8. Limitation of Liability. In no event and under no legal theory,
whether in tort (including negligence), contract, or otherwise,
unless required by applicable law (such as deliberate and grossly
negligent acts) or agreed to in writing, shall any Contributor be
liable to You for damages, including any direct, indirect, special,
incidental, or consequential damages of any character arising as a
result of this License or out of the use or inability to use the
Work (including but not limited to damages for loss of goodwill,
work stoppage, computer failure or malfunction, or any and all
other commercial damages or losses), even if such Contributor
has been advised of the possibility of such damages.
9. Accepting Warranty or Additional Liability. While redistributing
the Work or Derivative Works thereof, You may choose to offer,
and charge a fee for, acceptance of support, warranty, indemnity,
or other liability obligations and/or rights consistent with this
License. However, in accepting such obligations, You may act only
on Your own behalf and on Your sole responsibility, not on behalf
of any other Contributor, and only if You agree to indemnify,
defend, and hold each Contributor harmless for any liability
incurred by, or claims asserted against, such Contributor by reason
of your accepting any such warranty or additional liability.
END OF TERMS AND CONDITIONS
APPENDIX: How to apply the Apache License to your work.
To apply the Apache License to your work, attach the following
boilerplate notice, with the fields enclosed by brackets "[]"
replaced with your own identifying information. (Don't include
the brackets!) The text should be enclosed in the appropriate
comment syntax for the file format. We also recommend that a
file or class name and description of purpose be included on the
same "printed page" as the copyright notice for easier
identification within third-party archives.
Copyright [2020] [BOUFFALO LAB (NANJING) CO., LTD.]
Licensed under the Apache License, Version 2.0 (the "License");
you may not use this file except in compliance with the License.
You may obtain a copy of the License at
http://www.apache.org/licenses/LICENSE-2.0
Unless required by applicable law or agreed to in writing, software
distributed under the License is distributed on an "AS IS" BASIS,
WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
See the License for the specific language governing permissions and
limitations under the License.

View File

@@ -0,0 +1,235 @@
bl mcu sdk Release Notes
----------------------------
此文件包含 bl mcu sdk 软件开发包的发行说明。
每个版本的文字说明与发布时的说明保持一致(可能会有错别字的勘误)。
bl mcu sdk Release V1.4.2
----------------------------
新增功能说明:
1. 重构 dac、dma 驱动,更新 dac、dma doc
2. 新增 arch_ffsll、arch_ctzll、arch_clzll 等函数
3. 优化 usb 协议栈 log 信息msc 新增 sense code for requestSense command
修复问题说明:
1. 补充完整 xxx_close 函数,复位相关寄存器
2. 删除 drivers 下头文件部分依赖
3. 优化 usb 驱动中 端点0 设置 ack 的位置(放置中断中),防止重复设置。
bl mcu sdk Release V1.4.1
----------------------------
新增功能说明:
1. 新增 aes、ble pds31、freertos tickless、audio cube demo
2. 新增 usb 同步传输中断方式
3. 新增 lwip 组件以及对应 emac demo
4. 新增 pds31 快速唤醒功能
5. 文档更新包含flash、usb、fatfs、pm、emac、ble
修复问题说明:
1. pwm demo 文档中分频值修正
2. 修正 mtimer 获取 div 函数
3. 修正 dma 链表配置,当传输长度为 4095 时会配置错误,优化 if 判断
4. switch 禁用跳表选项 C flag 中添加 -fno-jump-tables
5. 部分 cdk 工程增加 syscall.c对系统函数重定向否则会进 M mode 异常
6. 修正 gpio func macro value该值对配置 gpio 为 uart 时会有问题,出现覆盖问题
7. 补全 calloc 函数,浮点打印会使用
8. 从驱动库文件移除 bflb_platform.h 文件,减少只使用 std drv 时的依赖项
bl mcu sdk Release V1.4.0
----------------------------
新增功能说明:
1. 新增 mbedtls、rt-thread、nmsis 组件,新增 rt-thread msh、mfcc、nn、dsp demo
2. 新增 flash 模拟u盘升级、 c++、adc 中断读取、boot2 usb iap、prng demo
3. 修改 makefile 调用 cmake 执行命令
4. usb 协议栈新增 usb hs 功能
5. freertos 新增 tickless 功能
6. 重构芯片驱动的公用头文件包含、删除 flash 的相关 api
7. cdk 工程源文件更新
8. fatfs port接口新增 flash 读写usb msc中可以使用
9. 使能所有外设的 BSP_USING_XXX 宏
10. ble 新增 oad 功能,带加密功能
11. mmheap 组件更新,链表式的内存管理减少了 ram 的使用,但是会增加 malloc 和 free 时间
修复问题说明:
1. 修复 ble 在 pc上连接失败的问题修改 capcode 可以解决
2. fatfs 中 FS_MAX_SS 参数需要适配其他种类的扇区,修复多个驱动注册到 fatfs 时,参数覆盖的 bug
3. bl706_avb 文件删除其他 demo 的 pinmux只留 camera + lcd 的配置,同理 bl706_iot 文件只留 i2s + usb + adc + pwm 配置
4. 修正 adc_read 函数,只读取了一个 fifo 数值,影响 adc 采样效率
5. 修正 usb_dc_ep_set_stall 在 端点 stall 时没有开启下一次的端点接收的问题
bl mcu sdk Release V1.3.0
----------------------------
新增功能说明:
1. 新增 acomp、rtc、boot2、wdt、pm hal driver 和 demo
2. 新增 romfs demo、usb 麦克风和扬声器双声道 demo、带 tinyjpeg 组件的 spi lcd 显示 demo
3. 重构 boot2_iap demo统一接口
4. 使能 romapi减少 codesize
5. 新增 flash 自动识别和配置功能,适配不同的 flash 芯片
6. 重构 mcu lcd 驱动层,适配多种 mcu lcd 驱动
7. 新增 ssd1306 spi 和 i2c 驱动,新增 ws2812 、wm8978 驱动
8. shell 新增颜色显示和自定义打印接口(使用各种终端工具可以查看)
9. bl602 和 bl702 驱动库相关更新
10. 新增外部 cmake 工程编译方式,从而让 sdk 作为 submodule 使用
11. ld 文件的更新
12. ble lib 文件更新(需要使用最新的 toolchainsifive才能编译 ble demo
修复问题说明:
1. 修复 eclipse openocd 调试时openocd 版本太低导致无法调试
2. case 运行异常时,需要添加死循环
3. 驱动库的一些 bug fix
4. 开关外设中断的重名名
5. fix 重复定义的宏带来的 warning
bl mcu sdk Release V1.2.6
----------------------------
新增功能说明:
1. 重构 board 系统目录结构
2. 删除 SUPPORT_XXX 功能,改成 cmake 自动识别组件库并参与编译,识别参数为 TARGET_REQUIRED_LIBS
3. 删除 device_register 中 flag 选项
4. 重构 timer hal 层, clock tree 和 demo
5. 添加 自动识别内外部 flash 并切换引脚功能
6. 添加 2线 flash 下载支持
7. 默认使能 cpu 浮点支持(非打印浮点支持)
8. 添加 bl702 qfn32 的 board 文件
9. 添加 boot2 hal 封装层
10. 添加 pid 算法
11. 添加 qdec hal 和 demo
修复问题说明:
1. 修复 开关全局中断嵌套带来的问题
2. 修复 使用 shell 功能时编译报错
3. memcpy 改用 romapi
4. 修复 cdk 中编译 ble demo 编译报错,未添加 board 支持
5. 修复 pwm demo 相关宏书写错误
6. 修复 std 和 hal 中 switch case 返回的一些 bug
7. cdk 相关 demo 改用 bl706_iot board
8. 修改 keyscan 默认时钟和分频
bl mcu sdk Release V1.2.5
----------------------------
新增功能说明:
1. 添加 tensorflow lite 支持
2. gpio_set_mode 添加高阻模式
3. 添加 keyscan hal 驱动
4. 新增 shell 文件系统
5. 更新 clock tree 宏定义、更新 board.c 中 pinmux 初始化配置
6. es8388 驱动增加双通道支持
7. il9341 增加字库,支持大字号显示
修复问题说明:
1. 修复 usb msc 中 interface num 为 0
2. 修复 uart 和 spi 开关 dma 时未设置 oflag 状态
3. 修改 CPU_ID 默认值,当不使用多核时默认为 none
4. 修复 adc 浮点输出问题
5. 修复 hal pwm 相关宏书写错误
bl mcu sdk Release V1.2.4
----------------------------
新增功能说明:
1. 增加部分 math 库函数对 arm dsp api 的兼容,以及优化 math 库效率
2. 增加 bl702 adc、camera 中断,重定义 clock tree 的相关宏,
3. 删除 GPIO32-GPIO37更新 GPIO 初始化和读写函数,更新 sf flash 引脚初始化
4. 增加 i2s 双通道支持
5. 增加 adc、pwm、camera 相关 api
6. 增加 camera pingpong buffer case
7. cdk 工程更新
8. 更新 openocd cfg 文件,适配 openocd 0.11 版本
修复问题说明:
1. 对 pwm readme 说明修改
2. 修复 hal_usb 中对端点 0 状态的判断逻辑
3. 修复 flash 擦除扇区时多擦除扇区的问题
4. ble、lvgl、usb、boot2iap、adc 相关 demo 的修改
bl mcu sdk Release V1.2.3
----------------------------
新增功能说明:
1. 增加 case 输出成功和失败的 log 提示
2. 更新 cdk 工程,使用 minilibc 替代本地 libc
3. 更新 usb api 及其他文档说明
修复问题说明:
1. 修改 bl702_flash.ld 文件中 ram 的实际大小
2. 修复 main 函数返回时一直重入的问题
3. 删除 hal driver 中不需要的内容
4. 修复 cdk 工程中编译 camera case 存在的问题
bl mcu sdk Release V1.2.2
----------------------------
新增功能说明:
1. 新增 pwm 驱动 dc motor 和 step motor、dht11、custom hid 、shell demo
2. 为所有的 examples 添加 cdk 工程
3. 为 cdk 工程添加 openocd 支持
4. 更新文档
5. 使用 clang-format 格式化代码
修复问题说明:
1. 修复 __riscv_float_abi_single 未定义带来的 warning
2. 修改 bl702_flash.ld 中 heap 的 分配方式
3. 更新 shell 组件,添加使用时删除中间字符的功能
bl mcu sdk Release V1.2.1
----------------------------
新增功能说明:
1. 新增 readme for demo command line build
2. 更新 cmake 运行顺序
3. 更新 cdk flashloader 和 openocd cfg
4. 更新文档
修复问题说明:
1. 修复 board.c 中 ADC 的引脚初始化
2. 修复 ble 静态库依赖问题
bl mcu sdk Release V1.2.0
----------------------------
新增功能说明:
1. 新增 xz、ble 组件
2. usb_stack 中新增 usb video、hid、audio 驱动
3. 新增 bl602 driver 和 bl602_iot board
4. 为 examples 补全 cdk 工程
5. 新增 ble、psram、camera、boot2_iap、emac、usb_video、usb_audio、usb_hid、gpio_int、pwm_it、flash读写、lowpower、pka、systick、timer demo
6. 更新 flash Tools
7. 更新 cmake 文件
8. 更新 mtimer 时钟频率为1M便于计算
9. 文档更新
修复问题说明:
1. 修复若干已知问题
bl mcu sdk Release V1.1.0
----------------------------
新增功能说明:
1. 新增 lvgl 组件以及基本 demo
2. 新增 freertos 702 port 以及基本 demo
3. 新增 usb 转串口标准驱动 demo支持博流自定义 DTR、RTS 流控协议;
4. 文件系统添加命令行功能;
5. hal 层添加强转宏,从而用户可以在程序内修改;
修复问题说明:
1. 修正 usb 设备描述符初始化宏,添加协议类代码初始化;
2. 修复 hal 层驱动。
bl mcu sdk Release V1.0.0
----------------------------
初始化项目。该项目基于 cmake 构建,包含 bl702/bl704/bl706 系列 mcu 底层驱动、基本外设例程、common 驱动以及第三方组件。
支持 bl706_avb、bl706_iot 开发板的开发工作;
该项目也支持使用 CDK、eclipse 编译、烧写、调试代码;
该项目中还包含烧录工具、调试脚本、flash 算法文件以及构建 cmake 需要的一些工具。

View File

@@ -0,0 +1,267 @@
/**
* @file bflb_platform.c
* @brief
*
* Copyright (c) 2021 Bouffalolab team
*
* Licensed to the Apache Software Foundation (ASF) under one or more
* contributor license agreements. See the NOTICE file distributed with
* this work for additional information regarding copyright ownership. The
* ASF licenses this file to you under the Apache License, Version 2.0 (the
* "License"); you may not use this file except in compliance with the
* License. You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
* License for the specific language governing permissions and limitations
* under the License.
*
*/
#include "bflb_platform.h"
#include "hal_common.h"
#include "hal_flash.h"
#include "hal_mtimer.h"
#include "hal_uart.h"
#include "ring_buffer.h"
extern uint32_t __HeapBase;
extern uint32_t __HeapLimit;
static uint8_t uart_dbg_disable = 0;
// struct heap_info mmheap_root;
__WEAK__ void board_init(void) {}
__WEAK__ enum uart_index_type board_get_debug_uart_index(void) { return 0; }
void bl_show_flashinfo(void) {
SPI_Flash_Cfg_Type flashCfg;
uint8_t *pFlashCfg = NULL;
uint32_t flashCfgLen = 0;
uint32_t flashJedecId = 0;
flashJedecId = flash_get_jedecid();
flash_get_cfg(&pFlashCfg, &flashCfgLen);
arch_memcpy((void *)&flashCfg, pFlashCfg, flashCfgLen);
MSG("show flash cfg:\r\n");
MSG("jedec id 0x%06X\r\n", flashJedecId);
MSG("mid 0x%02X\r\n", flashCfg.mid);
MSG("iomode 0x%02X\r\n", flashCfg.ioMode);
MSG("clk delay 0x%02X\r\n", flashCfg.clkDelay);
MSG("clk invert 0x%02X\r\n", flashCfg.clkInvert);
MSG("read reg cmd0 0x%02X\r\n", flashCfg.readRegCmd[0]);
MSG("read reg cmd1 0x%02X\r\n", flashCfg.readRegCmd[1]);
MSG("write reg cmd0 0x%02X\r\n", flashCfg.writeRegCmd[0]);
MSG("write reg cmd1 0x%02X\r\n", flashCfg.writeRegCmd[1]);
MSG("qe write len 0x%02X\r\n", flashCfg.qeWriteRegLen);
MSG("cread support 0x%02X\r\n", flashCfg.cReadSupport);
MSG("cread code 0x%02X\r\n", flashCfg.cReadMode);
MSG("burst wrap cmd 0x%02X\r\n", flashCfg.burstWrapCmd);
MSG("-------------------\r\n");
}
void bflb_platform_init(uint32_t baudrate) {
// static uint8_t initialized = 0;
BL_Err_Type ret = ERROR;
cpu_global_irq_disable();
ret = flash_init();
if (ret != SUCCESS) {
MSG("flash init fail!!!\r\n");
}
board_init();
if (!uart_dbg_disable) {
uart_register(board_get_debug_uart_index(), "debug_log");
struct device *uart = device_find("debug_log");
if (uart) {
device_open(uart, DEVICE_OFLAG_STREAM_TX | DEVICE_OFLAG_INT_RX);
device_set_callback(uart, NULL);
device_control(uart, DEVICE_CTRL_CLR_INT, (void *)(UART_RX_FIFO_IT));
}
}
static bool initialized = false;
if (!initialized) {
// system_mmheap[0].addr = (uint8_t *)&__HeapBase;
// system_mmheap[0].mem_size = ((size_t)&__HeapLimit - (size_t)&__HeapBase);
// if (system_mmheap[0].mem_size > 0) {
// mmheap_init(&mmheap_root, system_mmheap);
// }
// MSG("dynamic memory init success,heap size = %d Kbyte \r\n", system_mmheap[0].mem_size / 1024);
initialized = 1;
if (ret != SUCCESS) {
MSG("flash init fail!!!\r\n");
}
bl_show_flashinfo();
}
MSG("Enable IRQ's\r\n");
cpu_global_irq_enable();
}
#if ((defined BOOTROM) || (defined BFLB_EFLASH_LOADER))
static uint8_t eflash_loader_logbuf[1024] __attribute__((section(".system_ram_noinit")));
static uint32_t log_len = 0;
uint32_t bflb_platform_get_log(uint8_t *data, uint32_t maxlen) {
uint32_t len = log_len;
if (len > maxlen) {
len = maxlen;
}
memcpy(data, eflash_loader_logbuf, len);
return len;
}
#endif
void bflb_platform_printf(char *fmt, ...) {
struct device *uart;
char print_buf[128];
va_list ap;
if (!uart_dbg_disable) {
va_start(ap, fmt);
vsnprintf(print_buf, sizeof(print_buf) - 1, fmt, ap);
va_end(ap);
#if ((defined BOOTROM) || (defined BFLB_EFLASH_LOADER))
uint32_t len = strlen(print_buf);
if (log_len + len < sizeof(eflash_loader_logbuf)) {
memcpy(eflash_loader_logbuf + log_len, print_buf, len);
log_len += len;
}
#endif
uart = device_find("debug_log");
device_write(uart, 0, (uint8_t *)print_buf, strlen(print_buf));
}
}
void bflb_platform_print_set(uint8_t disable) { uart_dbg_disable = disable; }
uint8_t bflb_platform_print_get(void) { return uart_dbg_disable; }
void bflb_platform_deinit(void) {
if (!uart_dbg_disable) {
struct device *uart = device_find("debug_log");
if (uart) {
device_close(uart);
device_unregister("debug_log");
}
}
}
void bflb_platform_dump(uint8_t *data, uint32_t len) {
uint32_t i = 0;
if (!uart_dbg_disable) {
for (i = 0; i < len; i++) {
if (i % 16 == 0) {
bflb_platform_printf("\r\n");
}
bflb_platform_printf("%02x ", data[i]);
}
bflb_platform_printf("\r\n");
}
}
void bflb_platform_reg_dump(uint32_t addr) { bflb_platform_printf("%08x[31:0]=%08x\r\n", addr, *(volatile uint32_t *)(addr)); }
void bflb_platform_init_time() {}
void bflb_platform_deinit_time() {}
void bflb_platform_set_alarm_time(uint64_t time, void (*interruptFun)(void)) { mtimer_set_alarm_time(time, interruptFun); }
void bflb_platform_clear_time() {}
void bflb_platform_start_time() {}
void bflb_platform_stop_time() {}
uint64_t bflb_platform_get_time_ms() { return mtimer_get_time_ms(); }
uint64_t bflb_platform_get_time_us() { return mtimer_get_time_us(); }
void bflb_platform_delay_ms(uint32_t ms) { mtimer_delay_ms(ms); }
void bflb_platform_delay_us(uint32_t us) { mtimer_delay_us(us); }
void bflb_print_device_list(void) {
struct device *dev;
dlist_t *node;
uint8_t device_index = 0;
MSG("Device List Print\r\n");
dlist_for_each(node, device_get_list_header()) {
dev = dlist_entry(node, struct device, list);
MSG("Index %d\r\nDevice Name = %s \r\n", device_index, dev->name);
switch (dev->type) {
case DEVICE_CLASS_GPIO:
MSG("Device Type = %s \r\n", "GPIO");
break;
case DEVICE_CLASS_UART:
MSG("Device Type = %s \r\n", "UART");
break;
case DEVICE_CLASS_SPI:
MSG("Device Type = %s \r\n", "SPI");
break;
case DEVICE_CLASS_I2C:
MSG("Device Type = %s \r\n", "I2C");
break;
case DEVICE_CLASS_ADC:
MSG("Device Type = %s \r\n", "ADC");
break;
case DEVICE_CLASS_DMA:
MSG("Device Type = %s \r\n", "DMA");
break;
case DEVICE_CLASS_TIMER:
MSG("Device Type = %s \r\n", "TIMER");
break;
case DEVICE_CLASS_PWM:
MSG("Device Type = %s \r\n", "PWM");
break;
case DEVICE_CLASS_SDIO:
MSG("Device Type = %s \r\n", "SDIO");
break;
case DEVICE_CLASS_USB:
MSG("Device Type = %s \r\n", "USB");
break;
case DEVICE_CLASS_I2S:
MSG("Device Type = %s \r\n", "I2S");
break;
case DEVICE_CLASS_CAMERA:
MSG("Device Type = %s \r\n", "CAMERA");
break;
case DEVICE_CLASS_NONE:
break;
default:
break;
}
MSG("Device Handle = 0x%x \r\n", dev);
MSG("---------------------\r\n", dev);
device_index++;
}
}

View File

@@ -0,0 +1,110 @@
/**
* @file bflb_platform.h
* @brief
*
* Copyright (c) 2021 Bouffalolab team
*
* Licensed to the Apache Software Foundation (ASF) under one or more
* contributor license agreements. See the NOTICE file distributed with
* this work for additional information regarding copyright ownership. The
* ASF licenses this file to you under the Apache License, Version 2.0 (the
* "License"); you may not use this file except in compliance with the
* License. You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
* License for the specific language governing permissions and limitations
* under the License.
*
*/
#ifndef _BFLB_PLATFORM_H
#define _BFLB_PLATFORM_H
#ifdef __cplusplus
extern "C" {
#endif
#include <stdio.h>
#include <string.h>
#include <stdint.h>
#include <stdarg.h>
#include <stdbool.h>
#include <stdlib.h>
#define MSG(a, ...) bflb_platform_printf(a, ##__VA_ARGS__)
#define MSG_DBG(a, ...) bflb_platform_printf(a, ##__VA_ARGS__)
#define MSG_ERR(a, ...) bflb_platform_printf(a, ##__VA_ARGS__)
#define BL_CASE_FAIL \
{ \
MSG("case fail\r\n"); \
}
#define BL_CASE_SUCCESS \
{ \
MSG("case success\r\n"); \
}
/* compatible with old version */
#ifndef DBG_TAG
#define DBG_TAG "DEBUG"
#endif
/*
* The color for terminal (foreground)
* BLACK 30
* RED 31
* GREEN 32
* YELLOW 33
* BLUE 34
* PURPLE 35
* CYAN 36
* WHITE 37
*/
#define _DBG_COLOR(n) bflb_platform_printf("\033[" #n "m")
#define _DBG_LOG_HDR(lvl_name, color_n) \
bflb_platform_printf("\033[" #color_n "m[" lvl_name "/" DBG_TAG "] ")
#define _DBG_LOG_X_END \
bflb_platform_printf("\033[0m\n")
#define dbg_log_line(lvl, color_n, fmt, ...) \
do { \
_DBG_LOG_HDR(lvl, color_n); \
bflb_platform_printf(fmt, ##__VA_ARGS__); \
_DBG_LOG_X_END; \
} while (0)
#define LOG_D(fmt, ...) dbg_log_line("D", 0, fmt, ##__VA_ARGS__)
#define LOG_I(fmt, ...) dbg_log_line("I", 35, fmt, ##__VA_ARGS__)
#define LOG_W(fmt, ...) dbg_log_line("W", 33, fmt, ##__VA_ARGS__)
#define LOG_E(fmt, ...) dbg_log_line("E", 31, fmt, ##__VA_ARGS__)
#define LOG_RAW(...) bflb_platform_printf(__VA_ARGS__)
void bflb_platform_init(uint32_t baudrate);
void bflb_platform_printf(char *fmt, ...);
void bflb_platform_print_set(uint8_t disable);
uint8_t bflb_platform_print_get(void);
void bflb_platform_dump(uint8_t *data, uint32_t len);
void bflb_platform_reg_dump(uint32_t addr);
uint32_t bflb_platform_get_log(uint8_t *data, uint32_t maxlen);
void bflb_platform_deinit(void);
void bflb_platform_init_time(void);
void bflb_platform_clear_time(void);
uint64_t bflb_platform_get_time_ms(void);
uint64_t bflb_platform_get_time_us(void);
void bflb_platform_start_time(void);
void bflb_platform_stop_time(void);
void bflb_platform_set_alarm_time(uint64_t time, void (*interruptFun)(void));
void bflb_platform_deinit_time(void);
void bflb_platform_delay_ms(uint32_t ms);
void bflb_platform_delay_us(uint32_t us);
void bflb_print_device_list(void);
#ifdef __cplusplus
}
#endif
#endif

View File

@@ -0,0 +1,219 @@
#include <errno.h>
#include <reent.h>
#include <unistd.h>
// #include "drv_mmheap.h"
#include "drv_device.h"
extern struct heap_info mmheap_root;
#ifdef CONF_VFS_ENABLE
#include <vfs.h>
#endif
/* Reentrant versions of system calls. */
/* global errno in RT-Thread */
static volatile int _sys_errno = 0;
#ifndef _REENT_ONLY
int *__errno() {
// #if (configUSE_POSIX_ERRNO == 1)
// {
// extern int FreeRTOS_errno;
// return &FreeRTOS_errno;
// }
// #endif
return (int *)&_sys_errno;
}
#endif
int _getpid_r(struct _reent *ptr) { return 0; }
int _execve_r(struct _reent *ptr, const char *name, char *const *argv, char *const *env) {
/* return "not supported" */
ptr->_errno = -ENOSYS;
return -1;
}
int _fcntl_r(struct _reent *ptr, int fd, int cmd, int arg) {
/* return "not supported" */
ptr->_errno = -ENOSYS;
return -1;
}
int _fork_r(struct _reent *ptr) {
/* return "not supported" */
ptr->_errno = -ENOSYS;
return -1;
}
int _fstat_r(struct _reent *ptr, int fd, struct stat *pstat) {
/* return "not supported" */
ptr->_errno = -ENOSYS;
return -1;
}
int _isatty_r(struct _reent *ptr, int fd) {
/* return "not supported" */
ptr->_errno = -ENOSYS;
return -1;
}
int _kill_r(struct _reent *ptr, int pid, int sig) {
/* return "not supported" */
ptr->_errno = -ENOSYS;
return -1;
}
int _link_r(struct _reent *ptr, const char *old, const char *new) {
/* return "not supported" */
ptr->_errno = -ENOSYS;
return -1;
}
_off_t _lseek_r(struct _reent *ptr, int fd, _off_t pos, int whence) {
#ifndef CONF_VFS_ENABLE
/* return "not supported" */
ptr->_errno = -ENOSYS;
return -1;
#else
_off_t rc;
rc = aos_lseek(fd, pos, whence);
return rc;
#endif
}
int _mkdir_r(struct _reent *ptr, const char *name, int mode) {
#ifndef CONF_VFS_ENABLE
/* return "not supported" */
ptr->_errno = -ENOSYS;
return -1;
#else
int rc;
rc = aos_mkdir(name);
return rc;
#endif
}
int _open_r(struct _reent *ptr, const char *file, int flags, int mode) {
#ifndef CONF_VFS_ENABLE
/* return "not supported" */
ptr->_errno = -ENOSYS;
return -1;
#else
int rc;
rc = aos_open(file, flags);
return rc;
#endif
}
int _close_r(struct _reent *ptr, int fd) {
#ifndef CONF_VFS_ENABLE
/* return "not supported" */
ptr->_errno = -ENOSYS;
return -1;
#else
return aos_close(fd);
#endif
}
_ssize_t _read_r(struct _reent *ptr, int fd, void *buf, size_t nbytes) {
#ifndef CONF_VFS_ENABLE
/* return "not supported" */
ptr->_errno = -ENOSYS;
return -1;
#else
_ssize_t rc;
rc = aos_read(fd, buf, nbytes);
return rc;
#endif
}
int _rename_r(struct _reent *ptr, const char *old, const char *new) {
#ifndef CONF_VFS_ENABLE
/* return "not supported" */
ptr->_errno = -ENOSYS;
return -1;
#else
int rc;
rc = aos_rename(old, new);
return rc;
#endif
}
int _stat_r(struct _reent *ptr, const char *file, struct stat *pstat) {
#ifndef CONF_VFS_ENABLE
/* return "not supported" */
ptr->_errno = -ENOSYS;
return -1;
#else
int rc;
rc = aos_stat(file, pstat);
return rc;
#endif
}
int _unlink_r(struct _reent *ptr, const char *file) {
#ifndef CONF_VFS_ENABLE
/* return "not supported" */
ptr->_errno = -ENOSYS;
return -1;
#else
return aos_unlink(file);
#endif
}
int _wait_r(struct _reent *ptr, int *status) {
/* return "not supported" */
ptr->_errno = -ENOSYS;
return -1;
}
_ssize_t _write_r(struct _reent *ptr, int fd, const void *buf, size_t nbytes) {
#ifndef CONF_VFS_ENABLE
struct device *uart = device_find("debug_log");
if ((STDOUT_FILENO == fd) || (STDERR_FILENO == fd)) {
device_write(uart, 0, (uint8_t *)buf, nbytes);
}
return 0;
#else
_ssize_t rc;
rc = aos_write(fd, buf, nbytes);
return rc;
#endif
}
// void *_malloc_r(struct _reent *ptr, size_t size) { return NULL; }
// void *_realloc_r(struct _reent *ptr, void *old, size_t newlen) { return NULL; }
// void *_calloc_r(struct _reent *ptr, size_t size, size_t len) { return NULL; }
// void _free_r(struct _reent *ptr, void *addr) {}
void *_sbrk_r(struct _reent *ptr, ptrdiff_t incr) { return NULL; }
/* for exit() and abort() */
void __attribute__((noreturn)) _exit(int status) {
while (1) {}
}
void _system(const char *s) {}
mode_t umask(mode_t mask) { return 022; }
int flock(int fd, int operation) { return 0; }
/*
These functions are implemented and replaced by the 'common/time.c' file
int _gettimeofday_r(struct _reent *ptr, struct timeval *__tp, void *__tzp);
_CLOCK_T_ _times_r(struct _reent *ptr, struct tms *ptms);
*/

View File

@@ -0,0 +1,194 @@
/**
* @file uart_interface.c
* @brief
*
* Copyright (c) 2021 Bouffalolab team
*
* Licensed to the Apache Software Foundation (ASF) under one or more
* contributor license agreements. See the NOTICE file distributed with
* this work for additional information regarding copyright ownership. The
* ASF licenses this file to you under the Apache License, Version 2.0 (the
* "License"); you may not use this file except in compliance with the
* License. You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
* License for the specific language governing permissions and limitations
* under the License.
*
*/
#include "bflb_platform.h"
#include "hal_gpio.h"
#include "uart_interface.h"
#include "hal_usb.h"
#include "hal_dma.h"
#define USB_OUT_RINGBUFFER_SIZE (8 * 1024)
#define UART_RX_RINGBUFFER_SIZE (8 * 1024)
#define UART_TX_DMA_SIZE (4095)
uint8_t usb_rx_mem[USB_OUT_RINGBUFFER_SIZE] __attribute__((section(".system_ram")));
uint8_t uart_rx_mem[UART_RX_RINGBUFFER_SIZE] __attribute__((section(".system_ram")));
uint8_t src_buffer[UART_TX_DMA_SIZE] __attribute__((section(".tcm_code")));
struct device *uart1;
struct device *dma_ch2;
Ring_Buffer_Type usb_rx_rb;
Ring_Buffer_Type uart1_rx_rb;
void uart_irq_callback(struct device *dev, void *args, uint32_t size, uint32_t state)
{
if (state == UART_EVENT_RX_FIFO) {
if (size && size < Ring_Buffer_Get_Empty_Length(&uart1_rx_rb)) {
Ring_Buffer_Write(&uart1_rx_rb, (uint8_t *)args, size);
} else {
MSG("RF OV\r\n");
}
} else if (state == UART_EVENT_RTO) {
if (size && size < Ring_Buffer_Get_Empty_Length(&uart1_rx_rb)) {
Ring_Buffer_Write(&uart1_rx_rb, (uint8_t *)args, size);
} else {
MSG("RTO OV\r\n");
}
} else if (state == UART_RX_FER_IT) {
MSG("RX ERR\r\n");
}
}
void uart1_init(void)
{
#ifdef UART1_INDEX
uart_register(UART1_INDEX, "uart1");
uart1 = device_find("uart1");
if (uart1) {
// device_open(uart1, DEVICE_OFLAG_DMA_TX | DEVICE_OFLAG_INT_RX);
// device_set_callback(uart1, uart_irq_callback);
// device_control(uart1, DEVICE_CTRL_SET_INT, (void *)(UART_RX_FIFO_IT | UART_RTO_IT));
}
dma_register(DMA0_CH2_INDEX, "ch2");
dma_ch2 = device_find("ch2");
if (dma_ch2) {
DMA_DEV(dma_ch2)->direction = DMA_MEMORY_TO_PERIPH;
DMA_DEV(dma_ch2)->transfer_mode = DMA_LLI_ONCE_MODE;
DMA_DEV(dma_ch2)->src_req = DMA_REQUEST_NONE;
DMA_DEV(dma_ch2)->dst_req = DMA_REQUEST_UART1_TX;
DMA_DEV(dma_ch2)->src_addr_inc = DMA_ADDR_INCREMENT_ENABLE;
DMA_DEV(dma_ch2)->dst_addr_inc = DMA_ADDR_INCREMENT_DISABLE;
DMA_DEV(dma_ch2)->src_burst_size = DMA_BURST_1BYTE;
DMA_DEV(dma_ch2)->dst_burst_size = DMA_BURST_1BYTE;
DMA_DEV(dma_ch2)->src_width = DMA_TRANSFER_WIDTH_8BIT;
DMA_DEV(dma_ch2)->dst_width = DMA_TRANSFER_WIDTH_8BIT;
device_open(dma_ch2, 0);
}
#endif
}
void uart1_config(uint32_t baudrate, uart_databits_t databits, uart_parity_t parity, uart_stopbits_t stopbits)
{
device_close(uart1);
UART_DEV(uart1)->baudrate = baudrate;
UART_DEV(uart1)->stopbits = stopbits;
UART_DEV(uart1)->parity = parity;
UART_DEV(uart1)->databits = (databits - 5);
device_open(uart1, DEVICE_OFLAG_DMA_TX | DEVICE_OFLAG_INT_RX);
device_set_callback(uart1, uart_irq_callback);
device_control(uart1, DEVICE_CTRL_SET_INT, (void *)(UART_RX_FIFO_IT | UART_RTO_IT));
Ring_Buffer_Reset(&usb_rx_rb);
Ring_Buffer_Reset(&uart1_rx_rb);
}
static uint8_t uart1_dtr;
static uint8_t uart1_rts;
void uart1_set_dtr_rts(uint8_t dtr, uint8_t rts)
{
uart1_dtr = dtr;
uart1_rts = rts;
}
void uart1_dtr_init(void)
{
gpio_set_mode(uart1_dtr, GPIO_OUTPUT_MODE);
}
void uart1_rts_init(void)
{
gpio_set_mode(uart1_rts, GPIO_OUTPUT_MODE);
}
void uart1_dtr_deinit(void)
{
gpio_set_mode(uart1_dtr, GPIO_INPUT_MODE);
}
void uart1_rts_deinit(void)
{
gpio_set_mode(uart1_rts, GPIO_INPUT_MODE);
}
void dtr_pin_set(uint8_t status)
{
gpio_write(uart1_dtr, status);
}
void rts_pin_set(uint8_t status)
{
gpio_write(uart1_rts, status);
}
void ringbuffer_lock()
{
cpu_global_irq_disable();
}
void ringbuffer_unlock()
{
cpu_global_irq_enable();
}
void uart_ringbuffer_init(void)
{
/* init mem for ring_buffer */
memset(usb_rx_mem, 0, USB_OUT_RINGBUFFER_SIZE);
memset(uart_rx_mem, 0, UART_RX_RINGBUFFER_SIZE);
/* init ring_buffer */
Ring_Buffer_Init(&usb_rx_rb, usb_rx_mem, USB_OUT_RINGBUFFER_SIZE, ringbuffer_lock, ringbuffer_unlock);
Ring_Buffer_Init(&uart1_rx_rb, uart_rx_mem, UART_RX_RINGBUFFER_SIZE, ringbuffer_lock, ringbuffer_unlock);
}
static dma_control_data_t uart_dma_ctrl_cfg = {
.bits.fix_cnt = 0,
.bits.dst_min_mode = 0,
.bits.dst_add_mode = 0,
.bits.SI = 1,
.bits.DI = 0,
.bits.SWidth = DMA_TRANSFER_WIDTH_8BIT,
.bits.DWidth = DMA_TRANSFER_WIDTH_8BIT,
.bits.SBSize = 0,
.bits.DBSize = 0,
.bits.I = 0,
.bits.TransferSize = 4095
};
static dma_lli_ctrl_t uart_lli_list = {
.src_addr = (uint32_t)src_buffer,
.dst_addr = DMA_ADDR_UART1_TDR,
.nextlli = 0
};
void uart_send_from_ringbuffer(void)
{
if (Ring_Buffer_Get_Length(&usb_rx_rb)) {
if (!dma_channel_check_busy(dma_ch2)) {
uint32_t avalibleCnt = Ring_Buffer_Read(&usb_rx_rb, src_buffer, UART_TX_DMA_SIZE);
if (avalibleCnt) {
dma_channel_stop(dma_ch2);
uart_dma_ctrl_cfg.bits.TransferSize = avalibleCnt;
memcpy(&uart_lli_list.cfg, &uart_dma_ctrl_cfg, sizeof(dma_control_data_t));
dma_channel_update(dma_ch2, (void *)((uint32_t)&uart_lli_list));
dma_channel_start(dma_ch2);
}
}
}
}

View File

@@ -0,0 +1,44 @@
/**
* @file uart_interface.h
* @brief
*
* Copyright (c) 2021 Bouffalolab team
*
* Licensed to the Apache Software Foundation (ASF) under one or more
* contributor license agreements. See the NOTICE file distributed with
* this work for additional information regarding copyright ownership. The
* ASF licenses this file to you under the Apache License, Version 2.0 (the
* "License"); you may not use this file except in compliance with the
* License. You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
* License for the specific language governing permissions and limitations
* under the License.
*
*/
#ifndef __UART_IF_H__
#define __UART_IF_H__
#include "hal_uart.h"
#include "ring_buffer.h"
extern Ring_Buffer_Type usb_rx_rb;
extern Ring_Buffer_Type uart1_rx_rb;
void uart1_init(void);
void uart1_config(uint32_t baudrate, uart_databits_t databits, uart_parity_t parity, uart_stopbits_t stopbits);
void uart1_set_dtr_rts(uint8_t dtr, uint8_t rts);
void uart1_dtr_init(void);
void uart1_rts_init(void);
void uart1_dtr_deinit(void);
void uart1_rts_deinit(void);
void dtr_pin_set(uint8_t status);
void rts_pin_set(uint8_t status);
void uart_ringbuffer_init(void);
void uart_send_from_ringbuffer(void);
#endif

View File

@@ -0,0 +1,82 @@
/**
* @file usb_dc.c
* @brief
*
* Copyright (c) 2021 Bouffalolab team
*
* Licensed to the Apache Software Foundation (ASF) under one or more
* contributor license agreements. See the NOTICE file distributed with
* this work for additional information regarding copyright ownership. The
* ASF licenses this file to you under the Apache License, Version 2.0 (the
* "License"); you may not use this file except in compliance with the
* License. You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
* License for the specific language governing permissions and limitations
* under the License.
*
*/
#include "hal_usb.h"
#include "stdbool.h"
#include "usbd_core.h"
struct device *usb;
#ifdef USB_INDEX
static void usb_dc_event_callback(struct device *dev, void *args, uint32_t size, uint32_t state)
{
usbd_event_notify_handler(state, args);
}
#endif
struct device *usb_dc_init(void)
{
#ifdef USB_INDEX
usb_dc_register(USB_INDEX, "usb");
usb = device_find("usb");
device_set_callback(usb, usb_dc_event_callback);
device_open(usb, 0);
return usb;
#endif
return NULL;
}
int usbd_set_address(const uint8_t addr)
{
return usb_dc_set_dev_address(addr);
}
int usbd_ep_open(const struct usbd_endpoint_cfg *ep_cfg)
{
return usb_dc_ep_open(usb, (const struct usb_dc_ep_cfg *)ep_cfg);
}
int usbd_ep_close(const uint8_t ep)
{
return usb_dc_ep_close(ep);
}
int usbd_ep_set_stall(const uint8_t ep)
{
return usb_dc_ep_set_stall(ep);
}
int usbd_ep_clear_stall(const uint8_t ep)
{
return usb_dc_ep_clear_stall(ep);
}
int usbd_ep_is_stalled(const uint8_t ep, uint8_t *stalled)
{
return usb_dc_ep_is_stalled(usb, ep, stalled);
}
int usbd_ep_write(const uint8_t ep, const uint8_t *data, uint32_t data_len, uint32_t *ret_bytes)
{
return usb_dc_ep_write(usb, ep, data, data_len, ret_bytes);
}
int usbd_ep_read(const uint8_t ep, uint8_t *data, uint32_t max_data_len, uint32_t *read_bytes)
{
return usb_dc_ep_read(usb, ep, data, max_data_len, read_bytes);
}

View File

@@ -0,0 +1,62 @@
################# Add global include #################
list(APPEND ADD_INCLUDE
"${CMAKE_CURRENT_SOURCE_DIR}/ring_buffer"
"${CMAKE_CURRENT_SOURCE_DIR}/soft_crc"
"${CMAKE_CURRENT_SOURCE_DIR}/memheap"
"${CMAKE_CURRENT_SOURCE_DIR}/misc"
"${CMAKE_CURRENT_SOURCE_DIR}/list"
"${CMAKE_CURRENT_SOURCE_DIR}/device"
"${CMAKE_CURRENT_SOURCE_DIR}/partition"
"${CMAKE_CURRENT_SOURCE_DIR}/bl_math"
"${CMAKE_CURRENT_SOURCE_DIR}/pid"
"${CMAKE_CURRENT_SOURCE_DIR}/timestamp"
)
#######################################################
################# Add private include #################
# list(APPEND ADD_PRIVATE_INCLUDE
# )
#######################################################
############## Add current dir source files ###########
file(GLOB_RECURSE sources
"${CMAKE_CURRENT_SOURCE_DIR}/ring_buffer/*.c"
"${CMAKE_CURRENT_SOURCE_DIR}/soft_crc/*.c"
"${CMAKE_CURRENT_SOURCE_DIR}/memheap/*.c"
"${CMAKE_CURRENT_SOURCE_DIR}/misc/*.c"
"${CMAKE_CURRENT_SOURCE_DIR}/device/*.c"
"${CMAKE_CURRENT_SOURCE_DIR}/partition/*.c"
"${CMAKE_CURRENT_SOURCE_DIR}/bl_math/*.c"
"${CMAKE_CURRENT_SOURCE_DIR}/pid/*.c"
"${CMAKE_CURRENT_SOURCE_DIR}/timestamp/*.c"
)
#aux_source_directory(. sources)
list(APPEND ADD_SRCS ${sources})
#######################################################
########### Add required/dependent components #########
#list(APPEND ADD_REQUIREMENTS xxx)
#######################################################
############ Add static libs ##########################
#list(APPEND ADD_STATIC_LIB "libxxx.a")
#######################################################
############ Add dynamic libs #########################
# list(APPEND ADD_DYNAMIC_LIB "libxxx.so"
# )
#######################################################
############ Add global compile option ################
#add components denpend on this component
string(TOUPPER ${CHIP} CHIPNAME)
list(APPEND ADD_DEFINITIONS -D${CHIPNAME})
#######################################################
############ Add private compile option ################
#add compile option for this component that won't affect other modules
# list(APPEND ADD_PRIVATE_DEFINITIONS -Dxxx)
#######################################################
generate_library()

View File

@@ -0,0 +1,50 @@
/**
* @file arm_dsp_wrapper.h
* @brief
*
* Copyright (c) 2021 Bouffalolab team
*
* Licensed to the Apache Software Foundation (ASF) under one or more
* contributor license agreements. See the NOTICE file distributed with
* this work for additional information regarding copyright ownership. The
* ASF licenses this file to you under the Apache License, Version 2.0 (the
* "License"); you may not use this file except in compliance with the
* License. You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
* License for the specific language governing permissions and limitations
* under the License.
*
*/
#include "arm_dsp_wrapper.h"
void arm_fill_f32(float32_t value, float32_t *pDst, uint32_t blockSize)
{
uint32_t blkCnt = blockSize >> 2u;
float32_t in1 = value;
float32_t in2 = value;
float32_t in3 = value;
float32_t in4 = value;
while (blkCnt > 0u) {
*pDst++ = in1;
*pDst++ = in2;
*pDst++ = in3;
*pDst++ = in4;
blkCnt--;
}
blkCnt = blockSize % 0x4u;
while (blkCnt > 0u) {
*pDst++ = value;
blkCnt--;
}
}

View File

@@ -0,0 +1,44 @@
/**
* @file arm_dsp_wrapper.c
* @brief
*
* Copyright (c) 2021 Bouffalolab team
*
* Licensed to the Apache Software Foundation (ASF) under one or more
* contributor license agreements. See the NOTICE file distributed with
* this work for additional information regarding copyright ownership. The
* ASF licenses this file to you under the Apache License, Version 2.0 (the
* "License"); you may not use this file except in compliance with the
* License. You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
* License for the specific language governing permissions and limitations
* under the License.
*
*/
#ifndef __MY_MATH_F_H__
#define __MY_MATH_F_H__
#include "misc.h"
#include "math.h"
typedef float float32_t;
__INLINE__ float32_t arm_sqrt_f32(float32_t x)
{
return sqrtf(x);
}
__INLINE__ float32_t arm_cos_f32(float32_t x)
{
return cosf(x);
}
void arm_fill_f32(float32_t value, float32_t *pDst, uint32_t blockSize);
#endif

View File

@@ -0,0 +1,294 @@
/**
* @file drv_device.c
*
* Copyright (c) 2021 Bouffalolab team
*
* Licensed to the Apache Software Foundation (ASF) under one or more
* contributor license agreements. See the NOTICE file distributed with
* this work for additional information regarding copyright ownership. The
* ASF licenses this file to you under the Apache License, Version 2.0 (the
* "License"); you may not use this file except in compliance with the
* License. You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
* License for the specific language governing permissions and limitations
* under the License.
*
*/
#include "drv_device.h"
#define DEVICE_CHECK_PARAM
#define dev_open (dev->open)
#define dev_close (dev->close)
#define dev_read (dev->read)
#define dev_write (dev->write)
#define dev_control (dev->control)
dlist_t device_head = DLIST_OBJECT_INIT(device_head);
/**
* This function get device list header
*
* @param None
*
* @return device header
*/
dlist_t *device_get_list_header(void)
{
return &device_head;
}
/**
* This function registers a device driver with specified name.
*
* @param dev the pointer of device driver structure
* @param name the device driver's name
* @param flags the capabilities flag of device
*
* @return the error code, DEVICE_EOK on initialization successfully.
*/
int device_register(struct device *dev, const char *name)
{
dlist_t *node;
dlist_for_each(node, &device_head)
{
struct device *dev_obj;
dev_obj = dlist_entry(node, struct device, list);
if (dev_obj == dev) {
return -DEVICE_EEXIST;
}
}
strcpy(dev->name, name);
dlist_insert_after(&device_head, &(dev->list));
dev->status = DEVICE_REGISTERED;
return DEVICE_EOK;
}
/**
* This function unregisters a device driver with specified name.
*
* @param dev the pointer of device driver structure
* @param name the device driver's name
* @param flags the capabilities flag of device
*
* @return the error code, DEVICE_EOK on initialization successfully.
*/
int device_unregister(const char *name)
{
struct device *dev = device_find(name);
if (!dev) {
return -DEVICE_ENODEV;
}
dev->status = DEVICE_UNREGISTER;
/* remove from old list */
dlist_remove(&(dev->list));
return DEVICE_EOK;
}
/**
* This function finds a device driver by specified name.
*
* @param name the device driver's name
*
* @return the registered device driver on successful, or NULL on failure.
*/
struct device *device_find(const char *name)
{
struct device *dev;
dlist_t *node;
dlist_for_each(node, &device_head)
{
dev = dlist_entry(node, struct device, list);
if (strncmp(dev->name, name, DEVICE_NAME_MAX) == 0) {
return dev;
}
}
return NULL;
}
/**
* This function will open a device
*
* @param dev the pointer of device driver structure
* @param oflag the flags for device open
*
* @return the result
*/
int device_open(struct device *dev, uint16_t oflag)
{
#ifdef DEVICE_CHECK_PARAM
int retval = DEVICE_EOK;
if ((dev->status == DEVICE_REGISTERED) || (dev->status == DEVICE_CLOSED)) {
if (dev_open != NULL) {
retval = dev_open(dev, oflag);
dev->status = DEVICE_OPENED;
dev->oflag |= oflag;
} else {
retval = -DEVICE_EFAULT;
}
} else {
retval = -DEVICE_EINVAL;
}
return retval;
#else
return dev_open(dev, oflag);
#endif
}
/**
* This function will close a device
*
* @param dev the pointer of device driver structure
*
* @return the result
*/
int device_close(struct device *dev)
{
#ifdef DEVICE_CHECK_PARAM
int retval = DEVICE_EOK;
if (dev->status == DEVICE_OPENED) {
if (dev_close != NULL) {
retval = dev_close(dev);
dev->status = DEVICE_CLOSED;
dev->oflag = 0;
} else {
retval = -DEVICE_EFAULT;
}
} else {
retval = -DEVICE_EINVAL;
}
return retval;
#else
return dev_close(dev);
#endif
}
/**
* This function will perform a variety of control functions on devices.
*
* @param dev the pointer of device driver structure
* @param cmd the command sent to device
* @param arg the argument of command
*
* @return the result
*/
int device_control(struct device *dev, int cmd, void *args)
{
#ifdef DEVICE_CHECK_PARAM
int retval = DEVICE_EOK;
if (dev->status > DEVICE_UNREGISTER) {
if (dev_control != NULL) {
retval = dev_control(dev, cmd, args);
} else {
retval = -DEVICE_EFAULT;
}
} else {
retval = -DEVICE_EINVAL;
}
return retval;
#else
return dev_control(dev, cmd, args);
#endif
}
/**
* This function will write some data to a device.
*
* @param dev the pointer of device driver structure
* @param pos the position of written
* @param buffer the data buffer to be written to device
* @param size the size of buffer
*
* @return the actually written size on successful, otherwise negative returned.
*/
int device_write(struct device *dev, uint32_t pos, const void *buffer, uint32_t size)
{
#ifdef DEVICE_CHECK_PARAM
int retval = DEVICE_EOK;
if (dev->status == DEVICE_OPENED) {
if (dev_write != NULL) {
retval = dev_write(dev, pos, buffer, size);
} else {
retval = -DEVICE_EFAULT;
}
} else {
retval = -DEVICE_EINVAL;
}
return retval;
#else
return dev_write(dev, pos, buffer, size);
#endif
}
/**
* This function will read some data from a device.
*
* @param dev the pointer of device driver structure
* @param pos the position of reading
* @param buffer the data buffer to save read data
* @param size the size of buffer
*
* @return the actually read size on successful, otherwise negative returned.
*/
int device_read(struct device *dev, uint32_t pos, void *buffer, uint32_t size)
{
#ifdef DEVICE_CHECK_PARAM
int retval = DEVICE_EOK;
if (dev->status == DEVICE_OPENED) {
if (dev_read != NULL) {
retval = dev_read(dev, pos, buffer, size);
} else {
retval = -DEVICE_EFAULT;
}
} else {
retval = -DEVICE_EINVAL;
}
return retval;
#else
return dev_read(dev, pos, buffer, size);
#endif
}
/**
* This function will read some data from a device.
*
* @param dev the pointer of device driver structure
* @param pos the position of reading
* @param buffer the data buffer to save read data
* @param size the size of buffer
*
* @return the actually read size on successful, otherwise negative returned.
*/
int device_set_callback(struct device *dev, void (*callback)(struct device *dev, void *args, uint32_t size, uint32_t event))
{
int retval = DEVICE_EOK;
if (dev->status > DEVICE_UNREGISTER) {
if (callback != NULL) {
dev->callback = callback;
} else {
retval = -DEVICE_EFAULT;
}
} else {
retval = -DEVICE_EINVAL;
}
return retval;
}

View File

@@ -0,0 +1,135 @@
/**
* @file drv_device.h
* @brief
*
* Copyright (c) 2021 Bouffalolab team
*
* Licensed to the Apache Software Foundation (ASF) under one or more
* contributor license agreements. See the NOTICE file distributed with
* this work for additional information regarding copyright ownership. The
* ASF licenses this file to you under the Apache License, Version 2.0 (the
* "License"); you may not use this file except in compliance with the
* License. You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
* License for the specific language governing permissions and limitations
* under the License.
*
*/
#ifndef __DRV_DEVICE_H__
#define __DRV_DEVICE_H__
#include "drv_list.h"
#include "stdio.h"
#define DEVICE_NAME_MAX 20 /* max device name*/
#define DEVICE_OFLAG_DEFAULT 0x000 /* open with default */
#define DEVICE_OFLAG_STREAM_TX 0x001 /* open with poll tx */
#define DEVICE_OFLAG_STREAM_RX 0x002 /* open with poll rx */
#define DEVICE_OFLAG_INT_TX 0x004 /* open with interrupt tx */
#define DEVICE_OFLAG_INT_RX 0x008 /* open with interrupt rx */
#define DEVICE_OFLAG_DMA_TX 0x010 /* open with dma tx */
#define DEVICE_OFLAG_DMA_RX 0x020 /* open with dma rx */
#define DEVICE_CTRL_SET_INT 0x01 /* set interrupt */
#define DEVICE_CTRL_CLR_INT 0x02 /* clear interrupt */
#define DEVICE_CTRL_GET_INT 0x03 /* get interrupt status*/
#define DEVICE_CTRL_RESUME 0x04 /* resume device */
#define DEVICE_CTRL_SUSPEND 0x05 /* suspend device */
#define DEVICE_CTRL_CONFIG 0x06 /* config device */
#define DEVICE_CTRL_GET_CONFIG 0x07 /* get device configuration */
#define DEVICE_CTRL_ATTACH_TX_DMA 0x08 /* deivce link tx dma */
#define DEVICE_CTRL_ATTACH_RX_DMA 0x09 /* deivce link rx dma */
#define DEVICE_CTRL_TX_DMA_SUSPEND 0x0a /* deivce suspend tx dma */
#define DEVICE_CTRL_RX_DMA_SUSPEND 0x0b /* deivce suspend rx dma */
#define DEVICE_CTRL_TX_DMA_RESUME 0x0c /* deivce resume tx dma */
#define DEVICE_CTRL_RX_DMA_RESUME 0x0d /* deivce resume rx dma */
#define DEVICE_CTRL_RESVD1 0x0E
#define DEVICE_CTRL_RESVD2 0x0F
/*
* POSIX Error codes
*/
#define DEVICE_EOK 0
#define DEVICE_EFAULT 14 /* Bad address */
#define DEVICE_EEXIST 17 /* device exists */
#define DEVICE_ENODEV 19 /* No such device */
#define DEVICE_EINVAL 22 /* Invalid argument */
#define DEVICE_ENOSPACE 23 /* No more Device for Allocate */
#define __ASSERT_PRINT(fmt, ...) printf(fmt, ##__VA_ARGS__)
#define __ASSERT_LOC(test) \
__ASSERT_PRINT("ASSERTION FAIL [%s] @ %s:%d\n", \
#test, \
__FILE__, __LINE__)
#define DEVICE_ASSERT(test, fmt, ...) \
do { \
if (!(test)) { \
__ASSERT_LOC(test); \
__ASSERT_PRINT(fmt, ##__VA_ARGS__); \
} \
} while (0)
enum device_class_type {
DEVICE_CLASS_NONE = 0,
DEVICE_CLASS_GPIO,
DEVICE_CLASS_UART,
DEVICE_CLASS_SPI,
DEVICE_CLASS_I2C,
DEVICE_CLASS_ADC,
DEVICE_CLASS_DAC,
DEVICE_CLASS_DMA,
DEVICE_CLASS_TIMER,
DEVICE_CLASS_PWM,
DEVICE_CLASS_QDEC,
DEVICE_CLASS_SDIO,
DEVICE_CLASS_USB,
DEVICE_CLASS_RMII,
DEVICE_CLASS_I2S,
DEVICE_CLASS_CAMERA,
DEVICE_CLASS_SEC_HASH,
DEVICE_CLASS_KEYSCAN,
};
enum device_status_type {
DEVICE_UNREGISTER = 0,
DEVICE_REGISTERED,
DEVICE_OPENED,
DEVICE_CLOSED
};
struct device {
char name[DEVICE_NAME_MAX]; /*name of device */
dlist_t list; /*list node of device */
enum device_status_type status; /*status of device */
enum device_class_type type; /*type of device */
uint16_t oflag; /*oflag of device */
int (*open)(struct device *dev, uint16_t oflag);
int (*close)(struct device *dev);
int (*control)(struct device *dev, int cmd, void *args);
int (*write)(struct device *dev, uint32_t pos, const void *buffer, uint32_t size);
int (*read)(struct device *dev, uint32_t pos, void *buffer, uint32_t size);
void (*callback)(struct device *dev, void *args, uint32_t size, uint32_t event);
void *handle;
};
int device_register(struct device *dev, const char *name);
int device_unregister(const char *name);
struct device *device_find(const char *name);
int device_open(struct device *dev, uint16_t oflag);
int device_close(struct device *dev);
int device_control(struct device *dev, int cmd, void *args);
int device_write(struct device *dev, uint32_t pos, const void *buffer, uint32_t size);
int device_read(struct device *dev, uint32_t pos, void *buffer, uint32_t size);
int device_set_callback(struct device *dev, void (*callback)(struct device *dev, void *args, uint32_t size, uint32_t event));
dlist_t *device_get_list_header(void);
#endif

View File

@@ -0,0 +1,472 @@
/**
* @file drv_list.h
*
* Copyright (c) 2021 Bouffalolab team
*
* Licensed to the Apache Software Foundation (ASF) under one or more
* contributor license agreements. See the NOTICE file distributed with
* this work for additional information regarding copyright ownership. The
* ASF licenses this file to you under the Apache License, Version 2.0 (the
* "License"); you may not use this file except in compliance with the
* License. You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
* License for the specific language governing permissions and limitations
* under the License.
*
*/
#ifndef __DRV_LIST_H__
#define __DRV_LIST_H__
#include "string.h"
#include "stdint.h"
#ifdef __cplusplus
extern "C" {
#endif
/**
* container_of - return the member address of ptr, if the type of ptr is the
* struct type.
*/
#define container_of(ptr, type, member) \
((type *)((char *)(ptr) - (unsigned long)(&((type *)0)->member)))
/**
* Double List structure
*/
struct dlist_node {
struct dlist_node *next; /**< point to next node. */
struct dlist_node *prev; /**< point to prev node. */
};
typedef struct dlist_node dlist_t; /**< Type for lists. */
/**
* @brief initialize a list
*
* @param l list to be initialized
*/
static inline void dlist_init(dlist_t *l)
{
l->next = l->prev = l;
}
/**
* @brief insert a node after a list
*
* @param l list to insert it
* @param n new node to be inserted
*/
static inline void dlist_insert_after(dlist_t *l, dlist_t *n)
{
l->next->prev = n;
n->next = l->next;
l->next = n;
n->prev = l;
}
/**
* @brief insert a node before a list
*
* @param n new node to be inserted
* @param l list to insert it
*/
static inline void dlist_insert_before(dlist_t *l, dlist_t *n)
{
l->prev->next = n;
n->prev = l->prev;
l->prev = n;
n->next = l;
}
/**
* @brief remove node from list.
* @param n the node to remove from the list.
*/
static inline void dlist_remove(dlist_t *n)
{
n->next->prev = n->prev;
n->prev->next = n->next;
n->next = n->prev = n;
}
/**
* @brief move node from list.
* @param n the node to remove from the list.
*/
static inline void dlist_move_head(dlist_t *l, dlist_t *n)
{
dlist_remove(n);
dlist_insert_after(l, n);
}
/**
* @brief move node from list.
* @param n the node to remove from the list.
*/
static inline void dlist_move_tail(dlist_t *l, dlist_t *n)
{
dlist_remove(n);
dlist_insert_before(l, n);
}
/**
* @brief tests whether a list is empty
* @param l the list to test.
*/
static inline int dlist_isempty(const dlist_t *l)
{
return l->next == l;
}
/**
* @brief get the list length
* @param l the list to get.
*/
static inline unsigned int dlist_len(const dlist_t *l)
{
unsigned int len = 0;
const dlist_t *p = l;
while (p->next != l) {
p = p->next;
len++;
}
return len;
}
/**
* @brief initialize a dlist object
*/
#define DLIST_OBJECT_INIT(object) \
{ \
&(object), &(object) \
}
/**
* @brief initialize a dlist object
*/
#define DLIST_DEFINE(list) \
dlist_t list = { &(list), &(list) }
/**
* @brief get the struct for this entry
* @param node the entry point
* @param type the type of structure
* @param member the name of list in structure
*/
#define dlist_entry(node, type, member) \
container_of(node, type, member)
/**
* dlist_first_entry - get the first element from a list
* @ptr: the list head to take the element from.
* @type: the type of the struct this is embedded in.
* @member: the name of the list_struct within the struct.
*
* Note, that list is expected to be not empty.
*/
#define dlist_first_entry(ptr, type, member) \
dlist_entry((ptr)->next, type, member)
/**
* dlist_first_entry_or_null - get the first element from a list
* @ptr: the list head to take the element from.
* @type: the type of the struct this is embedded in.
* @member: the name of the list_struct within the struct.
*
* Note, that list is expected to be not empty.
*/
#define dlist_first_entry_or_null(ptr, type, member) \
(dlist_isempty(ptr) ? NULL : dlist_first_entry(ptr, type, member))
/**
* dlist_for_each - iterate over a list
* @pos: the dlist_t * to use as a loop cursor.
* @head: the head for your list.
*/
#define dlist_for_each(pos, head) \
for (pos = (head)->next; pos != (head); pos = pos->next)
/**
* dlist_for_each_prev - iterate over a list
* @pos: the dlist_t * to use as a loop cursor.
* @head: the head for your list.
*/
#define dlist_for_each_prev(pos, head) \
for (pos = (head)->prev; pos != (head); pos = pos->prev)
/**
* dlist_for_each_safe - iterate over a list safe against removal of list entry
* @pos: the dlist_t * to use as a loop cursor.
* @n: another dlist_t * to use as temporary storage
* @head: the head for your list.
*/
#define dlist_for_each_safe(pos, n, head) \
for (pos = (head)->next, n = pos->next; pos != (head); \
pos = n, n = pos->next)
#define dlist_for_each_prev_safe(pos, n, head) \
for (pos = (head)->prev, n = pos->prev; pos != (head); \
pos = n, n = pos->prev)
/**
* dlist_for_each_entry - iterate over list of given type
* @pos: the type * to use as a loop cursor.
* @head: the head for your list.
* @member: the name of the list_struct within the struct.
*/
#define dlist_for_each_entry(pos, head, member) \
for (pos = dlist_entry((head)->next, typeof(*pos), member); \
&pos->member != (head); \
pos = dlist_entry(pos->member.next, typeof(*pos), member))
/**
* dlist_for_each_entry_reverse - iterate over list of given type
* @pos: the type * to use as a loop cursor.
* @head: the head for your list.
* @member: the name of the list_struct within the struct.
*/
#define dlist_for_each_entry_reverse(pos, head, member) \
for (pos = dlist_entry((head)->prev, typeof(*pos), member); \
&pos->member != (head); \
pos = dlist_entry(pos->member.prev, typeof(*pos), member))
/**
* dlist_for_each_entry_safe - iterate over list of given type safe against removal of list entry
* @pos: the type * to use as a loop cursor.
* @n: another type * to use as temporary storage
* @head: the head for your list.
* @member: the name of the list_struct within the struct.
*/
#define dlist_for_each_entry_safe(pos, n, head, member) \
for (pos = dlist_entry((head)->next, typeof(*pos), member), \
n = dlist_entry(pos->member.next, typeof(*pos), member); \
&pos->member != (head); \
pos = n, n = dlist_entry(n->member.next, typeof(*n), member))
/**
* dlist_for_each_entry_safe - iterate over list of given type safe against removal of list entry
* @pos: the type * to use as a loop cursor.
* @n: another type * to use as temporary storage
* @head: the head for your list.
* @member: the name of the list_struct within the struct.
*/
#define dlist_for_each_entry_safe_reverse(pos, n, head, member) \
for (pos = dlist_entry((head)->prev, typeof(*pos), field), \
n = dlist_entry(pos->member.prev, typeof(*pos), member); \
&pos->member != (head); \
pos = n, n = dlist_entry(pos->member.prev, typeof(*pos), member))
/**
* Single List structure
*/
struct slist_node {
struct slist_node *next; /**< point to next node. */
};
typedef struct slist_node slist_t; /**< Type for single list. */
/**
* @brief initialize a single list
*
* @param l the single list to be initialized
*/
static inline void slist_init(slist_t *l)
{
l->next = NULL;
}
static inline void slist_add_head(slist_t *l, slist_t *n)
{
n->next = l->next;
l->next = n;
}
static inline void slist_add_tail(slist_t *l, slist_t *n)
{
while (l->next) {
l = l->next;
}
/* append the node to the tail */
l->next = n;
n->next = NULL;
}
static inline void slist_insert(slist_t *l, slist_t *next, slist_t *n)
{
if (!next) {
slist_add_tail(next, l);
return;
}
while (l->next) {
if (l->next == next) {
l->next = n;
n->next = next;
}
l = l->next;
}
}
static inline slist_t *slist_remove(slist_t *l, slist_t *n)
{
/* remove slist head */
while (l->next && l->next != n) {
l = l->next;
}
/* remove node */
if (l->next != (slist_t *)0) {
l->next = l->next->next;
}
return l;
}
static inline unsigned int slist_len(const slist_t *l)
{
unsigned int len = 0;
const slist_t *list = l->next;
while (list != NULL) {
list = list->next;
len++;
}
return len;
}
static inline unsigned int slist_contains(slist_t *l, slist_t *n)
{
while (l->next) {
if (l->next == n) {
return 0;
}
l = l->next;
}
return 1;
}
static inline slist_t *slist_head(slist_t *l)
{
return l->next;
}
static inline slist_t *slist_tail(slist_t *l)
{
while (l->next) {
l = l->next;
}
return l;
}
static inline slist_t *slist_next(slist_t *n)
{
return n->next;
}
static inline int slist_isempty(slist_t *l)
{
return l->next == NULL;
}
/**
* @brief initialize a slist object
*/
#define SLIST_OBJECT_INIT(object) \
{ \
NULL \
}
/**
* @brief initialize a slist object
*/
#define SLIST_DEFINE(slist) \
slist_t slist = { NULL }
/**
* @brief get the struct for this single list node
* @param node the entry point
* @param type the type of structure
* @param member the name of list in structure
*/
#define slist_entry(node, type, member) \
container_of(node, type, member)
/**
* slist_first_entry - get the first element from a slist
* @ptr: the slist head to take the element from.
* @type: the type of the struct this is embedded in.
* @member: the name of the slist_struct within the struct.
*
* Note, that slist is expected to be not empty.
*/
#define slist_first_entry(ptr, type, member) \
slist_entry((ptr)->next, type, member)
/**
* slist_tail_entry - get the tail element from a slist
* @ptr: the slist head to take the element from.
* @type: the type of the struct this is embedded in.
* @member: the name of the slist_struct within the struct.
*
* Note, that slist is expected to be not empty.
*/
#define slist_tail_entry(ptr, type, member) \
slist_entry(slist_tail(ptr), type, member)
/**
* slist_first_entry_or_null - get the first element from a slist
* @ptr: the slist head to take the element from.
* @type: the type of the struct this is embedded in.
* @member: the name of the slist_struct within the struct.
*
* Note, that slist is expected to be not empty.
*/
#define slist_first_entry_or_null(ptr, type, member) \
(slist_isempty(ptr) ? NULL : slist_first_entry(ptr, type, member))
/**
* slist_for_each - iterate over a single list
* @pos: the slist_t * to use as a loop cursor.
* @head: the head for your single list.
*/
#define slist_for_each(pos, head) \
for (pos = (head)->next; pos != NULL; pos = pos->next)
#define slist_for_each_safe(pos, next, head) \
for (pos = (head)->next, next = pos->next; pos; \
pos = next, next = pos->next)
/**
* slist_for_each_entry - iterate over single list of given type
* @pos: the type * to use as a loop cursor.
* @head: the head for your single list.
* @member: the name of the list_struct within the struct.
*/
#define slist_for_each_entry(pos, head, member) \
for (pos = slist_entry((head)->next, typeof(*pos), member); \
&pos->member != (NULL); \
pos = slist_entry(pos->member.next, typeof(*pos), member))
#define slist_for_each_entry_safe(pos, n, head, member) \
for (pos = slist_entry((head)->next, typeof(*pos), member), \
n = slist_entry(pos->member.next, typeof(*pos), member); \
&pos->member != (NULL); \
pos = n, n = slist_entry(pos->member.next, typeof(*pos), member))
#ifdef __cplusplus
}
#endif
#endif

View File

@@ -0,0 +1,65 @@
#ifndef __COMMON_H
#define __COMMON_H
/**
* @brief Memory access macro
*/
#define BL_RD_WORD(addr) (*((volatile uint32_t *)(uintptr_t)(addr)))
#define BL_WR_WORD(addr, val) ((*(volatile uint32_t *)(uintptr_t)(addr)) = (val))
#define BL_RD_SHORT(addr) (*((volatile uint16_t *)(uintptr_t)(addr)))
#define BL_WR_SHORT(addr, val) ((*(volatile uint16_t *)(uintptr_t)(addr)) = (val))
#define BL_RD_BYTE(addr) (*((volatile uint8_t *)(uintptr_t)(addr)))
#define BL_WR_BYTE(addr, val) ((*(volatile uint8_t *)(uintptr_t)(addr)) = (val))
#define BL_RDWD_FRM_BYTEP(p) ((p[3] << 24) | (p[2] << 16) | (p[1] << 8) | (p[0]))
#define BL_WRWD_TO_BYTEP(p, val) \
{ \
p[0] = val & 0xff; \
p[1] = (val >> 8) & 0xff; \
p[2] = (val >> 16) & 0xff; \
p[3] = (val >> 24) & 0xff; \
}
/**
* @brief Register access macro
*/
#define BL_RD_REG16(addr, regname) BL_RD_SHORT(addr + regname##_OFFSET)
#define BL_WR_REG16(addr, regname, val) BL_WR_SHORT(addr + regname##_OFFSET, val)
#define BL_RD_REG(addr, regname) BL_RD_WORD(addr + regname##_OFFSET)
#define BL_WR_REG(addr, regname, val) BL_WR_WORD(addr + regname##_OFFSET, val)
#define BL_SET_REG_BIT(val, bitname) ((val) | (1U << bitname##_POS))
#define BL_CLR_REG_BIT(val, bitname) ((val)&bitname##_UMSK)
#define BL_GET_REG_BITS_VAL(val, bitname) (((val)&bitname##_MSK) >> bitname##_POS)
#define BL_SET_REG_BITS_VAL(val, bitname, bitval) (((val)&bitname##_UMSK) | ((uint32_t)(bitval) << bitname##_POS))
#define BL_IS_REG_BIT_SET(val, bitname) (((val) & (1U << (bitname##_POS))) != 0)
#define BL_DRV_DUMMY \
{ \
__ASM volatile("nop"); \
__ASM volatile("nop"); \
__ASM volatile("nop"); \
__ASM volatile("nop"); \
}
/* Std driver attribute macro*/
#ifndef BFLB_USE_CUSTOM_LD_SECTIONS
//#define ATTR_UNI_SYMBOL
#define ATTR_STRINGIFY(x) #x
#define ATTR_TOSTRING(x) ATTR_STRINGIFY(x)
#define ATTR_UNI_SYMBOL __FILE__ ATTR_TOSTRING(__LINE__)
#define ATTR_CLOCK_SECTION __attribute__((section(".sclock_rlt_code." ATTR_UNI_SYMBOL)))
#define ATTR_CLOCK_CONST_SECTION __attribute__((section(".sclock_rlt_const." ATTR_UNI_SYMBOL)))
#define ATTR_TCM_SECTION __attribute__((section(".tcm_code." ATTR_UNI_SYMBOL)))
#define ATTR_TCM_CONST_SECTION __attribute__((section(".tcm_const." ATTR_UNI_SYMBOL)))
#define ATTR_DTCM_SECTION __attribute__((section(".tcm_data")))
#define ATTR_HSRAM_SECTION __attribute__((section(".hsram_code")))
#define ATTR_DMA_RAM_SECTION __attribute__((section(".system_ram")))
#define ATTR_NOCACHE_RAM_SECTION __attribute__((section(".nocache_ram")))
#define ATTR_NOCACHE_NOINIT_RAM_SECTION __attribute__((section(".nocache_noinit_ram")))
#define ATTR_HBN_RAM_SECTION __attribute__((section(".hbn_ram_code")))
#define ATTR_HBN_RAM_CONST_SECTION __attribute__((section(".hbn_ram_data")))
#define ATTR_EALIGN(x) __attribute__((aligned(x)))
#define ATTR_FALLTHROUGH() __attribute__((fallthrough))
#define ATTR_USED __attribute__((__used__))
#else
#include "bl_ld_sections.h"
#endif /* BFLB_USE_CUSTOM_LD_SECTIONS */
#endif

View File

@@ -0,0 +1,112 @@
#ifndef __GCC_H
#define __GCC_H
#ifndef __ORDER_BIG_ENDIAN__
#define __ORDER_BIG_ENDIAN__ (1)
#endif
#ifndef __ORDER_LITTLE_ENDIAN__
#define __ORDER_LITTLE_ENDIAN__ (2)
#endif
#define __BYTE_ORDER__ __ORDER_LITTLE_ENDIAN__
/* CPP header guards */
#ifdef __cplusplus
#define EXTERN_C_BEGIN extern "C" {
#define EXTERN_C_END }
#else
#define EXTERN_C_BEGIN
#define EXTERN_C_END
#endif
#define __MACRO_BEGIN do {
#define __MACRO_END \
} \
while (0)
#if defined(__GNUC__)
#ifndef __ASM
#define __ASM __asm
#endif
#ifndef __INLINE
#define __INLINE inline
#endif
#ifndef __INLINE__
#define __INLINE__ inline
#endif
#ifndef __ALWAYS_INLINE
#define __ALWAYS_INLINE inline __attribute__((always_inline))
#endif
#ifndef __ALWAYS_STATIC_INLINE
#define __ALWAYS_STATIC_INLINE __attribute__((always_inline)) static inline
#endif
#ifndef __STATIC_INLINE
#define __STATIC_INLINE static inline
#endif
#ifndef __NO_RETURN
#define __NO_RETURN __attribute__((noreturn))
#endif
#ifndef __USED
#define __USED __attribute__((used))
#endif
#ifndef __UNUSED__
#define __UNUSED__ __attribute__((__unused__))
#endif
#ifndef __WEAK
#define __WEAK __attribute__((weak))
#endif
#ifndef __WEAK__
#define __WEAK__ __attribute__((weak))
#endif
#ifndef __PACKED
#define __PACKED __attribute__((packed, aligned(1)))
#endif
#ifndef __PACKED__
#define __PACKED__ __attribute__((packed))
#endif
#ifndef __PACKED_STRUCT
#define __PACKED_STRUCT struct __attribute__((packed, aligned(1)))
#endif
#ifndef __PACKED_UNION
#define __PACKED_UNION union __attribute__((packed, aligned(1)))
#endif
#ifndef __IRQ
#define __IRQ __attribute__((interrupt))
#endif
#ifndef __IRQ_ALIGN64
#define __IRQ_ALIGN64 __attribute__((interrupt, aligned(64)))
#endif
#ifndef ALIGN4
#define ALIGN4 __attribute((aligned(4)))
#endif
#ifndef PACK_START
#define PACK_START
#endif
#ifndef PACK_END
#define PACK_END __attribute__((packed))
#endif
#ifndef likely
#define likely(x) __builtin_expect(!!(x), 1)
#endif
#ifndef unlikely
#define unlikely(x) __builtin_expect(!!(x), 0)
#endif
#ifndef __ALIGNED__
#define __ALIGNED__(x) __attribute__((aligned(x)))
#endif
#ifndef SECTION
#define SECTION(x) __attribute__((section(x)))
#endif
#ifndef __CONST__
#define __CONST__ __attribute__((__const__))
#endif
#ifndef __NAKED__
#define __NAKED__ __attribute__((naked))
#endif
#ifndef __deprecated
#define __deprecated __attribute__((deprecated))
#endif
#endif
#endif

View File

@@ -0,0 +1,253 @@
/**
* @file misc.c
* @brief
*
* Copyright (c) 2021 Bouffalolab team
*
* Licensed to the Apache Software Foundation (ASF) under one or more
* contributor license agreements. See the NOTICE file distributed with
* this work for additional information regarding copyright ownership. The
* ASF licenses this file to you under the Apache License, Version 2.0 (the
* "License"); you may not use this file except in compliance with the
* License. You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
* License for the specific language governing permissions and limitations
* under the License.
*
*/
#include "misc.h"
#ifndef BFLB_USE_ROM_DRIVER
/****************************************************************************/ /**
* @brief Char memcpy
*
* @param dst: Destination
* @param src: Source
* @param n: Count of char
*
* @return Destination pointer
*
*******************************************************************************/
__WEAK__ void *ATTR_TCM_SECTION arch_memcpy(void *dst, const void *src, uint32_t n)
{
const uint8_t *p = src;
uint8_t *q = dst;
while (n--) {
*q++ = *p++;
}
return dst;
}
/****************************************************************************/ /**
* @brief Word memcpy
*
* @param dst: Destination
* @param src: Source
* @param n: Count of words
*
* @return Destination pointer
*
*******************************************************************************/
__WEAK__ uint32_t *ATTR_TCM_SECTION arch_memcpy4(uint32_t *dst, const uint32_t *src, uint32_t n)
{
const uint32_t *p = src;
uint32_t *q = dst;
while (n--) {
*q++ = *p++;
}
return dst;
}
/****************************************************************************/ /**
* @brief Fast memcpy
*
* @param dst: Destination
* @param src: Source
* @param n: Count of bytes
*
* @return Destination pointer
*
*******************************************************************************/
__WEAK__ void *ATTR_TCM_SECTION arch_memcpy_fast(void *pdst, const void *psrc, uint32_t n)
{
uint32_t left, done, i = 0;
uint8_t *dst = (uint8_t *)pdst;
uint8_t *src = (uint8_t *)psrc;
if (((uint32_t)(uintptr_t)dst & 0x3) == 0 && ((uint32_t)(uintptr_t)src & 0x3) == 0) {
arch_memcpy4((uint32_t *)dst, (const uint32_t *)src, n >> 2);
left = n % 4;
done = n - left;
while (i < left) {
dst[done + i] = src[done + i];
i++;
}
} else {
arch_memcpy(dst, src, n);
}
return dst;
}
/****************************************************************************/ /**
* @brief char memset
*
* @param dst: Destination
* @param val: Value to set
* @param n: Count of char
*
* @return Destination pointer
*
*******************************************************************************/
__WEAK__ void *ATTR_TCM_SECTION arch_memset(void *s, uint8_t c, uint32_t n)
{
uint8_t *p = (uint8_t *)s;
while (n > 0) {
*p++ = (uint8_t)c;
--n;
}
return s;
}
/****************************************************************************/ /**
* @brief Word memset
*
* @param dst: Destination
* @param val: Value to set
* @param n: Count of words
*
* @return Destination pointer
*
*******************************************************************************/
__WEAK__ uint32_t *ATTR_TCM_SECTION arch_memset4(uint32_t *dst, const uint32_t val, uint32_t n)
{
uint32_t *q = dst;
while (n--) {
*q++ = val;
}
return dst;
}
/****************************************************************************/ /**
* @brief string compare
*
* @param s1: string 1
* @param s2: string 2
* @param n: Count of chars
*
* @return compare result
*
*******************************************************************************/
__WEAK__ int ATTR_TCM_SECTION arch_memcmp(const void *s1, const void *s2, uint32_t n)
{
const unsigned char *c1 = s1, *c2 = s2;
int d = 0;
while (n--) {
d = (int)*c1++ - (int)*c2++;
if (d) {
break;
}
}
return d;
}
#endif
void memcopy_to_fifo(void *fifo_addr, uint8_t *data, uint32_t length)
{
uint8_t *p = (uint8_t *)fifo_addr;
uint8_t *q = data;
while (length--) {
*p = *q++;
}
}
void fifocopy_to_mem(void *fifo_addr, uint8_t *data, uint32_t length)
{
uint8_t *p = (uint8_t *)fifo_addr;
uint8_t *q = data;
while (length--) {
*q++ = *p;
}
}
/****************************************************************************/ /**
* @brief get u64 first number 1 from right to left
*
* @param val: target value
* @param bit: first 1 in bit
*
* @return SUCCESS or ERROR
*
*******************************************************************************/
int arch_ffsll(uint64_t *val, uint32_t *bit)
{
if (!*val) {
return ERROR;
}
*bit = __builtin_ffsll(*val) - 1;
*val &= ~((1ULL) << (*bit));
return 0;
}
int arch_ctzll(uint64_t *val, uint32_t *bit)
{
if (!*val)
return -1;
*bit = __builtin_ctzll(*val);
*val &= ~((1ULL) << (*bit));
return 0;
}
int arch_clzll(uint64_t *val, uint32_t *bit)
{
if (!*val)
return -1;
*bit = __builtin_clzll(*val);
*val &= ~((1ULL) << (*bit));
return 0;
}
#ifdef DEBUG
/*******************************************************************************
* @brief Reports the name of the source file and the source line number
* where the CHECK_PARAM error has occurred.
* @param file: Pointer to the source file name
* @param line: assert_param error line source number
* @return None
*******************************************************************************/
void check_failed(uint8_t *file, uint32_t line)
{
/* Infinite loop */
while (1)
;
}
#endif /* DEBUG */
/*@} end of group DRIVER_Public_Functions */
/*@} end of group DRIVER_COMMON */
/*@} end of group BL602_Periph_Driver */

View File

@@ -0,0 +1,131 @@
/**
* @file misc.h
* @brief
*
* Copyright (c) 2021 Bouffalolab team
*
* Licensed to the Apache Software Foundation (ASF) under one or more
* contributor license agreements. See the NOTICE file distributed with
* this work for additional information regarding copyright ownership. The
* ASF licenses this file to you under the Apache License, Version 2.0 (the
* "License"); you may not use this file except in compliance with the
* License. You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
* License for the specific language governing permissions and limitations
* under the License.
*
*/
#ifndef _MISC_H
#define _MISC_H
#include <stdio.h>
#include <string.h>
#include <stdint.h>
#include <stdarg.h>
#include <stdbool.h>
#include <stdlib.h>
#include "compiler/gcc.h"
#include "compiler/common.h"
#ifdef BIT
#undef BIT
#define BIT(n) (1UL << (n))
#else
#define BIT(n) (1UL << (n))
#endif
/**
* @brief Null Type definition
*/
#ifndef NULL
#define NULL 0
#endif
/**
* @brief Error type definition
*/
typedef enum {
SUCCESS = 0,
ERROR = 1,
TIMEOUT = 2,
INVALID = 3, /* invalid arguments */
NORESC = 4 /* no resource or resource temperary unavailable */
} BL_Err_Type;
/**
* @brief Functional type definition
*/
typedef enum {
DISABLE = 0,
ENABLE = 1,
} BL_Fun_Type;
/**
* @brief Status type definition
*/
typedef enum {
RESET = 0,
SET = 1,
} BL_Sts_Type;
/**
* @brief Mask type definition
*/
typedef enum {
UNMASK = 0,
MASK = 1
} BL_Mask_Type;
/**
* @brief Logical status Type definition
*/
typedef enum {
LOGIC_LO = 0,
LOGIC_HI = !LOGIC_LO
} LogicalStatus;
/**
* @brief Active status Type definition
*/
typedef enum {
DEACTIVE = 0,
ACTIVE = !DEACTIVE
} ActiveStatus;
/**
* @brief Interrupt callback function type
*/
typedef void(intCallback_Type)(void);
typedef void (*pFunc)(void);
#define ARCH_MemCpy arch_memcpy
#define ARCH_MemSet arch_memset
#define ARCH_MemCmp arch_memcmp
#define ARCH_MemCpy4 arch_memcpy4
#define ARCH_MemCpy_Fast arch_memcpy_fast
#define ARCH_MemSet4 arch_memset4
#ifdef DEBUG
void check_failed(uint8_t *file, uint32_t line);
#define CHECK_PARAM(expr) ((expr) ? (void)0 : check_failed((uint8_t *)__FILE__, __LINE__))
#else
#define CHECK_PARAM(expr) ((void)0)
#endif /* DEBUG */
void *arch_memcpy(void *dst, const void *src, uint32_t n);
void *arch_memset(void *s, uint8_t c, uint32_t n);
int arch_memcmp(const void *s1, const void *s2, uint32_t n);
uint32_t *arch_memcpy4(uint32_t *dst, const uint32_t *src, uint32_t n);
void *arch_memcpy_fast(void *pdst, const void *psrc, uint32_t n);
uint32_t *arch_memset4(uint32_t *dst, const uint32_t val, uint32_t n);
void memcopy_to_fifo(void *fifo_addr, uint8_t *data, uint32_t length);
void fifocopy_to_mem(void *fifo_addr, uint8_t *data, uint32_t length);
int arch_ctzll(uint64_t *val, uint32_t *bit);
int arch_clzll(uint64_t *val, uint32_t *bit);
int arch_ffsll(uint64_t *val, uint32_t *bit);
#endif

View File

@@ -0,0 +1,544 @@
/**
******************************************************************************
* @file partition.c
* @version V1.0
* @date
* @brief This file is the standard driver c file
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2019 Bouffalo Lab</center></h2>
*
* 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. Neither the name of Bouffalo Lab nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
#include "partition.h"
#include "softcrc.h"
#include "bflb_platform.h"
/** @addtogroup BFLB_Common_Driver
* @{
*/
/** @addtogroup PARTITION
* @{
*/
/** @defgroup PARTITION_Private_Macros
* @{
*/
/*@} end of group PARTITION_Private_Macros */
/** @defgroup PARTITION_Private_Types
* @{
*/
/*@} end of group PARTITION_Private_Types */
/** @defgroup PARTITION_Private_Variables
* @{
*/
p_pt_table_flash_erase gp_pt_table_flash_erase = NULL;
p_pt_table_flash_write gp_pt_table_flash_write = NULL;
p_pt_table_flash_read gp_pt_table_flash_read = NULL;
pt_table_iap_param_type p_iap_param;
/*@} end of group PARTITION_Private_Variables */
/** @defgroup PARTITION_Global_Variables
* @{
*/
extern int main(void);
/*@} end of group PARTITION_Global_Variables */
/** @defgroup PARTITION_Private_Fun_Declaration
* @{
*/
/*@} end of group PARTITION_Private_Fun_Declaration */
/** @defgroup PARTITION_Private_Functions
* @{
*/
/****************************************************************************/ /**
* @brief Judge partition table valid
*
* @param ptStuff: Partition table stuff pointer
*
* @return 0 for invalid and 1 for valid
*
*******************************************************************************/
static uint8_t pt_table_valid(pt_table_stuff_config *pt_stuff)
{
pt_table_config *pt_table = &pt_stuff->pt_table;
pt_table_entry_config *pt_entries = pt_stuff->pt_entries;
uint32_t *p_crc32;
uint32_t entriesLen = sizeof(pt_table_entry_config) * pt_table->entryCnt;
if (pt_table->magicCode == BFLB_PT_MAGIC_CODE) {
if (pt_table->entryCnt > PT_ENTRY_MAX) {
MSG("PT Entry Count Error\r\n");
return 0;
}
if (pt_table->crc32 !=
BFLB_Soft_CRC32((uint8_t *)pt_table, sizeof(pt_table_config) - 4)) {
MSG("PT CRC Error\r\n");
return 0;
}
/* ToDo it is a trap here, when entryCnt > 8, crc32 will overflow, comment by zhangcheng */
p_crc32 = (uint32_t *)((uintptr_t)pt_entries + entriesLen);
if (*p_crc32 != BFLB_Soft_CRC32((uint8_t *)pt_entries, entriesLen)) {
MSG("PT Entry CRC Error\r\n");
return 0;
}
return 1;
}
return 0;
}
/*@} end of group PARTITION_Private_Functions */
/** @defgroup PARTITION_Public_Functions
* @{
*/
/****************************************************************************/ /**
* @brief Register partition flash read write erase fucntion
*
* @param erase: Flash erase function
* @param write: Flash write function
* @param read: Flash read function
*
* @return None
*
*******************************************************************************/
void pt_table_set_flash_operation(p_pt_table_flash_erase erase, p_pt_table_flash_write write, p_pt_table_flash_read read)
{
gp_pt_table_flash_erase = erase;
gp_pt_table_flash_write = write;
gp_pt_table_flash_read = read;
}
/****************************************************************************/ /**
* @brief Get active partition table whole stuff
*
* @param ptStuff[2]: Partition table stuff pointer
*
* @return Active partition table ID
*
*******************************************************************************/
pt_table_id_type pt_table_get_active_partition_need_lock(pt_table_stuff_config ptStuff[2])
{
uint32_t pt_valid[2] = { 0, 0 };
pt_table_id_type activePtID;
if (ptStuff == NULL) {
return PT_TABLE_ID_INVALID;
}
activePtID = PT_TABLE_ID_INVALID;
gp_pt_table_flash_read(BFLB_PT_TABLE0_ADDRESS, (uint8_t *)&ptStuff[0], sizeof(pt_table_stuff_config));
pt_valid[0] = pt_table_valid(&ptStuff[0]);
gp_pt_table_flash_read(BFLB_PT_TABLE1_ADDRESS, (uint8_t *)&ptStuff[1], sizeof(pt_table_stuff_config));
pt_valid[1] = pt_table_valid(&ptStuff[1]);
if (pt_valid[0] == 1 && pt_valid[1] == 1) {
if (ptStuff[0].pt_table.age >= ptStuff[1].pt_table.age) {
activePtID = PT_TABLE_ID_0;
} else {
activePtID = PT_TABLE_ID_1;
}
} else if (pt_valid[0] == 1) {
activePtID = PT_TABLE_ID_0;
} else if (pt_valid[1] == 1) {
activePtID = PT_TABLE_ID_1;
}
return activePtID;
}
/****************************************************************************/ /**
* @brief Get partition entry according to entry ID
*
* @param ptStuff: Partition table stuff pointer
* @param type: Type of partition entry
* @param ptEntry: Partition entry pointer to store read data
*
* @return PT_ERROR_SUCCESS or PT_ERROR_ENTRY_NOT_FOUND or PT_ERROR_PARAMETER
*
*******************************************************************************/
pt_table_error_type pt_table_get_active_entries_by_id(pt_table_stuff_config *pt_stuff,
pt_table_entry_type type,
pt_table_entry_config *pt_entry)
{
uint32_t i = 0;
if (pt_stuff == NULL || pt_entry == NULL) {
return PT_ERROR_PARAMETER;
}
for (i = 0; i < pt_stuff->pt_table.entryCnt; i++) {
if (pt_stuff->pt_entries[i].type == type) {
ARCH_MemCpy_Fast(pt_entry, &pt_stuff->pt_entries[i], sizeof(pt_table_entry_config));
return PT_ERROR_SUCCESS;
}
}
return PT_ERROR_ENTRY_NOT_FOUND;
}
/****************************************************************************/ /**
* @brief Get partition entry according to entry name
*
* @param ptStuff: Partition table stuff pointer
* @param name: Name of partition entry
* @param ptEntry: Partition entry pointer to store read data
*
* @return PT_ERROR_SUCCESS or PT_ERROR_ENTRY_NOT_FOUND or PT_ERROR_PARAMETER
*
*******************************************************************************/
pt_table_error_type pt_table_get_active_entries_by_name(pt_table_stuff_config *pt_stuff,
uint8_t *name,
pt_table_entry_config *pt_entry)
{
uint32_t i = 0;
uint32_t len = strlen((char *)name);
if (pt_stuff == NULL || pt_entry == NULL) {
return PT_ERROR_PARAMETER;
}
for (i = 0; i < pt_stuff->pt_table.entryCnt; i++) {
if (strlen((char *)pt_stuff->pt_entries[i].name) == len &&
memcmp((char *)pt_stuff->pt_entries[i].name, (char *)name, len) == 0) {
ARCH_MemCpy_Fast(pt_entry, &pt_stuff->pt_entries[i], sizeof(pt_table_entry_config));
return PT_ERROR_SUCCESS;
}
}
return PT_ERROR_ENTRY_NOT_FOUND;
}
/****************************************************************************/ /**
* @brief Update partition entry
*
* @param targetTableID: Target partition table to update
* @param ptStuff: Partition table stuff pointer
* @param ptEntry: Partition entry pointer to update
*
* @return Partition update result
*
*******************************************************************************/
pt_table_error_type pt_table_update_entry(pt_table_id_type target_table_id,
pt_table_stuff_config *pt_stuff,
pt_table_entry_config *pt_entry)
{
uint32_t i = 0;
BL_Err_Type ret;
uint32_t write_addr;
uint32_t entries_len;
pt_table_config *pt_table;
pt_table_entry_config *pt_entries;
uint32_t *crc32;
if (pt_entry == NULL || pt_stuff == NULL) {
return PT_ERROR_PARAMETER;
}
pt_table = &pt_stuff->pt_table;
pt_entries = pt_stuff->pt_entries;
if (target_table_id == PT_TABLE_ID_INVALID) {
return PT_ERROR_TABLE_NOT_VALID;
}
if (target_table_id == PT_TABLE_ID_0) {
write_addr = BFLB_PT_TABLE0_ADDRESS;
} else {
write_addr = BFLB_PT_TABLE1_ADDRESS;
}
for (i = 0; i < pt_table->entryCnt; i++) {
if (pt_entries[i].type == pt_entry->type) {
ARCH_MemCpy_Fast(&pt_entries[i], pt_entry, sizeof(pt_table_entry_config));
break;
}
}
if (i == pt_table->entryCnt) {
/* Not found this entry ,add new one */
if (pt_table->entryCnt < PT_ENTRY_MAX) {
ARCH_MemCpy_Fast(&pt_entries[pt_table->entryCnt], pt_entry, sizeof(pt_table_entry_config));
pt_table->entryCnt++;
} else {
return PT_ERROR_ENTRY_UPDATE_FAIL;
}
}
/* Prepare write back to flash */
/* Update age */
pt_table->age++;
pt_table->crc32 = BFLB_Soft_CRC32((uint8_t *)pt_table, sizeof(pt_table_config) - 4);
/* Update entries CRC */
entries_len = pt_table->entryCnt * sizeof(pt_table_entry_config);
crc32 = (uint32_t *)((uintptr_t)pt_entries + entries_len);
*crc32 = BFLB_Soft_CRC32((uint8_t *)&pt_entries[0], entries_len);
/* Write back to flash */
/* Erase flash first */
//ret = gp_pt_table_flash_erase(write_addr, write_addr + sizeof(pt_table_config) + entries_len + 4 - 1);
ret = gp_pt_table_flash_erase(write_addr, sizeof(pt_table_config) + entries_len + 4);
if (ret != SUCCESS) {
MSG_ERR("Flash Erase error\r\n");
return PT_ERROR_FALSH_WRITE;
}
/* Write flash */
ret = gp_pt_table_flash_write(write_addr, (uint8_t *)pt_stuff, sizeof(pt_table_stuff_config));
if (ret != SUCCESS) {
MSG_ERR("Flash Write error\r\n");
return PT_ERROR_FALSH_WRITE;
}
return PT_ERROR_SUCCESS;
}
/****************************************************************************/ /**
* @brief Create partition entry
*
* @param ptID: Partition table ID
*
* @return Partition create result
*
*******************************************************************************/
pt_table_error_type pt_table_create(pt_table_id_type pt_id)
{
uint32_t write_addr;
BL_Err_Type ret;
pt_table_config pt_table;
if (pt_id == PT_TABLE_ID_INVALID) {
return PT_ERROR_TABLE_NOT_VALID;
}
if (pt_id == PT_TABLE_ID_0) {
write_addr = BFLB_PT_TABLE0_ADDRESS;
} else {
write_addr = BFLB_PT_TABLE1_ADDRESS;
}
/* Prepare write back to flash */
pt_table.magicCode = BFLB_PT_MAGIC_CODE;
pt_table.version = 0;
pt_table.entryCnt = 0;
pt_table.age = 0;
pt_table.crc32 = BFLB_Soft_CRC32((uint8_t *)&pt_table, sizeof(pt_table_config) - 4);
/* Write back to flash */
//ret = gp_pt_table_flash_erase(write_addr, write_addr + sizeof(pt_table_config) - 1);
ret = gp_pt_table_flash_erase(write_addr,sizeof(pt_table_config));
if (ret != SUCCESS) {
MSG_ERR("Flash Erase error\r\n");
return PT_ERROR_FALSH_ERASE;
}
ret = gp_pt_table_flash_write(write_addr, (uint8_t *)&pt_table, sizeof(pt_table_config));
if (ret != SUCCESS) {
MSG_ERR("Flash Write error\r\n");
return PT_ERROR_FALSH_WRITE;
}
return PT_ERROR_SUCCESS;
}
pt_table_error_type pt_table_dump(void)
{
uint32_t pt_valid[2] = { 0, 0 };
pt_table_stuff_config pt_stuff[2];
gp_pt_table_flash_read(BFLB_PT_TABLE0_ADDRESS, (uint8_t *)&pt_stuff[0], sizeof(pt_table_stuff_config));
pt_valid[0] = pt_table_valid(&pt_stuff[0]);
gp_pt_table_flash_read(BFLB_PT_TABLE1_ADDRESS, (uint8_t *)&pt_stuff[1], sizeof(pt_table_stuff_config));
pt_valid[1] = pt_table_valid(&pt_stuff[1]);
if (pt_valid[0]) {
MSG("PT TABLE0 valid\r\n");
} else {
MSG("PT TABLE0 invalid\r\n");
}
if (pt_valid[1]) {
MSG("PT TABLE1 valid\r\n");
} else {
MSG("PT TABLE1 invalid\r\n");
}
for (int i = 0; i < 2; i++) {
if (pt_valid[i] == 1) {
MSG("ptStuff[%d].pt_table.magicCode 0x%08x\r\n", i, pt_stuff[i].pt_table.magicCode);
MSG("ptStuff[%d].pt_table.version 0x%08x\r\n", i, pt_stuff[i].pt_table.version);
MSG("ptStuff[%d].pt_table.entryCnt 0x%08x\r\n", i, pt_stuff[i].pt_table.entryCnt);
MSG("ptStuff[%d].pt_table.age 0x%08x\r\n", i, pt_stuff[i].pt_table.age);
MSG("ptStuff[%d].pt_table.crc32 0x%08x\r\n", i, pt_stuff[i].pt_table.crc32);
for (int j = 0; j < pt_stuff[i].pt_table.entryCnt; j++) {
MSG("ptStuff[%d].pt_entries[%d].type 0x%08x\r\n", i, j, pt_stuff[i].pt_entries[j].type);
MSG("ptStuff[%d].pt_entries[%d].device 0x%08x\r\n", i, j, pt_stuff[i].pt_entries[j].device);
MSG("ptStuff[%d].pt_entries[%d].active_index 0x%08x\r\n", i, j, pt_stuff[i].pt_entries[j].active_index);
MSG("ptStuff[%d].pt_entries[%d].Address[0] 0x%08x\r\n", i, j, pt_stuff[i].pt_entries[j].start_address[0]);
MSG("ptStuff[%d].pt_entries[%d].Address[1] 0x%08x\r\n", i, j, pt_stuff[i].pt_entries[j].start_address[1]);
MSG("ptStuff[%d].pt_entries[%d].maxLen[0] 0x%08x\r\n", i, j, pt_stuff[i].pt_entries[j].max_len[0]);
MSG("ptStuff[%d].pt_entries[%d].maxLen[1] 0x%08x\r\n", i, j, pt_stuff[i].pt_entries[j].max_len[1]);
MSG("ptStuff[%d].pt_entries[%d].len 0x%08x\r\n", i, j, pt_stuff[i].pt_entries[j].len);
MSG("ptStuff[%d].pt_entries[%d].age 0x%08x\r\n", i, j, pt_stuff[i].pt_entries[j].age);
}
}
}
return PT_ERROR_SUCCESS;
}
pt_table_error_type pt_table_get_iap_para(pt_table_iap_param_type *para)
{
uint32_t pt_valid[2] = { 0, 0 };
pt_table_stuff_config pt_stuff[2];
uint8_t active_index;
gp_pt_table_flash_read(BFLB_PT_TABLE0_ADDRESS, (uint8_t *)&pt_stuff[0], sizeof(pt_table_stuff_config));
pt_valid[0] = pt_table_valid(&pt_stuff[0]);
gp_pt_table_flash_read(BFLB_PT_TABLE1_ADDRESS, (uint8_t *)&pt_stuff[1], sizeof(pt_table_stuff_config));
pt_valid[1] = pt_table_valid(&pt_stuff[1]);
if ((pt_valid[0] == 1) && (pt_valid[1] == 1)) {
if (pt_stuff[0].pt_table.age >= pt_stuff[1].pt_table.age) {
active_index = pt_stuff[0].pt_entries[0].active_index;
para->iap_write_addr = para->iap_start_addr = pt_stuff[0].pt_entries[0].start_address[!(active_index & 0x01)];
para->inactive_index = !(active_index & 0x01);
para->inactive_table_index = 1;
} else {
active_index = pt_stuff[1].pt_entries[0].active_index;
para->iap_write_addr = para->iap_start_addr = pt_stuff[1].pt_entries[0].start_address[!(active_index & 0x01)];
para->inactive_index = !(active_index & 0x01);
para->inactive_table_index = 0;
}
} else if (pt_valid[1] == 1) {
active_index = pt_stuff[1].pt_entries[0].active_index;
para->iap_write_addr = para->iap_start_addr = pt_stuff[1].pt_entries[0].start_address[!(active_index & 0x01)];
para->inactive_index = !(active_index & 0x01);
para->inactive_table_index = 0;
} else if (pt_valid[0] == 1) {
active_index = pt_stuff[0].pt_entries[0].active_index;
para->iap_write_addr = para->iap_start_addr = pt_stuff[0].pt_entries[0].start_address[!(active_index & 0x01)];
para->inactive_index = !(active_index & 0x01);
para->inactive_table_index = 1;
} else {
return PT_ERROR_TABLE_NOT_VALID;
}
MSG("inactive_table_index %d, inactive index %d , IAP start addr %08x \r\n", para->inactive_table_index, para->inactive_index, para->iap_start_addr);
return PT_ERROR_SUCCESS;
}
pt_table_error_type pt_table_set_iap_para(pt_table_iap_param_type *para)
{
pt_table_stuff_config pt_stuff, pt_stuff_write;
int32_t ret;
uint32_t *p_crc32;
uint32_t entries_len;
if (para->inactive_table_index == 1) {
gp_pt_table_flash_read(BFLB_PT_TABLE0_ADDRESS, (uint8_t *)&pt_stuff, sizeof(pt_table_stuff_config));
} else if (para->inactive_table_index == 0) {
gp_pt_table_flash_read(BFLB_PT_TABLE1_ADDRESS, (uint8_t *)&pt_stuff, sizeof(pt_table_stuff_config));
}
ARCH_MemCpy_Fast((void *)&pt_stuff_write, (void *)&pt_stuff, sizeof(pt_table_stuff_config));
pt_stuff_write.pt_table.age += 1;
pt_stuff_write.pt_entries[0].active_index = !(pt_stuff_write.pt_entries[0].active_index & 0x01);
pt_stuff_write.pt_table.crc32 = BFLB_Soft_CRC32((uint8_t *)&pt_stuff_write, sizeof(pt_table_config) - 4);
entries_len = sizeof(pt_table_entry_config) * pt_stuff_write.pt_table.entryCnt;
//pt_stuff_write.crc32 = BFLB_Soft_CRC32((uint8_t*)pt_stuff_write.pt_entries,entries_len);
p_crc32 = (uint32_t *)((uintptr_t)pt_stuff_write.pt_entries + entries_len);
*p_crc32 = BFLB_Soft_CRC32((uint8_t *)pt_stuff_write.pt_entries, entries_len);
if (para->inactive_table_index == 1) {
//ret = gp_pt_table_flash_erase(BFLB_PT_TABLE1_ADDRESS, BFLB_PT_TABLE1_ADDRESS + sizeof(pt_table_stuff_config) - 1);
ret = gp_pt_table_flash_erase(BFLB_PT_TABLE1_ADDRESS, sizeof(pt_table_stuff_config));
if (ret != SUCCESS) {
MSG_ERR("Flash Erase error\r\n");
return PT_ERROR_FALSH_ERASE;
}
ret = gp_pt_table_flash_write(BFLB_PT_TABLE1_ADDRESS, (uint8_t *)&pt_stuff_write, sizeof(pt_table_stuff_config));
if (ret != SUCCESS) {
MSG_ERR("Flash Write error\r\n");
return PT_ERROR_FALSH_WRITE;
}
} else if (para->inactive_table_index == 0) {
//ret = gp_pt_table_flash_erase(BFLB_PT_TABLE0_ADDRESS, BFLB_PT_TABLE0_ADDRESS + sizeof(pt_table_stuff_config) - 1);
ret = gp_pt_table_flash_erase(BFLB_PT_TABLE0_ADDRESS, sizeof(pt_table_stuff_config));
if (ret != SUCCESS) {
MSG_ERR("Flash Erase error\r\n");
return PT_ERROR_FALSH_ERASE;
}
ret = gp_pt_table_flash_write(BFLB_PT_TABLE0_ADDRESS, (uint8_t *)&pt_stuff_write, sizeof(pt_table_stuff_config));
if (ret != SUCCESS) {
MSG_ERR("Flash Write error\r\n");
return PT_ERROR_FALSH_WRITE;
}
}
MSG("Update pt_table suss\r\n");
return PT_ERROR_SUCCESS;
}
/*@} end of group PARTITION_Public_Functions */
/*@} end of group PARTITION */
/*@} end of group BFLB_Common_Driver */

View File

@@ -0,0 +1,209 @@
/**
******************************************************************************
* @file partition.h
* @version V1.0
* @date
* @brief This file is the standard driver header file
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2020 Bouffalo Lab</center></h2>
*
* 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. Neither the name of Bouffalo Lab nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
#ifndef __PARTITION_H__
#define __PARTITION_H__
#include "misc.h"
/** @addtogroup BFLB_Common_Driver
* @{
*/
/** @addtogroup PARTITION
* @{
*/
/** @defgroup PARTITION_Public_Types
* @{
*/
/**
* @brief Partition table error type definition
*/
typedef enum {
PT_ERROR_SUCCESS, /*!< Partition table error type:success */
PT_ERROR_TABLE_NOT_VALID, /*!< Partition table error type:table not found */
PT_ERROR_ENTRY_NOT_FOUND, /*!< Partition table error type:entry not found */
PT_ERROR_ENTRY_UPDATE_FAIL, /*!< Partition table error type:entry update fail */
PT_ERROR_CRC32, /*!< Partition table error type:crc32 error */
PT_ERROR_PARAMETER, /*!< Partition table error type:input parameter error */
PT_ERROR_FALSH_READ, /*!< Partition table error type:flash read error */
PT_ERROR_FALSH_WRITE, /*!< Partition table error type:flash write error */
PT_ERROR_FALSH_ERASE, /*!< Partition table error type:flash erase error */
} pt_table_error_type;
/**
* @brief Partition id type definition
*/
typedef enum {
PT_TABLE_ID_0, /*!< Partition table ID 0 */
PT_TABLE_ID_1, /*!< Partition table ID 1 */
PT_TABLE_ID_INVALID, /*!< Partition table ID invalid */
} pt_table_id_type;
/**
* @brief Partition id type definition
*/
typedef enum {
PT_ENTRY_FW_CPU0, /*!< Partition entry type:CPU0 firmware */
PT_ENTRY_FW_CPU1, /*!< Partition entry type:CPU1 firmware */
PT_ENTRY_MAX = 16, /*!< Partition entry type:Max */
} pt_table_entry_type;
/**
* @brief Partition table config definition
*/
typedef struct
{
uint32_t magicCode; /*!< Partition table magic code */
uint16_t version; /*!< Partition table verdion */
uint16_t entryCnt; /*!< Partition table entry count */
uint32_t age; /*!< Partition table age */
uint32_t crc32; /*!< Partition table CRC32 value */
} pt_table_config;
/**
* @brief Partition table entry config definition
*/
typedef struct
{
uint8_t type; /*!< Partition entry type */
uint8_t device; /*!< Partition entry device */
uint8_t active_index; /*!< Partition entry active index */
uint8_t name[9]; /*!< Partition entry name */
uint32_t start_address[2]; /*!< Partition entry start address */
uint32_t max_len[2]; /*!< Partition entry max length */
uint32_t len; /*!< Partition entry length */
uint32_t age; /*!< Partition entry age */
} pt_table_entry_config;
/**
* @brief Partition table stuff config definition
*/
typedef struct
{
pt_table_config pt_table; /*!< Partition table */
pt_table_entry_config pt_entries[PT_ENTRY_MAX]; /*!< Partition entries */
uint32_t crc32; /*!< Partition entries crc32 */
} pt_table_stuff_config;
/**
* @brief Partition table iap param definition
*/
typedef struct
{
uint32_t iap_start_addr;
uint32_t iap_write_addr;
uint32_t iap_img_len;
uint8_t inactive_index;
uint8_t inactive_table_index;
} pt_table_iap_param_type;
/*@} end of group PARTITION_Public_Types */
/** @defgroup PARTITION_Public_Constants
* @{
*/
/** @defgroup pt_table_error_type
* @{
*/
#define IS_PTTABLE_ERROR_TYPE(type) (((type) == PT_ERROR_SUCCESS) || \
((type) == PT_ERROR_TABLE_NOT_VALID) || \
((type) == PT_ERROR_ENTRY_NOT_FOUND) || \
((type) == PT_ERROR_ENTRY_UPDATE_FAIL) || \
((type) == PT_ERROR_CRC32) || \
((type) == PT_ERROR_PARAMETER) || \
((type) == PT_ERROR_FALSH_READ) || \
((type) == PT_ERROR_FALSH_WRITE) || \
((type) == PT_ERROR_FALSH_ERASE))
/** @defgroup pt_table_id_type
* @{
*/
#define IS_PTTABLE_ID_TYPE(type) (((type) == PT_TABLE_ID_0) || \
((type) == PT_TABLE_ID_1) || \
((type) == PT_TABLE_ID_INVALID))
/** @defgroup pt_table_entry_type
* @{
*/
#define IS_PTTABLE_ENTRY_TYPE(type) (((type) == PT_ENTRY_FW_CPU0) || \
((type) == PT_ENTRY_FW_CPU1) || \
((type) == PT_ENTRY_MAX))
/*@} end of group PARTITION_Public_Constants */
/** @defgroup PARTITION_Public_Macros
* @{
*/
#define BFLB_PT_TABLE0_ADDRESS 0xE000
#define BFLB_PT_TABLE1_ADDRESS 0xF000
#define BFLB_PT_MAGIC_CODE 0x54504642
typedef BL_Err_Type (*p_pt_table_flash_erase)(uint32_t startaddr, uint32_t endaddr);
typedef BL_Err_Type (*p_pt_table_flash_write)(uint32_t addr, uint8_t *data, uint32_t len);
typedef BL_Err_Type (*p_pt_table_flash_read)(uint32_t addr, uint8_t *data, uint32_t len);
/*@} end of group PARTITION_Public_Macros */
/** @defgroup PARTITION_Public_Functions
* @{
*/
void pt_table_set_flash_operation(p_pt_table_flash_erase erase, p_pt_table_flash_write write, p_pt_table_flash_read read);
pt_table_id_type pt_table_get_active_partition_need_lock(pt_table_stuff_config ptStuff[2]);
pt_table_error_type pt_table_get_active_entries_by_id(pt_table_stuff_config *pt_stuff,
pt_table_entry_type type,
pt_table_entry_config *pt_entry);
pt_table_error_type pt_table_get_active_entries_by_name(pt_table_stuff_config *pt_stuff,
uint8_t *name,
pt_table_entry_config *pt_entry);
pt_table_error_type pt_table_update_entry(pt_table_id_type target_table_id,
pt_table_stuff_config *pt_stuff,
pt_table_entry_config *pt_entry);
pt_table_error_type pt_table_create(pt_table_id_type pt_id);
pt_table_error_type pt_table_dump(void);
pt_table_error_type pt_table_get_iap_para(pt_table_iap_param_type *para);
pt_table_error_type pt_table_set_iap_para(pt_table_iap_param_type *para);
/*@} end of group PARTITION_Public_Functions */
/*@} end of group PARTITION */
/*@} end of group BFLB_Common_Driver */
extern pt_table_iap_param_type p_iap_param;
#endif /* __PARTITION_H__ */

View File

@@ -0,0 +1,68 @@
/**
* @file pid.c
* @brief
*
* Copyright (c) 2021 Bouffalolab team
*
* Licensed to the Apache Software Foundation (ASF) under one or more
* contributor license agreements. See the NOTICE file distributed with
* this work for additional information regarding copyright ownership. The
* ASF licenses this file to you under the Apache License, Version 2.0 (the
* "License"); you may not use this file except in compliance with the
* License. You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
* License for the specific language governing permissions and limitations
* under the License.
*
*/
#include "pid.h"
void pid_init(pid_alg_t *pid)
{
pid->set_val = 0.0f;
pid->out_val = 0.0f;
pid->last_error = 0.0f;
pid->prev_error = 0.0f;
pid->kp = 3.0f;
pid->ki = 0.0f;
pid->kd = 0.0f;
pid->i_error = 0.0f;
pid->sum_error = 0.0f;
pid->max_val = 32;
pid->min_val = -32;
}
// standard pid
float standard_pid_cal(pid_alg_t *pid, float next_val)
{
pid->set_val = next_val;
pid->i_error = pid->set_val - pid->out_val;
pid->sum_error += pid->i_error;
pid->out_val = pid->kp * pid->i_error + pid->ki * pid->sum_error + pid->kd * (pid->i_error - pid->last_error);
pid->last_error = pid->i_error;
return pid->out_val;
}
// increment pid
float increment_pid_cal(pid_alg_t *pid, float next_val)
{
pid->set_val = next_val;
pid->i_error = pid->set_val - pid->out_val;
float increment = pid->kp * (pid->i_error - pid->prev_error) + pid->ki * pid->i_error + pid->kd * (pid->i_error - 2 * pid->prev_error + pid->last_error);
pid->out_val += increment;
pid->last_error = pid->prev_error;
pid->prev_error = pid->i_error;
return pid->out_val;
}

View File

@@ -0,0 +1,50 @@
/**
* @file pid.h
* @brief
*
* Copyright (c) 2021 Bouffalolab team
*
* Licensed to the Apache Software Foundation (ASF) under one or more
* contributor license agreements. See the NOTICE file distributed with
* this work for additional information regarding copyright ownership. The
* ASF licenses this file to you under the Apache License, Version 2.0 (the
* "License"); you may not use this file except in compliance with the
* License. You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
* License for the specific language governing permissions and limitations
* under the License.
*
*/
#ifndef __PID_H__
#define __PID_H__
#include "stdint.h"
typedef struct pid_alg {
float set_val;
float out_val;
float kp;
float ki;
float kd;
float i_error;
float last_error;
float prev_error;
float sum_error;
int max_val;
int min_val;
} pid_alg_t;
void pid_init(pid_alg_t *pid);
float standard_pid_cal(pid_alg_t *pid, float next_val);
float increment_pid_cal(pid_alg_t *pid, float next_val);
#endif

View File

@@ -0,0 +1,679 @@
/**
* @file ring_buffer.c
* @brief
*
* Copyright (c) 2021 Bouffalolab team
*
* Licensed to the Apache Software Foundation (ASF) under one or more
* contributor license agreements. See the NOTICE file distributed with
* this work for additional information regarding copyright ownership. The
* ASF licenses this file to you under the Apache License, Version 2.0 (the
* "License"); you may not use this file except in compliance with the
* License. You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
* License for the specific language governing permissions and limitations
* under the License.
*
*/
#include "ring_buffer.h"
/** @addtogroup BL_Common_Component
* @{
*/
/** @addtogroup RING_BUFFER
* @{
*/
/** @defgroup RING_BUFFER_Private_Macros
* @{
*/
/*@} end of group RING_BUFFER_Private_Macros */
/** @defgroup RING_BUFFER_Private_Types
* @{
*/
/*@} end of group RING_BUFFER_Private_Types */
/** @defgroup RING_BUFFER_Private_Fun_Declaration
* @{
*/
/*@} end of group RING_BUFFER_Private_Fun_Declaration */
/** @defgroup RING_BUFFER_Private_Variables
* @{
*/
/*@} end of group RING_BUFFER_Private_Variables */
/** @defgroup RING_BUFFER_Global_Variables
* @{
*/
/*@} end of group RING_BUFFER_Global_Variables */
/** @defgroup RING_BUFFER_Private_Functions
* @{
*/
/*@} end of group RING_BUFFER_Private_Functions */
/** @defgroup RING_BUFFER_Public_Functions
* @{
*/
/****************************************************************************/ /**
* @brief Ring buffer init function
*
* @param rbType: Ring buffer type structure pointer
* @param buffer: Pointer of ring buffer
* @param size: Size of ring buffer
* @param lockCb: Ring buffer lock callback function pointer
* @param unlockCb: Ring buffer unlock callback function pointer
*
* @return SUCCESS
*
*******************************************************************************/
BL_Err_Type Ring_Buffer_Init(Ring_Buffer_Type *rbType, uint8_t *buffer, uint32_t size, ringBuffer_Lock_Callback *lockCb, ringBuffer_Lock_Callback *unlockCb)
{
/* Init ring buffer pointer */
rbType->pointer = buffer;
/* Init read/write mirror and index */
rbType->readMirror = 0;
rbType->readIndex = 0;
rbType->writeMirror = 0;
rbType->writeIndex = 0;
/* Set ring buffer size */
rbType->size = size;
/* Set lock and unlock callback function */
rbType->lock = lockCb;
rbType->unlock = unlockCb;
return SUCCESS;
}
/****************************************************************************/ /**
* @brief Ring buffer reset function
*
* @param rbType: Ring buffer type structure pointer
*
* @return SUCCESS
*
*******************************************************************************/
BL_Err_Type Ring_Buffer_Reset(Ring_Buffer_Type *rbType)
{
if (rbType->lock != NULL) {
rbType->lock();
}
/* Clear read/write mirror and index */
rbType->readMirror = 0;
rbType->readIndex = 0;
rbType->writeMirror = 0;
rbType->writeIndex = 0;
if (rbType->unlock != NULL) {
rbType->unlock();
}
return SUCCESS;
}
/****************************************************************************/ /**
* @brief Use callback function to write ring buffer function
*
* @param rbType: Ring buffer type structure pointer
* @param length: Length of data want to write
* @param writeCb: Callback function pointer
* @param parameter: Parameter that callback function may use
*
* @return Length of data actually write
*
*******************************************************************************/
uint32_t Ring_Buffer_Write_Callback(Ring_Buffer_Type *rbType, uint32_t length, ringBuffer_Write_Callback *writeCb, void *parameter)
{
uint32_t sizeRemained = Ring_Buffer_Get_Empty_Length(rbType);
if (writeCb == NULL) {
return 0;
}
if (rbType->lock != NULL) {
rbType->lock();
}
/* Ring buffer has no space for new data */
if (sizeRemained == 0) {
if (rbType->unlock != NULL) {
rbType->unlock();
}
return 0;
}
/* Drop part of data when length out of space remained */
if (length > sizeRemained) {
length = sizeRemained;
}
/* Get size of space remained in current mirror */
sizeRemained = rbType->size - rbType->writeIndex;
if (sizeRemained > length) {
/* Space remained is enough for data in current mirror */
writeCb(parameter, &rbType->pointer[rbType->writeIndex], length);
rbType->writeIndex += length;
} else {
/* Data is divided to two parts with different mirror */
writeCb(parameter, &rbType->pointer[rbType->writeIndex], sizeRemained);
writeCb(parameter, &rbType->pointer[0], length - sizeRemained);
rbType->writeIndex = length - sizeRemained;
rbType->writeMirror = ~rbType->writeMirror;
}
if (rbType->unlock != NULL) {
rbType->unlock();
}
return length;
}
/****************************************************************************/ /**
* @brief Copy data from data buffer to ring buffer function
*
* @param parameter: Pointer to source pointer
* @param dest: Ring buffer to write
* @param length: Length of data to write
*
* @return None
*
*******************************************************************************/
static void Ring_Buffer_Write_Copy(void *parameter, uint8_t *dest, uint32_t length)
{
uint8_t **src = (uint8_t **)parameter;
ARCH_MemCpy_Fast(dest, *src, length);
*src += length;
}
/****************************************************************************/ /**
* @brief Write ring buffer function
*
* @param rbType: Ring buffer type structure pointer
* @param data: Data to write
* @param length: Length of data
*
* @return Length of data writted actually
*
*******************************************************************************/
uint32_t Ring_Buffer_Write(Ring_Buffer_Type *rbType, const uint8_t *data, uint32_t length)
{
return Ring_Buffer_Write_Callback(rbType, length, Ring_Buffer_Write_Copy, &data);
}
/****************************************************************************/ /**
* @brief Write 1 byte to ring buffer function
*
* @param rbType: Ring buffer type structure pointer
* @param data: Data to write
*
* @return Length of data writted actually
*
*******************************************************************************/
uint32_t Ring_Buffer_Write_Byte(Ring_Buffer_Type *rbType, const uint8_t data)
{
if (rbType->lock != NULL) {
rbType->lock();
}
/* Ring buffer has no space for new data */
if (!Ring_Buffer_Get_Empty_Length(rbType)) {
if (rbType->unlock != NULL) {
rbType->unlock();
}
return 0;
}
rbType->pointer[rbType->writeIndex] = data;
/* Judge to change index and mirror */
if (rbType->writeIndex != (rbType->size - 1)) {
rbType->writeIndex++;
} else {
rbType->writeIndex = 0;
rbType->writeMirror = ~rbType->writeMirror;
}
if (rbType->unlock != NULL) {
rbType->unlock();
}
return 1;
}
/****************************************************************************/ /**
* @brief Write ring buffer function, old data will be covered by new data when ring buffer is
* full
*
* @param rbType: Ring buffer type structure pointer
* @param data: Data to write
* @param length: Length of data
*
* @return Length of data writted actually
*
*******************************************************************************/
uint32_t Ring_Buffer_Write_Force(Ring_Buffer_Type *rbType, const uint8_t *data, uint32_t length)
{
uint32_t sizeRemained = Ring_Buffer_Get_Empty_Length(rbType);
uint32_t indexRemained = rbType->size - rbType->writeIndex;
if (rbType->lock != NULL) {
rbType->lock();
}
/* Drop extra data when data length is large than size of ring buffer */
if (length > rbType->size) {
data = &data[length - rbType->size];
length = rbType->size;
}
if (indexRemained > length) {
/* Space remained is enough for data in current mirror */
ARCH_MemCpy_Fast(&rbType->pointer[rbType->writeIndex], data, length);
rbType->writeIndex += length;
/* Update read index */
if (length > sizeRemained) {
rbType->readIndex = rbType->writeIndex;
}
} else {
/* Data is divided to two parts with different mirror */
ARCH_MemCpy_Fast(&rbType->pointer[rbType->writeIndex], data, indexRemained);
ARCH_MemCpy_Fast(&rbType->pointer[0], &data[indexRemained], length - indexRemained);
rbType->writeIndex = length - indexRemained;
rbType->writeMirror = ~rbType->writeMirror;
/* Update read index and mirror */
if (length > sizeRemained) {
rbType->readIndex = rbType->writeIndex;
rbType->readMirror = ~rbType->readMirror;
}
}
if (rbType->unlock != NULL) {
rbType->unlock();
}
return length;
}
/****************************************************************************/ /**
* @brief Write 1 byte to ring buffer function, old data will be covered by new data when ring
* buffer is full
*
* @param rbType: Ring buffer type structure pointer
* @param data: Data to write
*
* @return Length of data writted actually
*
*******************************************************************************/
uint32_t Ring_Buffer_Write_Byte_Force(Ring_Buffer_Type *rbType, const uint8_t data)
{
Ring_Buffer_Status_Type status = Ring_Buffer_Get_Status(rbType);
if (rbType->lock != NULL) {
rbType->lock();
}
rbType->pointer[rbType->writeIndex] = data;
/* Judge to change index and mirror */
if (rbType->writeIndex == rbType->size - 1) {
rbType->writeIndex = 0;
rbType->writeMirror = ~rbType->writeMirror;
/* Update read index and mirror */
if (status == RING_BUFFER_FULL) {
rbType->readIndex = rbType->writeIndex;
rbType->readMirror = ~rbType->readMirror;
}
} else {
rbType->writeIndex++;
/* Update read index */
if (status == RING_BUFFER_FULL) {
rbType->readIndex = rbType->writeIndex;
}
}
if (rbType->unlock != NULL) {
rbType->unlock();
}
return 1;
}
/****************************************************************************/ /**
* @brief Use callback function to read ring buffer function
*
* @param rbType: Ring buffer type structure pointer
* @param length: Length of data want to read
* @param readCb: Callback function pointer
* @param parameter: Parameter that callback function may use
*
* @return Length of data actually read
*
*******************************************************************************/
uint32_t Ring_Buffer_Read_Callback(Ring_Buffer_Type *rbType, uint32_t length, ringBuffer_Read_Callback *readCb, void *parameter)
{
uint32_t size = Ring_Buffer_Get_Length(rbType);
if (readCb == NULL) {
return 0;
}
if (rbType->lock != NULL) {
rbType->lock();
}
/* Ring buffer has no data */
if (!size) {
if (rbType->unlock != NULL) {
rbType->unlock();
}
return 0;
}
/* Ring buffer do not have enough data */
if (size < length) {
length = size;
}
/* Get size of space remained in current mirror */
size = rbType->size - rbType->readIndex;
if (size > length) {
/* Read all data needed */
readCb(parameter, &rbType->pointer[rbType->readIndex], length);
rbType->readIndex += length;
} else {
/* Read two part of data in different mirror */
readCb(parameter, &rbType->pointer[rbType->readIndex], size);
readCb(parameter, &rbType->pointer[0], length - size);
rbType->readIndex = length - size;
rbType->readMirror = ~rbType->readMirror;
}
if (rbType->unlock != NULL) {
rbType->unlock();
}
return length;
}
/****************************************************************************/ /**
* @brief Copy data from ring buffer to data buffer function
*
* @param parameter: Pointer to destination pointer
* @param data: Data buffer to copy
* @param length: Length of data to copy
*
* @return None
*
*******************************************************************************/
static void Ring_Buffer_Read_Copy(void *parameter, uint8_t *data, uint32_t length)
{
uint8_t **dest = (uint8_t **)parameter;
ARCH_MemCpy_Fast(*dest, data, length);
*dest += length;
}
/****************************************************************************/ /**
* @brief Read ring buffer function
*
* @param rbType: Ring buffer type structure pointer
* @param data: Buffer for data read
* @param length: Length of data to read
*
* @return Length of data read actually
*
*******************************************************************************/
uint32_t Ring_Buffer_Read(Ring_Buffer_Type *rbType, uint8_t *data, uint32_t length)
{
return Ring_Buffer_Read_Callback(rbType, length, Ring_Buffer_Read_Copy, &data);
}
/****************************************************************************/ /**
* @brief Read 1 byte from ring buffer function
*
* @param rbType: Ring buffer type structure pointer
* @param data: Data read
*
* @return Length of data actually read
*
*******************************************************************************/
uint32_t Ring_Buffer_Read_Byte(Ring_Buffer_Type *rbType, uint8_t *data)
{
if (rbType->lock != NULL) {
rbType->lock();
}
/* Ring buffer has no data */
if (!Ring_Buffer_Get_Length(rbType)) {
if (rbType->unlock != NULL) {
rbType->unlock();
}
return 0;
}
/* Read data */
*data = rbType->pointer[rbType->readIndex];
/* Update read index and mirror */
if (rbType->readIndex == rbType->size - 1) {
rbType->readIndex = 0;
rbType->readMirror = ~rbType->readMirror;
} else {
rbType->readIndex++;
}
if (rbType->unlock != NULL) {
rbType->unlock();
}
return 1;
}
/****************************************************************************/ /**
* @brief Read ring buffer function, do not remove from buffer actually
*
* @param rbType: Ring buffer type structure pointer
* @param data: Buffer for data read
* @param length: Length of data to read
*
* @return Length of data read actually
*
*******************************************************************************/
uint32_t Ring_Buffer_Peek(Ring_Buffer_Type *rbType, uint8_t *data, uint32_t length)
{
uint32_t size = Ring_Buffer_Get_Length(rbType);
if (rbType->lock != NULL) {
rbType->lock();
}
/* Ring buffer has no data */
if (!size) {
if (rbType->unlock != NULL) {
rbType->unlock();
}
return 0;
}
/* Ring buffer do not have enough data */
if (size < length) {
length = size;
}
/* Get size of space remained in current mirror */
size = rbType->size - rbType->readIndex;
if (size > length) {
/* Read all data needed */
ARCH_MemCpy_Fast(data, &rbType->pointer[rbType->readIndex], length);
} else {
/* Read two part of data in different mirror */
ARCH_MemCpy_Fast(data, &rbType->pointer[rbType->readIndex], size);
ARCH_MemCpy_Fast(&data[size], &rbType->pointer[0], length - size);
}
if (rbType->unlock != NULL) {
rbType->unlock();
}
return length;
}
/****************************************************************************/ /**
* @brief Read 1 byte from ring buffer function, do not remove from buffer actually
*
* @param rbType: Ring buffer type structure pointer
* @param data: Data read
*
* @return Length of data actually read
*
*******************************************************************************/
uint32_t Ring_Buffer_Peek_Byte(Ring_Buffer_Type *rbType, uint8_t *data)
{
if (rbType->lock != NULL) {
rbType->lock();
}
/* Ring buffer has no data */
if (!Ring_Buffer_Get_Length(rbType)) {
if (rbType->unlock != NULL) {
rbType->unlock();
}
return 0;
}
/* Read data */
*data = rbType->pointer[rbType->readIndex];
if (rbType->unlock != NULL) {
rbType->unlock();
}
return 1;
}
/****************************************************************************/ /**
* @brief Get length of data in ring buffer function
*
* @param rbType: Ring buffer type structure pointer
*
* @return Length of data
*
*******************************************************************************/
uint32_t Ring_Buffer_Get_Length(Ring_Buffer_Type *rbType)
{
uint32_t readMirror = 0;
uint32_t writeMirror = 0;
uint32_t readIndex = 0;
uint32_t writeIndex = 0;
uint32_t size = 0;
if (rbType->lock != NULL) {
rbType->lock();
}
readMirror = rbType->readMirror;
writeMirror = rbType->writeMirror;
readIndex = rbType->readIndex;
writeIndex = rbType->writeIndex;
size = rbType->size;
if (rbType->unlock != NULL) {
rbType->unlock();
}
if (readMirror == writeMirror) {
return writeIndex - readIndex;
} else {
return size - (readIndex - writeIndex);
}
}
/****************************************************************************/ /**
* @brief Get space remained in ring buffer function
*
* @param rbType: Ring buffer type structure pointer
*
* @return Length of space remained
*
*******************************************************************************/
uint32_t Ring_Buffer_Get_Empty_Length(Ring_Buffer_Type *rbType)
{
return (rbType->size - Ring_Buffer_Get_Length(rbType));
}
/****************************************************************************/ /**
* @brief Get ring buffer status function
*
* @param rbType: Ring buffer type structure pointer
*
* @return Status of ring buffer
*
*******************************************************************************/
Ring_Buffer_Status_Type Ring_Buffer_Get_Status(Ring_Buffer_Type *rbType)
{
if (rbType->lock != NULL) {
rbType->lock();
}
/* Judge empty or full */
if (rbType->readIndex == rbType->writeIndex) {
if (rbType->readMirror == rbType->writeMirror) {
if (rbType->unlock != NULL) {
rbType->unlock();
}
return RING_BUFFER_EMPTY;
} else {
if (rbType->unlock != NULL) {
rbType->unlock();
}
return RING_BUFFER_FULL;
}
}
if (rbType->unlock != NULL) {
rbType->unlock();
}
return RING_BUFFER_PARTIAL;
}
/*@} end of group RING_BUFFER_Public_Functions */
/*@} end of group RING_BUFFER */
/*@} end of group BL_Common_Component */

View File

@@ -0,0 +1,116 @@
/**
* @file ring_buffer.h
* @brief
*
* Copyright (c) 2021 Bouffalolab team
*
* Licensed to the Apache Software Foundation (ASF) under one or more
* contributor license agreements. See the NOTICE file distributed with
* this work for additional information regarding copyright ownership. The
* ASF licenses this file to you under the Apache License, Version 2.0 (the
* "License"); you may not use this file except in compliance with the
* License. You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
* License for the specific language governing permissions and limitations
* under the License.
*
*/
#ifndef __RING_BUFFER_H__
#define __RING_BUFFER_H__
#include "misc.h"
/** @addtogroup BL_Common_Component
* @{
*/
/** @addtogroup RING_BUFFER
* @{
*/
/** @defgroup RING_BUFFER_Public_Types
* @{
*/
/**
* @brief Ring buffer status type definition
*/
typedef enum {
RING_BUFFER_EMPTY, /*!< Ring buffer is empty */
RING_BUFFER_PARTIAL, /*!< Ring buffer has partial data */
RING_BUFFER_FULL, /*!< Ring buffer is full */
} Ring_Buffer_Status_Type;
/**
* @brief Ring buffer structure definition
*/
typedef struct
{
uint8_t *pointer; /*!< Pointer of ring buffer */
uint8_t readMirror; /*!< Read mirror,used to judge empty or full */
uint32_t readIndex; /*!< Index of read address */
uint8_t writeMirror; /*!< Write mirror,used to judge empty or full */
uint32_t writeIndex; /*!< Index of write address */
uint32_t size; /*!< Size of ring buffer */
void (*lock)(void); /*!< Lock ring buffer */
void (*unlock)(void); /*!< Unlock ring buffer */
} Ring_Buffer_Type;
/*@} end of group RING_BUFFER_Public_Types */
/** @defgroup RING_BUFFER_Public_Constants
* @{
*/
/** @defgroup RING_BUFFER_STATUS_TYPE
* @{
*/
#define IS_RING_BUFFER_STATUS_TYPE(type) (((type) == RING_BUFFER_EMPTY) || \
((type) == RING_BUFFER_PARTIAL) || \
((type) == RING_BUFFER_FULL))
/*@} end of group RING_BUFFER_Public_Constants */
/** @defgroup RING_BUFFER_Public_Macros
* @{
*/
typedef void(ringBuffer_Lock_Callback)(void);
typedef void(ringBuffer_Read_Callback)(void *, uint8_t *, uint32_t);
typedef void(ringBuffer_Write_Callback)(void *, uint8_t *, uint32_t);
/*@} end of group RING_BUFFER_Public_Macros */
/** @defgroup RING_BUFFER_Public_Functions
* @{
*/
BL_Err_Type Ring_Buffer_Init(Ring_Buffer_Type *rbType, uint8_t *buffer, uint32_t size, ringBuffer_Lock_Callback *lockCb,
ringBuffer_Lock_Callback *unlockCb);
BL_Err_Type Ring_Buffer_Reset(Ring_Buffer_Type *rbType);
uint32_t Ring_Buffer_Write_Callback(Ring_Buffer_Type *rbType, uint32_t length, ringBuffer_Write_Callback *writeCb,
void *parameter);
uint32_t Ring_Buffer_Write(Ring_Buffer_Type *rbType, const uint8_t *data, uint32_t length);
uint32_t Ring_Buffer_Write_Byte(Ring_Buffer_Type *rbType, const uint8_t data);
uint32_t Ring_Buffer_Write_Force(Ring_Buffer_Type *rbType, const uint8_t *data, uint32_t length);
uint32_t Ring_Buffer_Write_Byte_Force(Ring_Buffer_Type *rbType, const uint8_t data);
uint32_t Ring_Buffer_Read_Callback(Ring_Buffer_Type *rbType, uint32_t length, ringBuffer_Read_Callback *readCb,
void *parameter);
uint32_t Ring_Buffer_Read(Ring_Buffer_Type *rbType, uint8_t *data, uint32_t length);
uint32_t Ring_Buffer_Read_Byte(Ring_Buffer_Type *rbType, uint8_t *data);
uint32_t Ring_Buffer_Peek(Ring_Buffer_Type *rbType, uint8_t *data, uint32_t length);
uint32_t Ring_Buffer_Peek_Byte(Ring_Buffer_Type *rbType, uint8_t *data);
uint32_t Ring_Buffer_Get_Length(Ring_Buffer_Type *rbType);
uint32_t Ring_Buffer_Get_Empty_Length(Ring_Buffer_Type *rbType);
Ring_Buffer_Status_Type Ring_Buffer_Get_Status(Ring_Buffer_Type *rbType);
/*@} end of group RING_BUFFER_Public_Functions */
/*@} end of group RING_BUFFER */
/*@} end of group BL_Common_Component */
#endif /* __RING_BUFFER_H__ */

View File

@@ -0,0 +1,194 @@
/**
* @file softcrc.c
* @brief
*
* Copyright (c) 2021 Bouffalolab team
*
* Licensed to the Apache Software Foundation (ASF) under one or more
* contributor license agreements. See the NOTICE file distributed with
* this work for additional information regarding copyright ownership. The
* ASF licenses this file to you under the Apache License, Version 2.0 (the
* "License"); you may not use this file except in compliance with the
* License. You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
* License for the specific language governing permissions and limitations
* under the License.
*
*/
#include "softcrc.h"
#include "misc.h"
// ---------------- POPULAR POLYNOMIALS ----------------
// CCITT: x^16 + x^12 + x^5 + x^0 (0x1021,init 0x0000)
// CRC-16: x^16 + x^15 + x^2 + x^0 (0x8005,init 0xFFFF)
// we use 0x8005 here and
const uint8_t chCRCHTalbe[] = {
0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41,
0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40,
0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41,
0x00, 0xC1, 0x81, 0x40, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41,
0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41,
0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40,
0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40,
0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40,
0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41,
0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40,
0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41,
0x00, 0xC1, 0x81, 0x40, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41,
0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41,
0x00, 0xC1, 0x81, 0x40, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41,
0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41,
0x00, 0xC1, 0x81, 0x40, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41,
0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41,
0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40,
0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41,
0x00, 0xC1, 0x81, 0x40, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41,
0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41,
0x00, 0xC1, 0x81, 0x40
};
const uint8_t chCRCLTalbe[] = {
0x00, 0xC0, 0xC1, 0x01, 0xC3, 0x03, 0x02, 0xC2, 0xC6, 0x06, 0x07, 0xC7,
0x05, 0xC5, 0xC4, 0x04, 0xCC, 0x0C, 0x0D, 0xCD, 0x0F, 0xCF, 0xCE, 0x0E,
0x0A, 0xCA, 0xCB, 0x0B, 0xC9, 0x09, 0x08, 0xC8, 0xD8, 0x18, 0x19, 0xD9,
0x1B, 0xDB, 0xDA, 0x1A, 0x1E, 0xDE, 0xDF, 0x1F, 0xDD, 0x1D, 0x1C, 0xDC,
0x14, 0xD4, 0xD5, 0x15, 0xD7, 0x17, 0x16, 0xD6, 0xD2, 0x12, 0x13, 0xD3,
0x11, 0xD1, 0xD0, 0x10, 0xF0, 0x30, 0x31, 0xF1, 0x33, 0xF3, 0xF2, 0x32,
0x36, 0xF6, 0xF7, 0x37, 0xF5, 0x35, 0x34, 0xF4, 0x3C, 0xFC, 0xFD, 0x3D,
0xFF, 0x3F, 0x3E, 0xFE, 0xFA, 0x3A, 0x3B, 0xFB, 0x39, 0xF9, 0xF8, 0x38,
0x28, 0xE8, 0xE9, 0x29, 0xEB, 0x2B, 0x2A, 0xEA, 0xEE, 0x2E, 0x2F, 0xEF,
0x2D, 0xED, 0xEC, 0x2C, 0xE4, 0x24, 0x25, 0xE5, 0x27, 0xE7, 0xE6, 0x26,
0x22, 0xE2, 0xE3, 0x23, 0xE1, 0x21, 0x20, 0xE0, 0xA0, 0x60, 0x61, 0xA1,
0x63, 0xA3, 0xA2, 0x62, 0x66, 0xA6, 0xA7, 0x67, 0xA5, 0x65, 0x64, 0xA4,
0x6C, 0xAC, 0xAD, 0x6D, 0xAF, 0x6F, 0x6E, 0xAE, 0xAA, 0x6A, 0x6B, 0xAB,
0x69, 0xA9, 0xA8, 0x68, 0x78, 0xB8, 0xB9, 0x79, 0xBB, 0x7B, 0x7A, 0xBA,
0xBE, 0x7E, 0x7F, 0xBF, 0x7D, 0xBD, 0xBC, 0x7C, 0xB4, 0x74, 0x75, 0xB5,
0x77, 0xB7, 0xB6, 0x76, 0x72, 0xB2, 0xB3, 0x73, 0xB1, 0x71, 0x70, 0xB0,
0x50, 0x90, 0x91, 0x51, 0x93, 0x53, 0x52, 0x92, 0x96, 0x56, 0x57, 0x97,
0x55, 0x95, 0x94, 0x54, 0x9C, 0x5C, 0x5D, 0x9D, 0x5F, 0x9F, 0x9E, 0x5E,
0x5A, 0x9A, 0x9B, 0x5B, 0x99, 0x59, 0x58, 0x98, 0x88, 0x48, 0x49, 0x89,
0x4B, 0x8B, 0x8A, 0x4A, 0x4E, 0x8E, 0x8F, 0x4F, 0x8D, 0x4D, 0x4C, 0x8C,
0x44, 0x84, 0x85, 0x45, 0x87, 0x47, 0x46, 0x86, 0x82, 0x42, 0x43, 0x83,
0x41, 0x81, 0x80, 0x40
};
uint16_t BFLB_Soft_CRC16(void *dataIn, uint32_t len)
{
uint8_t chCRCHi = 0xFF;
uint8_t chCRCLo = 0xFF;
uint16_t wIndex;
uint8_t *data = (uint8_t *)dataIn;
while (len--) {
wIndex = chCRCLo ^ *data++;
chCRCLo = chCRCHi ^ chCRCHTalbe[wIndex];
chCRCHi = chCRCLTalbe[wIndex];
}
return ((chCRCHi << 8) | chCRCLo);
}
/*
x^32+x^26+x^23+x^22+x^16+x^12+x^11+x^10+x^8+x^7+x^5+x^4+x^2+x+1
*/
const uint32_t crc32Tab[256] = {
0x00000000, 0x77073096, 0xee0e612c, 0x990951ba, 0x076dc419, 0x706af48f,
0xe963a535, 0x9e6495a3, 0x0edb8832, 0x79dcb8a4, 0xe0d5e91e, 0x97d2d988,
0x09b64c2b, 0x7eb17cbd, 0xe7b82d07, 0x90bf1d91, 0x1db71064, 0x6ab020f2,
0xf3b97148, 0x84be41de, 0x1adad47d, 0x6ddde4eb, 0xf4d4b551, 0x83d385c7,
0x136c9856, 0x646ba8c0, 0xfd62f97a, 0x8a65c9ec, 0x14015c4f, 0x63066cd9,
0xfa0f3d63, 0x8d080df5, 0x3b6e20c8, 0x4c69105e, 0xd56041e4, 0xa2677172,
0x3c03e4d1, 0x4b04d447, 0xd20d85fd, 0xa50ab56b, 0x35b5a8fa, 0x42b2986c,
0xdbbbc9d6, 0xacbcf940, 0x32d86ce3, 0x45df5c75, 0xdcd60dcf, 0xabd13d59,
0x26d930ac, 0x51de003a, 0xc8d75180, 0xbfd06116, 0x21b4f4b5, 0x56b3c423,
0xcfba9599, 0xb8bda50f, 0x2802b89e, 0x5f058808, 0xc60cd9b2, 0xb10be924,
0x2f6f7c87, 0x58684c11, 0xc1611dab, 0xb6662d3d, 0x76dc4190, 0x01db7106,
0x98d220bc, 0xefd5102a, 0x71b18589, 0x06b6b51f, 0x9fbfe4a5, 0xe8b8d433,
0x7807c9a2, 0x0f00f934, 0x9609a88e, 0xe10e9818, 0x7f6a0dbb, 0x086d3d2d,
0x91646c97, 0xe6635c01, 0x6b6b51f4, 0x1c6c6162, 0x856530d8, 0xf262004e,
0x6c0695ed, 0x1b01a57b, 0x8208f4c1, 0xf50fc457, 0x65b0d9c6, 0x12b7e950,
0x8bbeb8ea, 0xfcb9887c, 0x62dd1ddf, 0x15da2d49, 0x8cd37cf3, 0xfbd44c65,
0x4db26158, 0x3ab551ce, 0xa3bc0074, 0xd4bb30e2, 0x4adfa541, 0x3dd895d7,
0xa4d1c46d, 0xd3d6f4fb, 0x4369e96a, 0x346ed9fc, 0xad678846, 0xda60b8d0,
0x44042d73, 0x33031de5, 0xaa0a4c5f, 0xdd0d7cc9, 0x5005713c, 0x270241aa,
0xbe0b1010, 0xc90c2086, 0x5768b525, 0x206f85b3, 0xb966d409, 0xce61e49f,
0x5edef90e, 0x29d9c998, 0xb0d09822, 0xc7d7a8b4, 0x59b33d17, 0x2eb40d81,
0xb7bd5c3b, 0xc0ba6cad, 0xedb88320, 0x9abfb3b6, 0x03b6e20c, 0x74b1d29a,
0xead54739, 0x9dd277af, 0x04db2615, 0x73dc1683, 0xe3630b12, 0x94643b84,
0x0d6d6a3e, 0x7a6a5aa8, 0xe40ecf0b, 0x9309ff9d, 0x0a00ae27, 0x7d079eb1,
0xf00f9344, 0x8708a3d2, 0x1e01f268, 0x6906c2fe, 0xf762575d, 0x806567cb,
0x196c3671, 0x6e6b06e7, 0xfed41b76, 0x89d32be0, 0x10da7a5a, 0x67dd4acc,
0xf9b9df6f, 0x8ebeeff9, 0x17b7be43, 0x60b08ed5, 0xd6d6a3e8, 0xa1d1937e,
0x38d8c2c4, 0x4fdff252, 0xd1bb67f1, 0xa6bc5767, 0x3fb506dd, 0x48b2364b,
0xd80d2bda, 0xaf0a1b4c, 0x36034af6, 0x41047a60, 0xdf60efc3, 0xa867df55,
0x316e8eef, 0x4669be79, 0xcb61b38c, 0xbc66831a, 0x256fd2a0, 0x5268e236,
0xcc0c7795, 0xbb0b4703, 0x220216b9, 0x5505262f, 0xc5ba3bbe, 0xb2bd0b28,
0x2bb45a92, 0x5cb36a04, 0xc2d7ffa7, 0xb5d0cf31, 0x2cd99e8b, 0x5bdeae1d,
0x9b64c2b0, 0xec63f226, 0x756aa39c, 0x026d930a, 0x9c0906a9, 0xeb0e363f,
0x72076785, 0x05005713, 0x95bf4a82, 0xe2b87a14, 0x7bb12bae, 0x0cb61b38,
0x92d28e9b, 0xe5d5be0d, 0x7cdcefb7, 0x0bdbdf21, 0x86d3d2d4, 0xf1d4e242,
0x68ddb3f8, 0x1fda836e, 0x81be16cd, 0xf6b9265b, 0x6fb077e1, 0x18b74777,
0x88085ae6, 0xff0f6a70, 0x66063bca, 0x11010b5c, 0x8f659eff, 0xf862ae69,
0x616bffd3, 0x166ccf45, 0xa00ae278, 0xd70dd2ee, 0x4e048354, 0x3903b3c2,
0xa7672661, 0xd06016f7, 0x4969474d, 0x3e6e77db, 0xaed16a4a, 0xd9d65adc,
0x40df0b66, 0x37d83bf0, 0xa9bcae53, 0xdebb9ec5, 0x47b2cf7f, 0x30b5ffe9,
0xbdbdf21c, 0xcabac28a, 0x53b39330, 0x24b4a3a6, 0xbad03605, 0xcdd70693,
0x54de5729, 0x23d967bf, 0xb3667a2e, 0xc4614ab8, 0x5d681b02, 0x2a6f2b94,
0xb40bbe37, 0xc30c8ea1, 0x5a05df1b, 0x2d02ef8d
};
uint32_t BFLB_Soft_CRC32_Table(void *dataIn, uint32_t len)
{
uint32_t crc = 0;
uint8_t *data = (uint8_t *)dataIn;
crc = crc ^ 0xffffffff;
while (len--) {
crc = crc32Tab[(crc ^ *data++) & 0xFF] ^ (crc >> 8);
}
return crc ^ 0xffffffff;
}
/******************************************************************************
* Name: CRC-32 x32+x26+x23+x22+x16+x12+x11+x10+x8+x7+x5+x4+x2+x+1
* Poly: 0x4C11DB7
* Init: 0xFFFFFFF
* Refin: True
* Refout: True
* Xorout: 0xFFFFFFF
* Alias: CRC_32/ADCCP
* Use: WinRAR,ect.
*****************************************************************************/
uint32_t ATTR_TCM_SECTION BFLB_Soft_CRC32_Ex(uint32_t initial, void *dataIn, uint32_t len)
{
uint8_t i;
uint32_t crc = ~initial; // Initial value
uint8_t *data=(uint8_t *)dataIn;
while(len--){
crc ^= *data++; // crc ^= *data; data++;
for (i = 0; i < 8; ++i){
if (crc & 1){
crc = (crc >> 1) ^ 0xEDB88320;// 0xEDB88320= reverse 0x04C11DB7
}else{
crc = (crc >> 1);
}
}
}
return ~crc;
}
#ifndef BFLB_USE_ROM_DRIVER
__WEAK__
uint32_t ATTR_TCM_SECTION BFLB_Soft_CRC32(void *dataIn, uint32_t len)
{
return BFLB_Soft_CRC32_Ex(0,dataIn,len);
}
#endif

View File

@@ -0,0 +1,32 @@
/**
* @file softcrc.h
* @brief
*
* Copyright (c) 2021 Bouffalolab team
*
* Licensed to the Apache Software Foundation (ASF) under one or more
* contributor license agreements. See the NOTICE file distributed with
* this work for additional information regarding copyright ownership. The
* ASF licenses this file to you under the Apache License, Version 2.0 (the
* "License"); you may not use this file except in compliance with the
* License. You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
* License for the specific language governing permissions and limitations
* under the License.
*
*/
#ifndef __SOFTCRC_H__
#define __SOFTCRC_H__
#include "stdint.h"
uint16_t BFLB_Soft_CRC16(void *dataIn, uint32_t len);
uint32_t BFLB_Soft_CRC32_Ex(uint32_t initial, void *dataIn, uint32_t len);
uint32_t BFLB_Soft_CRC32(void *dataIn, uint32_t len);
#endif

View File

@@ -0,0 +1,136 @@
/**
* @file timestamp.c
* @brief
*
* Copyright (c) 2021 Bouffalolab team
*
* Licensed to the Apache Software Foundation (ASF) under one or more
* contributor license agreements. See the NOTICE file distributed with
* this work for additional information regarding copyright ownership. The
* ASF licenses this file to you under the Apache License, Version 2.0 (the
* "License"); you may not use this file except in compliance with the
* License. You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
* License for the specific language governing permissions and limitations
* under the License.
*
*/
#include "timestamp.h"
#define FOUR_YEAR_DAY ((365 << 2) + 1) //The total number of days in a 4-year cycle
#define TIMEZONE (8) //Beijing time Zone adjustment
#define SEC_NUM_PER_DAY (24 * 60 * 60)
#define SEC_NUM_PER_HOUR (60 * 60)
#define SEC_NUM_PER_MINUTE (60)
static uint8_t month_day[12] = { 31, 28, 31, 30, 31, 30, 31, 31, 30, 31, 30, 31 }; //平年
static uint8_t Leap_month_day[12] = { 31, 29, 31, 30, 31, 30, 31, 31, 30, 31, 30, 31 }; //闰年
/**
* @bref judge if it is a leap year
* @para year to be judge
* @return 1leap year 0 nonleap year
*/
bool check_leap_year(uint16_t year)
{
if (year % 4) {
return false;
} else {
if ((year % 100 == 0) && (year % 400 != 0)) {
return false;
} else {
return true;
}
}
}
void cal_weekday(rtc_time *beijing_time)
{
uint32_t y,m,d,w;
y=beijing_time->year;
m=beijing_time->month;
d=beijing_time->day;
if((m==1)||(m==2))
{
m+=12;
y--;
}
/*
把一月和二月看成是上一年的十三月和十四月如果是2004-1-10则换算成2003-13-10来代入公式计算。
以公元元年为参考公元元年1月1日为星期一</PRE><PRE>程序如下:
利用基姆拉尔森计算日期公式 w=(d+2*m+3*(m+1)/5+y+y/4-y/100+y/400)
*/
w=(d+2*m+3*(m+1)/5+y+y/4-y/100+y/400+1)%7;
beijing_time->week=(uint8_t)w;
}
void unixtime2bejingtime(uint32_t unixtime, rtc_time *beijing_time)
{
uint32_t totle_day_num;
uint32_t current_sec_num;
uint16_t remain_day;
uint16_t temp_year;
uint8_t *p = NULL;
totle_day_num = unixtime / SEC_NUM_PER_DAY; //The total number of days
current_sec_num = unixtime % SEC_NUM_PER_DAY; //The number of seconds this day
/* use the number of seconds this day, To calculate hour\minute\second */
beijing_time->hour = current_sec_num / SEC_NUM_PER_HOUR;
beijing_time->minute = (current_sec_num % SEC_NUM_PER_HOUR) / SEC_NUM_PER_MINUTE;
beijing_time->second = (current_sec_num % SEC_NUM_PER_HOUR) % SEC_NUM_PER_MINUTE;
/* Adjust the time zone and check whether the date is +1 */
beijing_time->hour += 8;
if (beijing_time->hour > 23) {
beijing_time->hour -= 24;
totle_day_num++;
}
/* calculate year */
beijing_time->year = 1970 + (totle_day_num / FOUR_YEAR_DAY) * 4; // 4-year as a cycle
remain_day = totle_day_num % FOUR_YEAR_DAY; //remaining day nym( < 4 year )
/* calculate year & day */
temp_year = check_leap_year(beijing_time->year) ? 366 : 365;
while (remain_day >= temp_year) {
beijing_time->year++;
remain_day -= temp_year;
temp_year = check_leap_year(beijing_time->year) ? 366 : 365;
}
/* Calculate specific dates(month\day)*/
p = check_leap_year(beijing_time->year) ? Leap_month_day : month_day;
remain_day++; //The actual day starts at 1
beijing_time->month = 0;
while (remain_day > *(p + beijing_time->month)) {
remain_day -= *(p + beijing_time->month);
beijing_time->month++;
}
beijing_time->month++; //The actual month starts at 1
beijing_time->day = remain_day;
/*利用基姆拉尔森计算日期公式 w=(d+2*m+3*(m+1)/5+y+y/4-y/100+y/400)*/
beijing_time->week = beijing_time->day + 2*beijing_time->month + 3*(beijing_time->month+1)/5 + \
beijing_time->year + beijing_time->year/4 - beijing_time->year/100 +beijing_time->year/400 ;
cal_weekday(beijing_time);
}

View File

@@ -0,0 +1,45 @@
/**
* @file timestamp.h
* @brief
*
* Copyright (c) 2021 Bouffalolab team
*
* Licensed to the Apache Software Foundation (ASF) under one or more
* contributor license agreements. See the NOTICE file distributed with
* this work for additional information regarding copyright ownership. The
* ASF licenses this file to you under the Apache License, Version 2.0 (the
* "License"); you may not use this file except in compliance with the
* License. You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
* License for the specific language governing permissions and limitations
* under the License.
*
*/
#ifndef _TIMESTAMP_
#define _TIMESTAMP_
#include "stdint.h"
#include "stddef.h"
#include "stdbool.h"
typedef struct _rtc_time_t
{
uint16_t year;
uint8_t month;
uint8_t day;
uint8_t week;
uint8_t hour;
uint8_t minute;
uint8_t second;
}rtc_time;
void unixtime2bejingtime(uint32_t unixtime,rtc_time* beijing_time);
#endif

View File

@@ -0,0 +1,112 @@
/*
* FreeRTOS Kernel V10.2.1
* Copyright (C) 2019 Amazon.com, Inc. or its affiliates. All Rights Reserved.
*
* Permission is hereby granted, free of charge, to any person obtaining a copy of
* this software and associated documentation files (the "Software"), to deal in
* the Software without restriction, including without limitation the rights to
* use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of
* the Software, and to permit persons to whom the Software is furnished to do so,
* subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in all
* copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS
* FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR
* COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER
* IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN
* CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
*
* http://www.FreeRTOS.org
* http://aws.amazon.com/freertos
*
* 1 tab == 4 spaces!
*/
#ifndef FREERTOS_CONFIG_H
#define FREERTOS_CONFIG_H
/*-----------------------------------------------------------
* Application specific definitions.
*
* These definitions should be adjusted for your particular hardware and
* application requirements.
*
* THESE PARAMETERS ARE DESCRIBED WITHIN THE 'CONFIGURATION' SECTION OF THE
* FreeRTOS API DOCUMENTATION AVAILABLE ON THE FreeRTOS.org WEB SITE.
*
* See http://www.freertos.org/a00110.html.
*----------------------------------------------------------*/
#define configSUPPORT_STATIC_ALLOCATION 1
#define CLINT_CTRL_ADDR (0x02000000UL)
#define configCLINT_BASE_ADDRESS CLINT_CTRL_ADDR
#define configUSE_PREEMPTION 1
#define configUSE_IDLE_HOOK 0
#define configUSE_TICK_HOOK 0
#define configCPU_CLOCK_HZ (1000000UL)
#define configTICK_RATE_HZ ((TickType_t)1000)
#define configMAX_PRIORITIES (7)
#define configMINIMAL_STACK_SIZE ((unsigned short)512) /* Only needs to be this high as some demo tasks also use this constant. In production only the idle task would use this. */
#define configTOTAL_HEAP_SIZE ((size_t)48 * 1024)
#define configMAX_TASK_NAME_LEN (16)
#define configUSE_TRACE_FACILITY 1
#define configUSE_16_BIT_TICKS 0
#define configIDLE_SHOULD_YIELD 0
#define configUSE_MUTEXES 1
#define configQUEUE_REGISTRY_SIZE 8
#define configCHECK_FOR_STACK_OVERFLOW 2
#define configUSE_RECURSIVE_MUTEXES 1
#define configUSE_MALLOC_FAILED_HOOK 1
#define configUSE_APPLICATION_TASK_TAG 0
#define configUSE_COUNTING_SEMAPHORES 1
#define configGENERATE_RUN_TIME_STATS 0
#define configUSE_PORT_OPTIMISED_TASK_SELECTION 1
#define configUSE_STATS_FORMATTING_FUNCTIONS 2
#define configUSE_TICKLESS_IDLE 0
/* Co-routine definitions. */
#define configUSE_CO_ROUTINES 0
#define configMAX_CO_ROUTINE_PRIORITIES (2)
/* Software timer definitions. */
#define configUSE_TIMERS 1
#define configTIMER_TASK_PRIORITY (configMAX_PRIORITIES - 1)
#define configTIMER_QUEUE_LENGTH 8
#define configTIMER_TASK_STACK_DEPTH (160)
/* Task priorities. Allow these to be overridden. */
#ifndef uartPRIMARY_PRIORITY
#define uartPRIMARY_PRIORITY (configMAX_PRIORITIES - 3)
#endif
/* Set the following definitions to 1 to include the API function, or zero
to exclude the API function. */
#define INCLUDE_vTaskPrioritySet 1
#define INCLUDE_uxTaskPriorityGet 1
#define INCLUDE_vTaskDelete 1
#define INCLUDE_vTaskCleanUpResources 1
#define INCLUDE_vTaskSuspend 1
#define INCLUDE_vTaskDelayUntil 1
#define INCLUDE_vTaskDelay 1
#define INCLUDE_eTaskGetState 1
#define INCLUDE_xTimerPendFunctionCall 1
#define INCLUDE_xTaskAbortDelay 1
#define INCLUDE_xTaskGetHandle 1
#define INCLUDE_xSemaphoreGetMutexHolder 1
/* Normal assert() semantics without relying on the provision of an assert.h
header file. */
void vAssertCalled(void);
#define configASSERT(x) \
if ((x) == 0) \
vAssertCalled()
#if (configUSE_TICKLESS_IDLE != 0)
void vApplicationSleep(uint32_t xExpectedIdleTime);
#define portSUPPRESS_TICKS_AND_SLEEP(xExpectedIdleTime) vApplicationSleep(xExpectedIdleTime)
#endif
#define portUSING_MPU_WRAPPERS 0
#endif /* FREERTOS_CONFIG_H */

View File

@@ -0,0 +1,67 @@
/*
* FreeRTOS Kernel V10.2.1
* Copyright (C) 2019 Amazon.com, Inc. or its affiliates. All Rights Reserved.
*
* Permission is hereby granted, free of charge, to any person obtaining a copy of
* this software and associated documentation files (the "Software"), to deal in
* the Software without restriction, including without limitation the rights to
* use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of
* the Software, and to permit persons to whom the Software is furnished to do so,
* subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in all
* copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS
* FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR
* COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER
* IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN
* CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
*
* http://www.FreeRTOS.org
* http://aws.amazon.com/freertos
*
* 1 tab == 4 spaces!
*/
/*
* The FreeRTOS kernel's RISC-V port is split between the the code that is
* common across all currently supported RISC-V chips (implementations of the
* RISC-V ISA), and code that tailors the port to a specific RISC-V chip:
*
* + FreeRTOS\Source\portable\GCC\RISC-V-RV32\portASM.S contains the code that
* is common to all currently supported RISC-V chips. There is only one
* portASM.S file because the same file is built for all RISC-V target chips.
*
* + Header files called freertos_risc_v_chip_specific_extensions.h contain the
* code that tailors the FreeRTOS kernel's RISC-V port to a specific RISC-V
* chip. There are multiple freertos_risc_v_chip_specific_extensions.h files
* as there are multiple RISC-V chip implementations.
*
* !!!NOTE!!!
* TAKE CARE TO INCLUDE THE CORRECT freertos_risc_v_chip_specific_extensions.h
* HEADER FILE FOR THE CHIP IN USE. This is done using the assembler's (not the
* compiler's!) include path. For example, if the chip in use includes a core
* local interrupter (CLINT) and does not include any chip specific register
* extensions then add the path below to the assembler's include path:
* FreeRTOS\Source\portable\GCC\RISC-V-RV32\chip_specific_extensions\RV32I_CLINT_no_extensions
*
*/
#ifndef __FREERTOS_RISC_V_EXTENSIONS_H__
#define __FREERTOS_RISC_V_EXTENSIONS_H__
#define portasmHAS_CLINT 1
#define portasmADDITIONAL_CONTEXT_SIZE 0 /* Must be even number on 32-bit cores. */
.macro portasmSAVE_ADDITIONAL_REGISTERS
/* No additional registers to save, so this macro does nothing. */
.endm
/* Restore the additional registers found on the Pulpino. */
.macro portasmRESTORE_ADDITIONAL_REGISTERS
/* No additional registers to restore, so this macro does nothing. */
.endm
#endif /* __FREERTOS_RISC_V_EXTENSIONS_H__ */

View File

@@ -0,0 +1,195 @@
/*
* FreeRTOS Kernel V10.2.1
* Copyright (C) 2019 Amazon.com, Inc. or its affiliates. All Rights Reserved.
*
* Permission is hereby granted, free of charge, to any person obtaining a copy of
* this software and associated documentation files (the "Software"), to deal in
* the Software without restriction, including without limitation the rights to
* use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of
* the Software, and to permit persons to whom the Software is furnished to do so,
* subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in all
* copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS
* FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR
* COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER
* IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN
* CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
*
* http://www.FreeRTOS.org
* http://aws.amazon.com/freertos
*
* 1 tab == 4 spaces!
*/
/*-----------------------------------------------------------
* Implementation of functions defined in portable.h for the RISC-V RV32 port.
*----------------------------------------------------------*/
/* Scheduler includes. */
#include "FreeRTOS.h"
#include "task.h"
#include "portmacro.h"
#ifndef configCLINT_BASE_ADDRESS
#warning configCLINT_BASE_ADDRESS must be defined in FreeRTOSConfig.h. If the target chip includes a Core Local Interrupter (CLINT) then set configCLINT_BASE_ADDRESS to the CLINT base address. Otherwise set configCLINT_BASE_ADDRESS to 0.
#endif
/* Let the user override the pre-loading of the initial LR with the address of
prvTaskExitError() in case it messes up unwinding of the stack in the
debugger. */
#ifdef configTASK_RETURN_ADDRESS
#define portTASK_RETURN_ADDRESS configTASK_RETURN_ADDRESS
#else
#define portTASK_RETURN_ADDRESS prvTaskExitError
#endif
/* The stack used by interrupt service routines. Set configISR_STACK_SIZE_WORDS
to use a statically allocated array as the interrupt stack. Alternative leave
configISR_STACK_SIZE_WORDS undefined and update the linker script so that a
linker variable names __freertos_irq_stack_top has the same value as the top
of the stack used by main. Using the linker script method will repurpose the
stack that was used by main before the scheduler was started for use as the
interrupt stack after the scheduler has started. */
#ifdef configISR_STACK_SIZE_WORDS
static __attribute__((aligned(16))) StackType_t xISRStack[configISR_STACK_SIZE_WORDS] = { 0 };
const StackType_t xISRStackTop = (StackType_t) & (xISRStack[configISR_STACK_SIZE_WORDS & ~portBYTE_ALIGNMENT_MASK]);
#else
extern const uint32_t __freertos_irq_stack_top[];
const StackType_t xISRStackTop = (StackType_t)__freertos_irq_stack_top;
#endif
/*
* Setup the timer to generate the tick interrupts. The implementation in this
* file is weak to allow application writers to change the timer used to
* generate the tick interrupt.
*/
void vPortSetupTimerInterrupt(void) __attribute__((weak));
/*-----------------------------------------------------------*/
/* Used to program the machine timer compare register. */
uint64_t ullNextTime = 0ULL;
const uint64_t *pullNextTime = &ullNextTime;
const size_t uxTimerIncrementsForOneTick = (size_t)(configCPU_CLOCK_HZ / configTICK_RATE_HZ); /* Assumes increment won't go over 32-bits. */
volatile uint64_t *const pullMachineTimerCompareRegisterBase = (volatile uint64_t *const)(configCLINT_BASE_ADDRESS + 0x4000);
volatile uint64_t *pullMachineTimerCompareRegister = 0;
BaseType_t TrapNetCounter = 0;
const BaseType_t *pTrapNetCounter = &TrapNetCounter;
/* Set configCHECK_FOR_STACK_OVERFLOW to 3 to add ISR stack checking to task
stack checking. A problem in the ISR stack will trigger an assert, not call the
stack overflow hook function (because the stack overflow hook is specific to a
task stack, not the ISR stack). */
#if (configCHECK_FOR_STACK_OVERFLOW > 2)
#warning This path not tested, or even compiled yet.
/* Don't use 0xa5 as the stack fill bytes as that is used by the kernerl for
the task stacks, and so will legitimately appear in many positions within
the ISR stack. */
#define portISR_STACK_FILL_BYTE 0xee
static const uint8_t ucExpectedStackBytes[] = {
portISR_STACK_FILL_BYTE, portISR_STACK_FILL_BYTE, portISR_STACK_FILL_BYTE, portISR_STACK_FILL_BYTE,
portISR_STACK_FILL_BYTE, portISR_STACK_FILL_BYTE, portISR_STACK_FILL_BYTE, portISR_STACK_FILL_BYTE,
portISR_STACK_FILL_BYTE, portISR_STACK_FILL_BYTE, portISR_STACK_FILL_BYTE, portISR_STACK_FILL_BYTE,
portISR_STACK_FILL_BYTE, portISR_STACK_FILL_BYTE, portISR_STACK_FILL_BYTE, portISR_STACK_FILL_BYTE,
portISR_STACK_FILL_BYTE, portISR_STACK_FILL_BYTE, portISR_STACK_FILL_BYTE, portISR_STACK_FILL_BYTE
};
#define portCHECK_ISR_STACK() configASSERT((memcmp((void *)xISRStack, (void *)ucExpectedStackBytes, sizeof(ucExpectedStackBytes)) == 0))
#else
/* Define the function away. */
#define portCHECK_ISR_STACK()
#endif /* configCHECK_FOR_STACK_OVERFLOW > 2 */
/*-----------------------------------------------------------*/
#if (configCLINT_BASE_ADDRESS != 0)
void vPortSetupTimerInterrupt(void)
{
uint32_t ulCurrentTimeHigh, ulCurrentTimeLow;
volatile uint32_t *const pulTimeHigh = (volatile uint32_t *const)(configCLINT_BASE_ADDRESS + 0xBFFC);
volatile uint32_t *const pulTimeLow = (volatile uint32_t *const)(configCLINT_BASE_ADDRESS + 0xBFF8);
volatile uint32_t ulHartId = 0;
__asm volatile("csrr %0, mhartid"
: "=r"(ulHartId));
pullMachineTimerCompareRegister = &(pullMachineTimerCompareRegisterBase[ulHartId]);
do {
ulCurrentTimeHigh = *pulTimeHigh;
ulCurrentTimeLow = *pulTimeLow;
} while (ulCurrentTimeHigh != *pulTimeHigh);
ullNextTime = (uint64_t)ulCurrentTimeHigh;
ullNextTime <<= 32ULL;
ullNextTime |= (uint64_t)ulCurrentTimeLow;
ullNextTime += (uint64_t)uxTimerIncrementsForOneTick;
*pullMachineTimerCompareRegister = ullNextTime;
/* Prepare the time to use after the next tick interrupt. */
ullNextTime += (uint64_t)uxTimerIncrementsForOneTick;
}
#endif /* ( configCLINT_BASE_ADDRESS != 0 ) */
/*-----------------------------------------------------------*/
BaseType_t xPortStartScheduler(void)
{
extern void xPortStartFirstTask(void);
#if (configASSERT_DEFINED == 1)
{
volatile uint32_t mtvec = 0;
/* Check the least significant two bits of mtvec are 00 - indicating
single vector mode. */
__asm volatile("csrr %0, mtvec"
: "=r"(mtvec));
//configASSERT( ( mtvec & 0x03UL ) == 0 );
/* Check alignment of the interrupt stack - which is the same as the
stack that was being used by main() prior to the scheduler being
started. */
configASSERT((xISRStackTop & portBYTE_ALIGNMENT_MASK) == 0);
}
#endif /* configASSERT_DEFINED */
/* If there is a CLINT then it is ok to use the default implementation
in this file, otherwise vPortSetupTimerInterrupt() must be implemented to
configure whichever clock is to be used to generate the tick interrupt. */
vPortSetupTimerInterrupt();
#if (configCLINT_BASE_ADDRESS != 0)
{
/* Enable mtime and external interrupts. 1<<7 for timer interrupt, 1<<11
for external interrupt. _RB_ What happens here when mtime is not present as
with pulpino? */
__asm volatile("csrs mie, %0" ::"r"(0x880));
}
#else
{
/* Enable external interrupts. */
__asm volatile("csrs mie, %0" ::"r"(0x800));
}
#endif /* configCLINT_BASE_ADDRESS */
*(uint8_t *)(0x02800400 + 7) = 1;
xPortStartFirstTask();
/* Should not get here as after calling xPortStartFirstTask() only tasks
should be executing. */
return pdFAIL;
}
/*-----------------------------------------------------------*/
void vPortEndScheduler(void)
{
/* Not implemented. */
for (;;)
;
}

View File

@@ -0,0 +1,452 @@
/*
* FreeRTOS Kernel V10.2.1
* Copyright (C) 2019 Amazon.com, Inc. or its affiliates. All Rights Reserved.
*
* Permission is hereby granted, free of charge, to any person obtaining a copy of
* this software and associated documentation files (the "Software"), to deal in
* the Software without restriction, including without limitation the rights to
* use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of
* the Software, and to permit persons to whom the Software is furnished to do so,
* subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in all
* copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS
* FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR
* COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER
* IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN
* CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
*
* http://www.FreeRTOS.org
* http://aws.amazon.com/freertos
*
* 1 tab == 4 spaces!
*/
/*
* The FreeRTOS kernel's RISC-V port is split between the the code that is
* common across all currently supported RISC-V chips (implementations of the
* RISC-V ISA), and code which tailors the port to a specific RISC-V chip:
*
* + The code that is common to all RISC-V chips is implemented in
* FreeRTOS\Source\portable\GCC\RISC-V-RV32\portASM.S. There is only one
* portASM.S file because the same file is used no matter which RISC-V chip is
* in use.
*
* + The code that tailors the kernel's RISC-V port to a specific RISC-V
* chip is implemented in freertos_risc_v_chip_specific_extensions.h. There
* is one freertos_risc_v_chip_specific_extensions.h that can be used with any
* RISC-V chip that both includes a standard CLINT and does not add to the
* base set of RISC-V registers. There are additional
* freertos_risc_v_chip_specific_extensions.h files for RISC-V implementations
* that do not include a standard CLINT or do add to the base set of RISC-V
* registers.
*
* CARE MUST BE TAKEN TO INCLDUE THE CORRECT
* freertos_risc_v_chip_specific_extensions.h HEADER FILE FOR THE CHIP
* IN USE. To include the correct freertos_risc_v_chip_specific_extensions.h
* header file ensure the path to the correct header file is in the assembler's
* include path.
*
* This freertos_risc_v_chip_specific_extensions.h is for use on RISC-V chips
* that include a standard CLINT and do not add to the base set of RISC-V
* registers.
*
*/
#if __riscv_xlen == 64
#define portWORD_SIZE 8
#define store_x sd
#define load_x ld
#elif __riscv_xlen == 32
#define store_x sw
#define load_x lw
#define portWORD_SIZE 4
#else
#error Assembler did not define __riscv_xlen
#endif
#include "freertos_risc_v_chip_specific_extensions.h"
/* Check the freertos_risc_v_chip_specific_extensions.h and/or command line
definitions. */
#ifndef portasmHAS_CLINT
#error freertos_risc_v_chip_specific_extensions.h must define portasmHAS_CLINT to either 1 (CLINT present) or 0 (clint not present).
#endif
#ifndef portasmHANDLE_INTERRUPT
#error portasmHANDLE_INTERRUPT must be defined to the function to be called to handle external/peripheral interrupts. portasmHANDLE_INTERRUPT can be defined on the assmbler command line or in the appropriate freertos_risc_v_chip_specific_extensions.h header file.
#endif
/* Only the standard core registers are stored by default. Any additional
registers must be saved by the portasmSAVE_ADDITIONAL_REGISTERS and
portasmRESTORE_ADDITIONAL_REGISTERS macros - which can be defined in a chip
specific version of freertos_risc_v_chip_specific_extensions.h. See the notes
at the top of this file. */
#define portCONTEXT_SIZE ( 30 * portWORD_SIZE )
.global xPortStartFirstTask
.global freertos_risc_v_trap_handler
.global pxPortInitialiseStack
.extern pxCurrentTCB
.extern ulPortTrapHandler
.extern vTaskSwitchContext
.extern xTaskIncrementTick
.extern Timer_IRQHandler
.extern pullMachineTimerCompareRegister
.extern pullNextTime
.extern pTrapNetCounter
.extern uxTimerIncrementsForOneTick /* size_t type so 32-bit on 32-bit core and 64-bits on 64-bit core. */
.extern xISRStackTop
.extern portasmHANDLE_INTERRUPT
.extern Trap_Handler
/*-----------------------------------------------------------*/
.align 8
.func
freertos_risc_v_trap_handler:
addi sp, sp, -portCONTEXT_SIZE
store_x x1, 1 * portWORD_SIZE( sp )
store_x x5, 2 * portWORD_SIZE( sp )
store_x x6, 3 * portWORD_SIZE( sp )
store_x x7, 4 * portWORD_SIZE( sp )
store_x x8, 5 * portWORD_SIZE( sp )
store_x x9, 6 * portWORD_SIZE( sp )
store_x x10, 7 * portWORD_SIZE( sp )
store_x x11, 8 * portWORD_SIZE( sp )
store_x x12, 9 * portWORD_SIZE( sp )
store_x x13, 10 * portWORD_SIZE( sp )
store_x x14, 11 * portWORD_SIZE( sp )
store_x x15, 12 * portWORD_SIZE( sp )
store_x x16, 13 * portWORD_SIZE( sp )
store_x x17, 14 * portWORD_SIZE( sp )
store_x x18, 15 * portWORD_SIZE( sp )
store_x x19, 16 * portWORD_SIZE( sp )
store_x x20, 17 * portWORD_SIZE( sp )
store_x x21, 18 * portWORD_SIZE( sp )
store_x x22, 19 * portWORD_SIZE( sp )
store_x x23, 20 * portWORD_SIZE( sp )
store_x x24, 21 * portWORD_SIZE( sp )
store_x x25, 22 * portWORD_SIZE( sp )
store_x x26, 23 * portWORD_SIZE( sp )
store_x x27, 24 * portWORD_SIZE( sp )
store_x x28, 25 * portWORD_SIZE( sp )
store_x x29, 26 * portWORD_SIZE( sp )
store_x x30, 27 * portWORD_SIZE( sp )
store_x x31, 28 * portWORD_SIZE( sp )
csrr t0, mstatus /* Required for MPIE bit. */
store_x t0, 29 * portWORD_SIZE( sp )
portasmSAVE_ADDITIONAL_REGISTERS /* Defined in freertos_risc_v_chip_specific_extensions.h to save any registers unique to the RISC-V implementation. */
load_x t0, pTrapNetCounter
lw t1, 0( t0 )
addi t1, t1, 1
store_x t1, 0( t0 )
load_x t0, pxCurrentTCB /* Load pxCurrentTCB. */
store_x sp, 0( t0 ) /* Write sp to first TCB member. */
csrr a0, mcause
csrr a1, mepc
li t0, 0x80000FFF
and a0, a0, t0
test_if_asynchronous:
srli a2, a0, __riscv_xlen - 1 /* MSB of mcause is 1 if handing an asynchronous interrupt - shift to LSB to clear other bits. */
beq a2, x0, handle_synchronous /* Branch past interrupt handing if not asynchronous. */
store_x a1, 0( sp ) /* Asynch so save unmodified exception return address. */
handle_asynchronous:
#if( portasmHAS_CLINT != 0 )
test_if_mtimer: /* If there is a CLINT then the mtimer is used to generate the tick interrupt. */
addi t0, x0, 1
slli t0, t0, __riscv_xlen - 1 /* LSB is already set, shift into MSB. Shift 31 on 32-bit or 63 on 64-bit cores. */
addi t1, t0, 7 /* 0x8000[]0007 == machine timer interrupt. */
bne a0, t1, test_if_external_interrupt
load_x t0, pullMachineTimerCompareRegister /* Load address of compare register into t0. */
load_x t1, pullNextTime /* Load the address of ullNextTime into t1. */
#if( __riscv_xlen == 32 )
/* Update the 64-bit mtimer compare match value in two 32-bit writes. */
li t4, -1
lw t2, 0(t1) /* Load the low word of ullNextTime into t2. */
lw t3, 4(t1) /* Load the high word of ullNextTime into t3. */
sw t4, 0(t0) /* Low word no smaller than old value to start with - will be overwritten below. */
sw t3, 4(t0) /* Store high word of ullNextTime into compare register. No smaller than new value. */
sw t2, 0(t0) /* Store low word of ullNextTime into compare register. */
lw t0, uxTimerIncrementsForOneTick /* Load the value of ullTimerIncrementForOneTick into t0 (could this be optimized by storing in an array next to pullNextTime?). */
add t4, t0, t2 /* Add the low word of ullNextTime to the timer increments for one tick (assumes timer increment for one tick fits in 32-bits). */
sltu t5, t4, t2 /* See if the sum of low words overflowed (what about the zero case?). */
add t6, t3, t5 /* Add overflow to high word of ullNextTime. */
sw t4, 0(t1) /* Store new low word of ullNextTime. */
sw t6, 4(t1) /* Store new high word of ullNextTime. */
#endif /* __riscv_xlen == 32 */
#if( __riscv_xlen == 64 )
/* Update the 64-bit mtimer compare match value. */
ld t2, 0(t1) /* Load ullNextTime into t2. */
sd t2, 0(t0) /* Store ullNextTime into compare register. */
ld t0, uxTimerIncrementsForOneTick /* Load the value of ullTimerIncrementForOneTick into t0 (could this be optimized by storing in an array next to pullNextTime?). */
add t4, t0, t2 /* Add ullNextTime to the timer increments for one tick. */
sd t4, 0(t1) /* Store ullNextTime. */
#endif /* __riscv_xlen == 64 */
load_x sp, xISRStackTop /* Switch to ISR stack before function call. */
jal xTaskIncrementTick
beqz a0, processed_source /* Don't switch context if incrementing tick didn't unblock a task. */
jal vTaskSwitchContext
j processed_source
test_if_external_interrupt: /* If there is a CLINT and the mtimer interrupt is not pending then check to see if an external interrupt is pending. */
//addi t1, t1, 4 /* 0x80000007 + 4 = 0x8000000b == Machine external interrupt. */
//bne a0, t1, as_yet_unhandled /* Something as yet unhandled. */
#endif /* portasmHAS_CLINT */
load_x sp, xISRStackTop /* Switch to ISR stack before function call. */
jal portasmHANDLE_INTERRUPT /* Jump to the interrupt handler if there is no CLINT or if there is a CLINT and it has been determined that an external interrupt is pending. */
j processed_source
handle_synchronous:
addi a1, a1, 4 /* Synchronous so updated exception return address to the instruction after the instruction that generated the exeption. */
store_x a1, 0( sp ) /* Save updated exception return address. */
test_if_environment_call:
li t0, 11 /* 11 == environment call. */
bne a0, t0, is_exception /* Not an M environment call, so some other exception. */
load_x sp, xISRStackTop /* Switch to ISR stack before function call. */
jal vTaskSwitchContext
j processed_source
is_exception:
csrr t0, mcause /* For viewing in the debugger only. */
csrr t1, mepc /* For viewing in the debugger only */
csrr t2, mstatus
load_x sp, xISRStackTop
jal Trap_Handler
j is_exception
as_yet_unhandled:
csrr t0, mcause /* For viewing in the debugger only. */
j as_yet_unhandled
processed_source:
load_x t0, pTrapNetCounter
lw t1, 0 ( t0 )
addi t1, t1, -1
store_x t1, 0( t0 )
load_x t1, pxCurrentTCB /* Load pxCurrentTCB. */
load_x sp, 0( t1 ) /* Read sp from first TCB member. */
/* Load mret with the address of the next instruction in the task to run next. */
load_x t0, 0( sp )
csrw mepc, t0
portasmRESTORE_ADDITIONAL_REGISTERS /* Defined in freertos_risc_v_chip_specific_extensions.h to restore any registers unique to the RISC-V implementation. */
/* Load mstatus with the interrupt enable bits used by the task. */
load_x t0, 29 * portWORD_SIZE( sp )
csrw mstatus, t0 /* Required for MPIE bit. */
load_x x1, 1 * portWORD_SIZE( sp )
load_x x5, 2 * portWORD_SIZE( sp ) /* t0 */
load_x x6, 3 * portWORD_SIZE( sp ) /* t1 */
load_x x7, 4 * portWORD_SIZE( sp ) /* t2 */
load_x x8, 5 * portWORD_SIZE( sp ) /* s0/fp */
load_x x9, 6 * portWORD_SIZE( sp ) /* s1 */
load_x x10, 7 * portWORD_SIZE( sp ) /* a0 */
load_x x11, 8 * portWORD_SIZE( sp ) /* a1 */
load_x x12, 9 * portWORD_SIZE( sp ) /* a2 */
load_x x13, 10 * portWORD_SIZE( sp ) /* a3 */
load_x x14, 11 * portWORD_SIZE( sp ) /* a4 */
load_x x15, 12 * portWORD_SIZE( sp ) /* a5 */
load_x x16, 13 * portWORD_SIZE( sp ) /* a6 */
load_x x17, 14 * portWORD_SIZE( sp ) /* a7 */
load_x x18, 15 * portWORD_SIZE( sp ) /* s2 */
load_x x19, 16 * portWORD_SIZE( sp ) /* s3 */
load_x x20, 17 * portWORD_SIZE( sp ) /* s4 */
load_x x21, 18 * portWORD_SIZE( sp ) /* s5 */
load_x x22, 19 * portWORD_SIZE( sp ) /* s6 */
load_x x23, 20 * portWORD_SIZE( sp ) /* s7 */
load_x x24, 21 * portWORD_SIZE( sp ) /* s8 */
load_x x25, 22 * portWORD_SIZE( sp ) /* s9 */
load_x x26, 23 * portWORD_SIZE( sp ) /* s10 */
load_x x27, 24 * portWORD_SIZE( sp ) /* s11 */
load_x x28, 25 * portWORD_SIZE( sp ) /* t3 */
load_x x29, 26 * portWORD_SIZE( sp ) /* t4 */
load_x x30, 27 * portWORD_SIZE( sp ) /* t5 */
load_x x31, 28 * portWORD_SIZE( sp ) /* t6 */
addi sp, sp, portCONTEXT_SIZE
mret
.endfunc
/*-----------------------------------------------------------*/
.align 8
.func
xPortStartFirstTask:
#if( portasmHAS_CLINT != 0 )
/* If there is a clint then interrupts can branch directly to the FreeRTOS
trap handler. Otherwise the interrupt controller will need to be configured
outside of this file. */
la t0, freertos_risc_v_trap_handler
ori t0, t0, 2
csrw mtvec, t0
#endif /* portasmHAS_CLILNT */
load_x sp, pxCurrentTCB /* Load pxCurrentTCB. */
load_x sp, 0( sp ) /* Read sp from first TCB member. */
load_x x1, 0( sp ) /* Note for starting the scheduler the exception return address is used as the function return address. */
portasmRESTORE_ADDITIONAL_REGISTERS /* Defined in freertos_risc_v_chip_specific_extensions.h to restore any registers unique to the RISC-V implementation. */
load_x t0, 29 * portWORD_SIZE( sp ) /* mstatus */
addi t0, t0, 0x08 /* Set MIE bit so the first task starts with interrupts enabled - required as returns with ret not eret. */
csrrw x0, mstatus, t0 /* Interrupts enabled from here! */
load_x x5, 2 * portWORD_SIZE( sp ) /* t0 */
load_x x6, 3 * portWORD_SIZE( sp ) /* t1 */
load_x x7, 4 * portWORD_SIZE( sp ) /* t2 */
load_x x8, 5 * portWORD_SIZE( sp ) /* s0/fp */
load_x x9, 6 * portWORD_SIZE( sp ) /* s1 */
load_x x10, 7 * portWORD_SIZE( sp ) /* a0 */
load_x x11, 8 * portWORD_SIZE( sp ) /* a1 */
load_x x12, 9 * portWORD_SIZE( sp ) /* a2 */
load_x x13, 10 * portWORD_SIZE( sp ) /* a3 */
load_x x14, 11 * portWORD_SIZE( sp ) /* a4 */
load_x x15, 12 * portWORD_SIZE( sp ) /* a5 */
load_x x16, 13 * portWORD_SIZE( sp ) /* a6 */
load_x x17, 14 * portWORD_SIZE( sp ) /* a7 */
load_x x18, 15 * portWORD_SIZE( sp ) /* s2 */
load_x x19, 16 * portWORD_SIZE( sp ) /* s3 */
load_x x20, 17 * portWORD_SIZE( sp ) /* s4 */
load_x x21, 18 * portWORD_SIZE( sp ) /* s5 */
load_x x22, 19 * portWORD_SIZE( sp ) /* s6 */
load_x x23, 20 * portWORD_SIZE( sp ) /* s7 */
load_x x24, 21 * portWORD_SIZE( sp ) /* s8 */
load_x x25, 22 * portWORD_SIZE( sp ) /* s9 */
load_x x26, 23 * portWORD_SIZE( sp ) /* s10 */
load_x x27, 24 * portWORD_SIZE( sp ) /* s11 */
load_x x28, 25 * portWORD_SIZE( sp ) /* t3 */
load_x x29, 26 * portWORD_SIZE( sp ) /* t4 */
load_x x30, 27 * portWORD_SIZE( sp ) /* t5 */
load_x x31, 28 * portWORD_SIZE( sp ) /* t6 */
addi sp, sp, portCONTEXT_SIZE
ret
.endfunc
/*-----------------------------------------------------------*/
/*
* Unlike other ports pxPortInitialiseStack() is written in assembly code as it
* needs access to the portasmADDITIONAL_CONTEXT_SIZE constant. The prototype
* for the function is as per the other ports:
* StackType_t *pxPortInitialiseStack( StackType_t *pxTopOfStack, TaskFunction_t pxCode, void *pvParameters );
*
* As per the standard RISC-V ABI pxTopcOfStack is passed in in a0, pxCode in
* a1, and pvParameters in a2. The new top of stack is passed out in a0.
*
* RISC-V maps registers to ABI names as follows (X1 to X31 integer registers
* for the 'I' profile, X1 to X15 for the 'E' profile, currently I assumed).
*
* Register ABI Name Description Saver
* x0 zero Hard-wired zero -
* x1 ra Return address Caller
* x2 sp Stack pointer Callee
* x3 gp Global pointer -
* x4 tp Thread pointer -
* x5-7 t0-2 Temporaries Caller
* x8 s0/fp Saved register/Frame pointer Callee
* x9 s1 Saved register Callee
* x10-11 a0-1 Function Arguments/return values Caller
* x12-17 a2-7 Function arguments Caller
* x18-27 s2-11 Saved registers Callee
* x28-31 t3-6 Temporaries Caller
*
* The RISC-V context is saved t FreeRTOS tasks in the following stack frame,
* where the global and thread pointers are currently assumed to be constant so
* are not saved:
*
* mstatus
* x31
* x30
* x29
* x28
* x27
* x26
* x25
* x24
* x23
* x22
* x21
* x20
* x19
* x18
* x17
* x16
* x15
* x14
* x13
* x12
* x11
* pvParameters
* x9
* x8
* x7
* x6
* x5
* portTASK_RETURN_ADDRESS
* [chip specific registers go here]
* pxCode
*/
.align 8
.func
pxPortInitialiseStack:
csrr t0, mstatus /* Obtain current mstatus value. */
#if 1
li t1, 0x1880
or t0, t0, t1 /* MPP = 0b11, MPIE = 1 */
andi t0, t0, 0xFFFFFFF7 /* !!! MIE = 0 !!! */
#else
addi t1, x0, 0x188 /* Generate the value 0x1888, which are the MIE, MPIE and privilege bits to set in mstatus. */
slli t1, t1, 4
or t0, t0, t1 /* Set MPIE and MPP bits in mstatus value. */
#endif
addi a0, a0, -portWORD_SIZE
store_x t0, 0(a0) /* mstatus onto the stack. */
addi a0, a0, -(22 * portWORD_SIZE) /* Space for registers x11-x31. */
store_x a2, 0(a0) /* Task parameters (pvParameters parameter) goes into register X10/a0 on the stack. */
addi a0, a0, -(6 * portWORD_SIZE) /* Space for registers x5-x9. */
store_x x0, 0(a0) /* Return address onto the stack, could be portTASK_RETURN_ADDRESS */
addi t0, x0, portasmADDITIONAL_CONTEXT_SIZE /* The number of chip specific additional registers. */
chip_specific_stack_frame: /* First add any chip specific registers to the stack frame being created. */
beq t0, x0, 1f /* No more chip specific registers to save. */
addi a0, a0, -portWORD_SIZE /* Make space for chip specific register. */
store_x x0, 0(a0) /* Give the chip specific register an initial value of zero. */
addi t0, t0, -1 /* Decrement the count of chip specific registers remaining. */
j chip_specific_stack_frame /* Until no more chip specific registers. */
1:
addi a0, a0, -portWORD_SIZE
store_x a1, 0(a0) /* mret value (pxCode parameter) onto the stack. */
ret
.endfunc
/*-----------------------------------------------------------*/

View File

@@ -0,0 +1,164 @@
/*
* FreeRTOS Kernel V10.2.1
* Copyright (C) 2019 Amazon.com, Inc. or its affiliates. All Rights Reserved.
*
* Permission is hereby granted, free of charge, to any person obtaining a copy of
* this software and associated documentation files (the "Software"), to deal in
* the Software without restriction, including without limitation the rights to
* use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of
* the Software, and to permit persons to whom the Software is furnished to do so,
* subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in all
* copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS
* FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR
* COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER
* IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN
* CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
*
* http://www.FreeRTOS.org
* http://aws.amazon.com/freertos
*
* 1 tab == 4 spaces!
*/
#ifndef PORTMACRO_H
#define PORTMACRO_H
#ifdef __cplusplus
extern "C" {
#endif
/*-----------------------------------------------------------
* Port specific definitions.
*
* The settings in this file configure FreeRTOS correctly for the
* given hardware and compiler.
*
* These settings should not be altered.
*-----------------------------------------------------------
*/
#include <stddef.h>
#include <stdint.h>
/* Type definitions. */
#if __riscv_xlen == 64
#define portSTACK_TYPE uint64_t
#define portBASE_TYPE int64_t
#define portUBASE_TYPE uint64_t
#define portMAX_DELAY (TickType_t)0xffffffffffffffffUL
#define portPOINTER_SIZE_TYPE uint64_t
#elif __riscv_xlen == 32
#define portSTACK_TYPE uint32_t
#define portBASE_TYPE int /* int32_t */
#define portUBASE_TYPE uint32_t
#define portMAX_DELAY (TickType_t)0xffffffffUL
#ifdef __riscv_float_abi_single
/* better to use float replace double here,
* so that it will generates floating point instructions
*/
#define portDOUBLE float /* double */
#else
#define portDOUBLE double
#endif
#else
#error Assembler did not define __riscv_xlen
#endif
typedef portSTACK_TYPE StackType_t;
typedef portBASE_TYPE BaseType_t;
typedef portUBASE_TYPE UBaseType_t;
typedef portUBASE_TYPE TickType_t;
/* 32-bit tick type on a 32-bit architecture, so reads of the tick count do
not need to be guarded with a critical section. */
#define portTICK_TYPE_IS_ATOMIC 1
/*-----------------------------------------------------------*/
/* Architecture specifics. */
#define portSTACK_GROWTH (-1)
#define portTICK_PERIOD_MS ((TickType_t)1000 / configTICK_RATE_HZ)
#ifdef __riscv64
#error This is the RV32 port that has not yet been adapted for 64.
#define portBYTE_ALIGNMENT 16
#else
#define portBYTE_ALIGNMENT 16
#endif
/*-----------------------------------------------------------*/
/* Scheduler utilities. */
extern BaseType_t TrapNetCounter;
extern void vTaskSwitchContext(void);
#define portYIELD() __asm volatile("ecall");
#define portEND_SWITCHING_ISR(xSwitchRequired) \
if (xSwitchRequired) \
vTaskSwitchContext()
#define portYIELD_FROM_ISR(x) portEND_SWITCHING_ISR(x)
/*-----------------------------------------------------------*/
/* Critical section management. */
#define portCRITICAL_NESTING_IN_TCB 1
extern void vTaskEnterCritical(void);
extern void vTaskExitCritical(void);
#define portSET_INTERRUPT_MASK_FROM_ISR() 0
#define portCLEAR_INTERRUPT_MASK_FROM_ISR(uxSavedStatusValue) (void)uxSavedStatusValue
#define portDISABLE_INTERRUPTS() __asm volatile("csrc mstatus, 8")
#define portENABLE_INTERRUPTS() __asm volatile("csrs mstatus, 8")
#define portENTER_CRITICAL() vTaskEnterCritical()
#define portEXIT_CRITICAL() vTaskExitCritical()
/*-----------------------------------------------------------*/
/* Architecture specific optimisations. */
#ifndef configUSE_PORT_OPTIMISED_TASK_SELECTION
#define configUSE_PORT_OPTIMISED_TASK_SELECTION 1
#endif
#if (configUSE_PORT_OPTIMISED_TASK_SELECTION == 1)
/* Check the configuration. */
#if (configMAX_PRIORITIES > 32)
#error configUSE_PORT_OPTIMISED_TASK_SELECTION can only be set to 1 when configMAX_PRIORITIES is less than or equal to 32. It is very rare that a system requires more than 10 to 15 difference priorities as tasks that share a priority will time slice.
#endif
/* Store/clear the ready priorities in a bit map. */
#define portRECORD_READY_PRIORITY(uxPriority, uxReadyPriorities) (uxReadyPriorities) |= (1UL << (uxPriority))
#define portRESET_READY_PRIORITY(uxPriority, uxReadyPriorities) (uxReadyPriorities) &= ~(1UL << (uxPriority))
/*-----------------------------------------------------------*/
#define portGET_HIGHEST_PRIORITY(uxTopPriority, uxReadyPriorities) uxTopPriority = (31UL - __builtin_clz(uxReadyPriorities))
#endif /* configUSE_PORT_OPTIMISED_TASK_SELECTION */
/*-----------------------------------------------------------*/
/* Task function macros as described on the FreeRTOS.org WEB site. These are
not necessary for to use this port. They are defined so the common demo files
(which build with all the ports) will build. */
#define portTASK_FUNCTION_PROTO(vFunction, pvParameters) void vFunction(void *pvParameters)
#define portTASK_FUNCTION(vFunction, pvParameters) void vFunction(void *pvParameters)
/*-----------------------------------------------------------*/
#define portNOP() __asm volatile(" nop ")
#define portINLINE __inline
#ifndef portFORCE_INLINE
#define portFORCE_INLINE inline __attribute__((always_inline))
#endif
#define portMEMORY_BARRIER() __asm volatile("" ::: "memory")
portFORCE_INLINE static BaseType_t xPortIsInsideInterrupt(void) { return TrapNetCounter ? 1 : 0; }
#ifdef __cplusplus
}
#endif
#endif /* PORTMACRO_H */

View File

@@ -0,0 +1,20 @@
Each real time kernel port consists of three files that contain the core kernel
components and are common to every port, and one or more files that are
specific to a particular microcontroller and/or compiler.
+ The FreeRTOS/Source/Portable/MemMang directory contains the five sample
memory allocators as described on the http://www.FreeRTOS.org WEB site.
+ The other directories each contain files specific to a particular
microcontroller or compiler, where the directory name denotes the compiler
specific files the directory contains.
For example, if you are interested in the [compiler] port for the [architecture]
microcontroller, then the port specific files are contained in
FreeRTOS/Source/Portable/[compiler]/[architecture] directory. If this is the
only port you are interested in then all the other directories can be
ignored.

View File

@@ -0,0 +1,46 @@
################# Add global include #################
list(APPEND ADD_INCLUDE
"${CMAKE_CURRENT_SOURCE_DIR}/core/inc"
"${CMAKE_CURRENT_SOURCE_DIR}/dsp/inc"
"${CMAKE_CURRENT_SOURCE_DIR}/nn/inc"
)
#######################################################
################# Add private include #################
list(APPEND ADD_PRIVATE_INCLUDE
"${CMAKE_CURRENT_SOURCE_DIR}/dsp/privateInc"
)
#######################################################
############## Add current dir source files ###########
file(GLOB_RECURSE sources "${CMAKE_CURRENT_SOURCE_DIR}/dsp/*.c"
"${CMAKE_CURRENT_SOURCE_DIR}/nn/*.c"
)
list(APPEND ADD_SRCS ${sources})
# aux_source_directory(src ADD_SRCS)
# list(REMOVE_ITEM ADD_SRCS "${CMAKE_CURRENT_SOURCE_DIR}")
#######################################################
########### Add required/dependent components #########
# list(APPEND ADD_REQUIREMENTS common)
#######################################################
############ Add static libs ##########################
#list(APPEND ADD_STATIC_LIB "libxxx.a")
#######################################################
############ Add dynamic libs #########################
# list(APPEND ADD_DYNAMIC_LIB "libxxx.so")
#######################################################
############ Add global compile option ################
#add components denpend on this component
list(APPEND ADD_DEFINITIONS -D__RISCV_FEATURE_MVE=0 -Wno-incompatible-pointer-types -Wno-parentheses)
#######################################################
############ Add private compile option ################
#add compile option for this component that won't affect other modules
# list(APPEND ADD_PRIVATE_DEFINITIONS )
#######################################################
generate_library()

View File

@@ -0,0 +1,226 @@
/*
* Copyright (c) 2019 Nuclei Limited. All rights reserved.
*
* SPDX-License-Identifier: Apache-2.0
*
* Licensed under the Apache License, Version 2.0 (the License); you may
* not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an AS IS BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*/
#ifndef __CORE_COMPATIABLE_H__
#define __CORE_COMPATIABLE_H__
/*!
* @file core_compatiable.h
* @brief ARM compatiable function definitions header file
*/
#ifdef __cplusplus
extern "C" {
#endif
/* ===== ARM Compatiable Functions ===== */
/**
* \defgroup NMSIS_Core_ARMCompatiable_Functions ARM Compatiable Functions
* \ingroup NMSIS_Core
* \brief A few functions that compatiable with ARM CMSIS-Core.
* \details
*
* Here we provided a few functions that compatiable with ARM CMSIS-Core,
* mostly used in the DSP and NN library.
* @{
*/
/** \brief Instruction Synchronization Barrier, compatiable with ARM */
#define __ISB() __RWMB()
/** \brief Data Synchronization Barrier, compatiable with ARM */
#define __DSB() __RWMB()
/** \brief Data Memory Barrier, compatiable with ARM */
#define __DMB() __RWMB()
/** \brief LDRT Unprivileged (8 bit), ARM Compatiable */
#define __LDRBT(ptr) __LB((ptr))
/** \brief LDRT Unprivileged (16 bit), ARM Compatiable */
#define __LDRHT(ptr) __LH((ptr))
/** \brief LDRT Unprivileged (32 bit), ARM Compatiable */
#define __LDRT(ptr) __LW((ptr))
/** \brief STRT Unprivileged (8 bit), ARM Compatiable */
#define __STRBT(val, ptr) __SB((ptr), (val))
/** \brief STRT Unprivileged (16 bit), ARM Compatiable */
#define __STRHT(val, ptr) __SH((ptr), (val))
/** \brief STRT Unprivileged (32 bit), ARM Compatiable */
#define __STRT(val, ptr) __SW((ptr), (val))
/* ===== Saturation Operations ===== */
/**
* \brief Signed Saturate
* \details Saturates a signed value.
* \param [in] value Value to be saturated
* \param [in] sat Bit position to saturate to (1..32)
* \return Saturated value
*/
#if defined(__DSP_PRESENT) && (__DSP_PRESENT == 1)
#define __SSAT(val, sat) __RV_SCLIP32((val), (sat - 1))
#else
__STATIC_FORCEINLINE int32_t __SSAT(int32_t val, uint32_t sat)
{
if ((sat >= 1U) && (sat <= 32U)) {
const int32_t max = (int32_t)((1U << (sat - 1U)) - 1U);
const int32_t min = -1 - max;
if (val > max) {
return max;
} else if (val < min) {
return min;
}
}
return val;
}
#endif
/**
* \brief Unsigned Saturate
* \details Saturates an unsigned value.
* \param [in] value Value to be saturated
* \param [in] sat Bit position to saturate to (0..31)
* \return Saturated value
*/
#if defined(__DSP_PRESENT) && (__DSP_PRESENT == 1)
#define __USAT(val, sat) __RV_UCLIP32((val), (sat))
#else
__STATIC_FORCEINLINE uint32_t __USAT(int32_t val, uint32_t sat)
{
if (sat <= 31U) {
const uint32_t max = ((1U << sat) - 1U);
if (val > (int32_t)max) {
return max;
} else if (val < 0) {
return 0U;
}
}
return (uint32_t)val;
}
#endif
#if 0
/* ===== Data Processing Operations ===== */
/**
* \brief Reverse byte order (32 bit)
* \details Reverses the byte order in unsigned integer value.
* For example, 0x12345678 becomes 0x78563412.
* \param [in] value Value to reverse
* \return Reversed value
*/
__STATIC_FORCEINLINE uint32_t __REV(uint32_t value)
{
uint32_t result;
result = ((value & 0xff000000) >> 24) | ((value & 0x00ff0000) >> 8) | ((value & 0x0000ff00) << 8) | ((value & 0x000000ff) << 24);
return result;
}
/**
* \brief Reverse byte order (16 bit)
* \details Reverses the byte order within each halfword of a word.
* For example, 0x12345678 becomes 0x34127856.
* \param [in] value Value to reverse
* \return Reversed value
*/
__STATIC_FORCEINLINE uint32_t __REV16(uint32_t value)
{
uint32_t result;
result = ((value & 0xff000000) >> 8) | ((value & 0x00ff00000) << 8) | ((value & 0x0000ff00) >> 8) | ((value & 0x000000ff) << 8);
return result;
}
/**
* \brief Reverse byte order (16 bit)
* \details Reverses the byte order in a 16-bit value
* and returns the signed 16-bit result.
* For example, 0x0080 becomes 0x8000.
* \param [in] value Value to reverse
* \return Reversed value
*/
__STATIC_FORCEINLINE int16_t __REVSH(int16_t value)
{
int16_t result;
result = ((value & 0xff00) >> 8) | ((value & 0x00ff) << 8);
return result;
}
#endif
/**
* \brief Rotate Right in unsigned value (32 bit)
* \details Rotate Right (immediate) provides the value of
* the contents of a register rotated by a variable number of bits.
* \param [in] op1 Value to rotate
* \param [in] op2 Number of Bits to rotate(0-31)
* \return Rotated value
*/
__STATIC_FORCEINLINE uint32_t __ROR(uint32_t op1, uint32_t op2)
{
op2 = op2 & 0x1F;
if (op2 == 0U) {
return op1;
}
return (op1 >> op2) | (op1 << (32U - op2));
}
/**
* \brief Reverse bit order of value
* \details Reverses the bit order of the given value.
* \param [in] value Value to reverse
* \return Reversed value
*/
#if defined(__DSP_PRESENT) && (__DSP_PRESENT == 1)
#define __RBIT(value) __RV_BITREVI((value), 31)
#else
__STATIC_FORCEINLINE uint32_t __RBIT(uint32_t value)
{
uint32_t result;
uint32_t s = (4U /*sizeof(v)*/ * 8U) - 1U; /* extra shift needed at end */
result = value; /* r will be reversed bits of v; first get LSB of v */
for (value >>= 1U; value != 0U; value >>= 1U) {
result <<= 1U;
result |= value & 1U;
s--;
}
result <<= s; /* shift when v's highest bits are zero */
return result;
}
#endif /* defined(__DSP_PRESENT) && (__DSP_PRESENT == 1) */
/**
* \brief Count leading zeros
* \details Counts the number of leading zeros of a data value.
* \param [in] data Value to count the leading zeros
* \return number of leading zeros in value
*/
#if defined(__DSP_PRESENT) && (__DSP_PRESENT == 1)
#define __CLZ(data) __RV_CLZ32(data)
#else
__STATIC_FORCEINLINE uint8_t __CLZ(uint32_t data)
{
uint8_t ret = 0;
uint32_t temp = ~data;
while (temp & 0x80000000) {
temp <<= 1;
ret++;
}
return ret;
}
#endif /* defined(__DSP_PRESENT) && (__DSP_PRESENT == 1) */
/** @} */ /* End of Doxygen Group NMSIS_Core_ARMCompatiable_Functions */
#ifdef __cplusplus
}
#endif
#endif /* __CORE_COMPATIABLE_H__ */

File diff suppressed because it is too large Load Diff

View File

@@ -0,0 +1,897 @@
/*
* Copyright (c) 2019 Nuclei Limited. All rights reserved.
*
* SPDX-License-Identifier: Apache-2.0
*
* Licensed under the Apache License, Version 2.0 (the License); you may
* not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an AS IS BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*/
#ifndef __CORE_FEATURE_ECLIC__
#define __CORE_FEATURE_ECLIC__
/*!
* @file core_feature_eclic.h
* @brief ECLIC feature API header file for Nuclei N/NX Core
*/
/*
* ECLIC Feature Configuration Macro:
* 1. __ECLIC_PRESENT: Define whether Enhanced Core Local Interrupt Controller (ECLIC) Unit is present or not
* * 0: Not present
* * 1: Present
* 2. __ECLIC_BASEADDR: Base address of the ECLIC unit.
* 3. ECLIC_GetInfoCtlbits(): Define the number of hardware bits are actually implemented in the clicintctl registers.
* Valid number is 1 - 8.
* 4. __ECLIC_INTNUM : Define the external interrupt number of ECLIC Unit
*
*/
#ifdef __cplusplus
extern "C" {
#endif
#if defined(__ECLIC_PRESENT) && (__ECLIC_PRESENT == 1)
/**
* \defgroup NMSIS_Core_ECLIC_Registers Register Define and Type Definitions Of ECLIC
* \ingroup NMSIS_Core_Registers
* \brief Type definitions and defines for eclic registers.
*
* @{
*/
/**
* \brief Union type to access CLICFG configure register.
*/
typedef union
{
struct {
uint8_t _reserved0:1; /*!< bit: 0 Overflow condition code flag */
uint8_t nlbits:4; /*!< bit: 29 Carry condition code flag */
uint8_t _reserved1:2; /*!< bit: 30 Zero condition code flag */
uint8_t _reserved2:1; /*!< bit: 31 Negative condition code flag */
} b; /*!< Structure used for bit access */
uint8_t w; /*!< Type used for byte access */
} CLICCFG_Type;
/**
* \brief Union type to access CLICINFO information register.
*/
typedef union {
struct {
uint32_t numint:13; /*!< bit: 0..12 number of maximum interrupt inputs supported */
uint32_t version:8; /*!< bit: 13..20 20:17 for architecture version,16:13 for implementation version */
uint32_t intctlbits:4; /*!< bit: 21..24 specifies how many hardware bits are actually implemented in the clicintctl registers */
uint32_t _reserved0:7; /*!< bit: 25..31 Reserved */
} b; /*!< Structure used for bit access */
uint32_t w; /*!< Type used for word access */
} CLICINFO_Type;
/**
* \brief Access to the structure of a vector interrupt controller.
*/
typedef struct {
__IOM uint8_t INTIP; /*!< Offset: 0x000 (R/W) Interrupt set pending register */
__IOM uint8_t INTIE; /*!< Offset: 0x001 (R/W) Interrupt set enable register */
__IOM uint8_t INTATTR; /*!< Offset: 0x002 (R/W) Interrupt set attributes register */
__IOM uint8_t INTCTRL; /*!< Offset: 0x003 (R/W) Interrupt configure register */
} CLIC_CTRL_Type;
typedef struct {
__IOM uint8_t CFG; /*!< Offset: 0x000 (R/W) CLIC configuration register */
uint8_t RESERVED0[3];
__IM uint32_t INFO; /*!< Offset: 0x004 (R/ ) CLIC information register */
uint8_t RESERVED1[3];
__IOM uint8_t MTH; /*!< Offset: 0x00B (R/W) CLIC machine mode threshold register */
uint32_t RESERVED2[0x3FD];
CLIC_CTRL_Type CTRL[4096]; /*!< Offset: 0x1000 (R/W) CLIC register structure for INTIP, INTIE, INTATTR, INTCTL */
} CLIC_Type;
#define CLIC_CLICCFG_NLBIT_Pos 1U /*!< CLIC CLICCFG: NLBIT Position */
#define CLIC_CLICCFG_NLBIT_Msk (0xFUL << CLIC_CLICCFG_NLBIT_Pos) /*!< CLIC CLICCFG: NLBIT Mask */
#define CLIC_CLICINFO_CTLBIT_Pos 21U /*!< CLIC INTINFO: __ECLIC_GetInfoCtlbits() Position */
#define CLIC_CLICINFO_CTLBIT_Msk (0xFUL << CLIC_CLICINFO_CTLBIT_Pos) /*!< CLIC INTINFO: __ECLIC_GetInfoCtlbits() Mask */
#define CLIC_CLICINFO_VER_Pos 13U /*!< CLIC CLICINFO: VERSION Position */
#define CLIC_CLICINFO_VER_Msk (0xFFUL << CLIC_CLICCFG_NLBIT_Pos) /*!< CLIC CLICINFO: VERSION Mask */
#define CLIC_CLICINFO_NUM_Pos 0U /*!< CLIC CLICINFO: NUM Position */
#define CLIC_CLICINFO_NUM_Msk (0xFFFUL << CLIC_CLICINFO_NUM_Pos) /*!< CLIC CLICINFO: NUM Mask */
#define CLIC_INTIP_IP_Pos 0U /*!< CLIC INTIP: IP Position */
#define CLIC_INTIP_IP_Msk (0x1UL << CLIC_INTIP_IP_Pos) /*!< CLIC INTIP: IP Mask */
#define CLIC_INTIE_IE_Pos 0U /*!< CLIC INTIE: IE Position */
#define CLIC_INTIE_IE_Msk (0x1UL << CLIC_INTIE_IE_Pos) /*!< CLIC INTIE: IE Mask */
#define CLIC_INTATTR_TRIG_Pos 1U /*!< CLIC INTATTR: TRIG Position */
#define CLIC_INTATTR_TRIG_Msk (0x3UL << CLIC_INTATTR_TRIG_Pos) /*!< CLIC INTATTR: TRIG Mask */
#define CLIC_INTATTR_SHV_Pos 0U /*!< CLIC INTATTR: SHV Position */
#define CLIC_INTATTR_SHV_Msk (0x1UL << CLIC_INTATTR_SHV_Pos) /*!< CLIC INTATTR: SHV Mask */
#define ECLIC_MAX_NLBITS 8U /*!< Max nlbit of the CLICINTCTLBITS */
#define ECLIC_MODE_MTVEC_Msk 3U /*!< ECLIC Mode mask for MTVT CSR Register */
#define ECLIC_NON_VECTOR_INTERRUPT 0x0 /*!< Non-Vector Interrupt Mode of ECLIC */
#define ECLIC_VECTOR_INTERRUPT 0x1 /*!< Vector Interrupt Mode of ECLIC */
/**\brief ECLIC Trigger Enum for different Trigger Type */
typedef enum ECLIC_TRIGGER {
ECLIC_LEVEL_TRIGGER = 0x0, /*!< Level Triggerred, trig[0] = 0 */
ECLIC_POSTIVE_EDGE_TRIGGER = 0x1, /*!< Postive/Rising Edge Triggered, trig[0] = 1, trig[1] = 0 */
ECLIC_NEGTIVE_EDGE_TRIGGER = 0x3, /*!< Negtive/Falling Edge Triggered, trig[0] = 1, trig[1] = 1 */
ECLIC_MAX_TRIGGER = 0x3 /*!< MAX Supported Trigger Mode */
} ECLIC_TRIGGER_Type;
#ifndef __ECLIC_BASEADDR
/* Base address of ECLIC(__ECLIC_BASEADDR) should be defined in <Device.h> */
#error "__ECLIC_BASEADDR is not defined, please check!"
#endif
#ifndef __ECLIC_INTCTLBITS
/* Define __ECLIC_INTCTLBITS to get via ECLIC->INFO if not defined */
#define __ECLIC_INTCTLBITS (__ECLIC_GetInfoCtlbits())
#endif
/* ECLIC Memory mapping of Device */
#define ECLIC_BASE __ECLIC_BASEADDR /*!< ECLIC Base Address */
#define ECLIC ((CLIC_Type *) ECLIC_BASE) /*!< CLIC configuration struct */
/** @} */ /* end of group NMSIS_Core_ECLIC_Registers */
/* ########################## ECLIC functions #################################### */
/**
* \defgroup NMSIS_Core_IntExc Interrupts and Exceptions
* \brief Functions that manage interrupts and exceptions via the ECLIC.
*
* @{
*/
/**
* \brief Definition of IRQn numbers
* \details
* The core interrupt enumeration names for IRQn values are defined in the file <b><Device>.h</b>.
* - Interrupt ID(IRQn) from 0 to 18 are reserved for core internal interrupts.
* - Interrupt ID(IRQn) start from 19 represent device-specific external interrupts.
* - The first device-specific interrupt has the IRQn value 19.
*
* The table below describes the core interrupt names and their availability in various Nuclei Cores.
*/
/* The following enum IRQn definition in this file
* is only used for doxygen documentation generation,
* The <Device>.h is the real file to define it by vendor
*/
#if defined(__ONLY_FOR_DOXYGEN_DOCUMENT_GENERATION__)
typedef enum IRQn {
/* ========= Nuclei N/NX Core Specific Interrupt Numbers =========== */
/* Core Internal Interrupt IRQn definitions */
Reserved0_IRQn = 0, /*!< Internal reserved */
Reserved1_IRQn = 1, /*!< Internal reserved */
Reserved2_IRQn = 2, /*!< Internal reserved */
SysTimerSW_IRQn = 3, /*!< System Timer SW interrupt */
Reserved3_IRQn = 4, /*!< Internal reserved */
Reserved4_IRQn = 5, /*!< Internal reserved */
Reserved5_IRQn = 6, /*!< Internal reserved */
SysTimer_IRQn = 7, /*!< System Timer Interrupt */
Reserved6_IRQn = 8, /*!< Internal reserved */
Reserved7_IRQn = 9, /*!< Internal reserved */
Reserved8_IRQn = 10, /*!< Internal reserved */
Reserved9_IRQn = 11, /*!< Internal reserved */
Reserved10_IRQn = 12, /*!< Internal reserved */
Reserved11_IRQn = 13, /*!< Internal reserved */
Reserved12_IRQn = 14, /*!< Internal reserved */
Reserved13_IRQn = 15, /*!< Internal reserved */
Reserved14_IRQn = 16, /*!< Internal reserved */
Reserved15_IRQn = 17, /*!< Internal reserved */
Reserved16_IRQn = 18, /*!< Internal reserved */
/* ========= Device Specific Interrupt Numbers =================== */
/* ToDo: add here your device specific external interrupt numbers.
* 19~max(NUM_INTERRUPT, 1023) is reserved number for user.
* Maxmum interrupt supported could get from clicinfo.NUM_INTERRUPT.
* According the interrupt handlers defined in startup_Device.S
* eg.: Interrupt for Timer#1 eclic_tim1_handler -> TIM1_IRQn */
FirstDeviceSpecificInterrupt_IRQn = 19, /*!< First Device Specific Interrupt */
SOC_INT_MAX, /*!< Number of total interrupts */
} IRQn_Type;
#endif /* __ONLY_FOR_DOXYGEN_DOCUMENT_GENERATION__ */
#ifdef NMSIS_ECLIC_VIRTUAL
#ifndef NMSIS_ECLIC_VIRTUAL_HEADER_FILE
#define NMSIS_ECLIC_VIRTUAL_HEADER_FILE "nmsis_eclic_virtual.h"
#endif
#include NMSIS_ECLIC_VIRTUAL_HEADER_FILE
#else
#define ECLIC_SetCfgNlbits __ECLIC_SetCfgNlbits
#define ECLIC_GetCfgNlbits __ECLIC_GetCfgNlbits
#define ECLIC_GetInfoVer __ECLIC_GetInfoVer
#define ECLIC_GetInfoCtlbits __ECLIC_GetInfoCtlbits
#define ECLIC_GetInfoNum __ECLIC_GetInfoNum
#define ECLIC_SetMth __ECLIC_SetMth
#define ECLIC_GetMth __ECLIC_GetMth
#define ECLIC_EnableIRQ __ECLIC_EnableIRQ
#define ECLIC_GetEnableIRQ __ECLIC_GetEnableIRQ
#define ECLIC_DisableIRQ __ECLIC_DisableIRQ
#define ECLIC_SetPendingIRQ __ECLIC_SetPendingIRQ
#define ECLIC_GetPendingIRQ __ECLIC_GetPendingIRQ
#define ECLIC_ClearPendingIRQ __ECLIC_ClearPendingIRQ
#define ECLIC_SetTrigIRQ __ECLIC_SetTrigIRQ
#define ECLIC_GetTrigIRQ __ECLIC_GetTrigIRQ
#define ECLIC_SetShvIRQ __ECLIC_SetShvIRQ
#define ECLIC_GetShvIRQ __ECLIC_GetShvIRQ
#define ECLIC_SetCtrlIRQ __ECLIC_SetCtrlIRQ
#define ECLIC_GetCtrlIRQ __ECLIC_GetCtrlIRQ
#define ECLIC_SetLevelIRQ __ECLIC_SetLevelIRQ
#define ECLIC_GetLevelIRQ __ECLIC_GetLevelIRQ
#define ECLIC_SetPriorityIRQ __ECLIC_SetPriorityIRQ
#define ECLIC_GetPriorityIRQ __ECLIC_GetPriorityIRQ
#endif /* NMSIS_ECLIC_VIRTUAL */
#ifdef NMSIS_VECTAB_VIRTUAL
#ifndef NMSIS_VECTAB_VIRTUAL_HEADER_FILE
#define NMSIS_VECTAB_VIRTUAL_HEADER_FILE "nmsis_vectab_virtual.h"
#endif
#include NMSIS_VECTAB_VIRTUAL_HEADER_FILE
#else
#define ECLIC_SetVector __ECLIC_SetVector
#define ECLIC_GetVector __ECLIC_GetVector
#endif /* (NMSIS_VECTAB_VIRTUAL) */
/**
* \brief Set nlbits value
* \details
* This function set the nlbits value of CLICCFG register.
* \param [in] nlbits nlbits value
* \remarks
* - nlbits is used to set the width of level in the CLICINTCTL[i].
* \sa
* - \ref ECLIC_GetCfgNlbits
*/
__STATIC_FORCEINLINE void __ECLIC_SetCfgNlbits(uint32_t nlbits)
{
ECLIC->CFG &= ~CLIC_CLICCFG_NLBIT_Msk;
ECLIC->CFG |= (uint8_t)((nlbits <<CLIC_CLICCFG_NLBIT_Pos) & CLIC_CLICCFG_NLBIT_Msk);
}
/**
* \brief Get nlbits value
* \details
* This function get the nlbits value of CLICCFG register.
* \return nlbits value of CLICCFG register
* \remarks
* - nlbits is used to set the width of level in the CLICINTCTL[i].
* \sa
* - \ref ECLIC_SetCfgNlbits
*/
__STATIC_FORCEINLINE uint32_t __ECLIC_GetCfgNlbits(void)
{
return ((uint32_t)((ECLIC->CFG & CLIC_CLICCFG_NLBIT_Msk) >> CLIC_CLICCFG_NLBIT_Pos));
}
/**
* \brief Get the ECLIC version number
* \details
* This function gets the hardware version information from CLICINFO register.
* \return hardware version number in CLICINFO register.
* \remarks
* - This function gets harware version information from CLICINFO register.
* - Bit 20:17 for architecture version, bit 16:13 for implementation version.
* \sa
* - \ref ECLIC_GetInfoNum
*/
__STATIC_FORCEINLINE uint32_t __ECLIC_GetInfoVer(void)
{
return ((uint32_t)((ECLIC->INFO & CLIC_CLICINFO_VER_Msk) >> CLIC_CLICINFO_VER_Pos));
}
/**
* \brief Get CLICINTCTLBITS
* \details
* This function gets CLICINTCTLBITS from CLICINFO register.
* \return CLICINTCTLBITS from CLICINFO register.
* \remarks
* - In the CLICINTCTL[i] registers, with 2 <= CLICINTCTLBITS <= 8.
* - The implemented bits are kept left-justified in the most-significant bits of each 8-bit
* CLICINTCTL[I] register, with the lower unimplemented bits treated as hardwired to 1.
* \sa
* - \ref ECLIC_GetInfoNum
*/
__STATIC_FORCEINLINE uint32_t __ECLIC_GetInfoCtlbits(void)
{
return ((uint32_t)((ECLIC->INFO & CLIC_CLICINFO_CTLBIT_Msk) >> CLIC_CLICINFO_CTLBIT_Pos));
}
/**
* \brief Get number of maximum interrupt inputs supported
* \details
* This function gets number of maximum interrupt inputs supported from CLICINFO register.
* \return number of maximum interrupt inputs supported from CLICINFO register.
* \remarks
* - This function gets number of maximum interrupt inputs supported from CLICINFO register.
* - The num_interrupt field specifies the actual number of maximum interrupt inputs supported in this implementation.
* \sa
* - \ref ECLIC_GetInfoCtlbits
*/
__STATIC_FORCEINLINE uint32_t __ECLIC_GetInfoNum(void)
{
return ((uint32_t)((ECLIC->INFO & CLIC_CLICINFO_NUM_Msk) >> CLIC_CLICINFO_NUM_Pos));
}
/**
* \brief Set Machine Mode Interrupt Level Threshold
* \details
* This function sets machine mode interrupt level threshold.
* \param [in] mth Interrupt Level Threshold.
* \sa
* - \ref ECLIC_GetMth
*/
__STATIC_FORCEINLINE void __ECLIC_SetMth(uint8_t mth)
{
ECLIC->MTH = mth;
}
/**
* \brief Get Machine Mode Interrupt Level Threshold
* \details
* This function gets machine mode interrupt level threshold.
* \return Interrupt Level Threshold.
* \sa
* - \ref ECLIC_SetMth
*/
__STATIC_FORCEINLINE uint8_t __ECLIC_GetMth(void)
{
return (ECLIC->MTH);
}
/**
* \brief Enable a specific interrupt
* \details
* This function enables the specific interrupt \em IRQn.
* \param [in] IRQn Interrupt number
* \remarks
* - IRQn must not be negative.
* \sa
* - \ref ECLIC_DisableIRQ
*/
__STATIC_FORCEINLINE void __ECLIC_EnableIRQ(IRQn_Type IRQn)
{
ECLIC->CTRL[IRQn].INTIE |= CLIC_INTIE_IE_Msk;
}
/**
* \brief Get a specific interrupt enable status
* \details
* This function returns the interrupt enable status for the specific interrupt \em IRQn.
* \param [in] IRQn Interrupt number
* \returns
* - 0 Interrupt is not enabled
* - 1 Interrupt is pending
* \remarks
* - IRQn must not be negative.
* \sa
* - \ref ECLIC_EnableIRQ
* - \ref ECLIC_DisableIRQ
*/
__STATIC_FORCEINLINE uint32_t __ECLIC_GetEnableIRQ(IRQn_Type IRQn)
{
return((uint32_t) (ECLIC->CTRL[IRQn].INTIE) & CLIC_INTIE_IE_Msk);
}
/**
* \brief Disable a specific interrupt
* \details
* This function disables the specific interrupt \em IRQn.
* \param [in] IRQn Number of the external interrupt to disable
* \remarks
* - IRQn must not be negative.
* \sa
* - \ref ECLIC_EnableIRQ
*/
__STATIC_FORCEINLINE void __ECLIC_DisableIRQ(IRQn_Type IRQn)
{
ECLIC->CTRL[IRQn].INTIE &= ~CLIC_INTIE_IE_Msk;
}
/**
* \brief Get the pending specific interrupt
* \details
* This function returns the pending status of the specific interrupt \em IRQn.
* \param [in] IRQn Interrupt number
* \returns
* - 0 Interrupt is not pending
* - 1 Interrupt is pending
* \remarks
* - IRQn must not be negative.
* \sa
* - \ref ECLIC_SetPendingIRQ
* - \ref ECLIC_ClearPendingIRQ
*/
__STATIC_FORCEINLINE int32_t __ECLIC_GetPendingIRQ(IRQn_Type IRQn)
{
return((uint32_t)(ECLIC->CTRL[IRQn].INTIP) & CLIC_INTIP_IP_Msk);
}
/**
* \brief Set a specific interrupt to pending
* \details
* This function sets the pending bit for the specific interrupt \em IRQn.
* \param [in] IRQn Interrupt number
* \remarks
* - IRQn must not be negative.
* \sa
* - \ref ECLIC_GetPendingIRQ
* - \ref ECLIC_ClearPendingIRQ
*/
__STATIC_FORCEINLINE void __ECLIC_SetPendingIRQ(IRQn_Type IRQn)
{
ECLIC->CTRL[IRQn].INTIP |= CLIC_INTIP_IP_Msk;
}
/**
* \brief Clear a specific interrupt from pending
* \details
* This function removes the pending state of the specific interrupt \em IRQn.
* \em IRQn cannot be a negative number.
* \param [in] IRQn Interrupt number
* \remarks
* - IRQn must not be negative.
* \sa
* - \ref ECLIC_SetPendingIRQ
* - \ref ECLIC_GetPendingIRQ
*/
__STATIC_FORCEINLINE void __ECLIC_ClearPendingIRQ(IRQn_Type IRQn)
{
ECLIC->CTRL[IRQn].INTIP &= ~ CLIC_INTIP_IP_Msk;
}
/**
* \brief Set trigger mode and polarity for a specific interrupt
* \details
* This function set trigger mode and polarity of the specific interrupt \em IRQn.
* \param [in] IRQn Interrupt number
* \param [in] trig
* - 00 level trigger, \ref ECLIC_LEVEL_TRIGGER
* - 01 positive edge trigger, \ref ECLIC_POSTIVE_EDGE_TRIGGER
* - 02 level trigger, \ref ECLIC_LEVEL_TRIGGER
* - 03 negative edge trigger, \ref ECLIC_NEGTIVE_EDGE_TRIGGER
* \remarks
* - IRQn must not be negative.
*
* \sa
* - \ref ECLIC_GetTrigIRQ
*/
__STATIC_FORCEINLINE void __ECLIC_SetTrigIRQ(IRQn_Type IRQn, uint32_t trig)
{
ECLIC->CTRL[IRQn].INTATTR &= ~CLIC_INTATTR_TRIG_Msk;
ECLIC->CTRL[IRQn].INTATTR |= (uint8_t)(trig<<CLIC_INTATTR_TRIG_Pos);
}
/**
* \brief Get trigger mode and polarity for a specific interrupt
* \details
* This function get trigger mode and polarity of the specific interrupt \em IRQn.
* \param [in] IRQn Interrupt number
* \return
* - 00 level trigger, \ref ECLIC_LEVEL_TRIGGER
* - 01 positive edge trigger, \ref ECLIC_POSTIVE_EDGE_TRIGGER
* - 02 level trigger, \ref ECLIC_LEVEL_TRIGGER
* - 03 negative edge trigger, \ref ECLIC_NEGTIVE_EDGE_TRIGGER
* \remarks
* - IRQn must not be negative.
* \sa
* - \ref ECLIC_SetTrigIRQ
*/
__STATIC_FORCEINLINE uint32_t __ECLIC_GetTrigIRQ(IRQn_Type IRQn)
{
return ((int32_t)(((ECLIC->CTRL[IRQn].INTATTR) & CLIC_INTATTR_TRIG_Msk)>>CLIC_INTATTR_TRIG_Pos));
}
/**
* \brief Set interrupt working mode for a specific interrupt
* \details
* This function set selective hardware vector or non-vector working mode of the specific interrupt \em IRQn.
* \param [in] IRQn Interrupt number
* \param [in] shv
* - 0 non-vector mode, \ref ECLIC_NON_VECTOR_INTERRUPT
* - 1 vector mode, \ref ECLIC_VECTOR_INTERRUPT
* \remarks
* - IRQn must not be negative.
* \sa
* - \ref ECLIC_GetShvIRQ
*/
__STATIC_FORCEINLINE void __ECLIC_SetShvIRQ(IRQn_Type IRQn, uint32_t shv)
{
ECLIC->CTRL[IRQn].INTATTR &= ~CLIC_INTATTR_SHV_Msk;
ECLIC->CTRL[IRQn].INTATTR |= (uint8_t)(shv<<CLIC_INTATTR_SHV_Pos);
}
/**
* \brief Get interrupt working mode for a specific interrupt
* \details
* This function get selective hardware vector or non-vector working mode of the specific interrupt \em IRQn.
* \param [in] IRQn Interrupt number
* \return shv
* - 0 non-vector mode, \ref ECLIC_NON_VECTOR_INTERRUPT
* - 1 vector mode, \ref ECLIC_VECTOR_INTERRUPT
* \remarks
* - IRQn must not be negative.
* \sa
* - \ref ECLIC_SetShvIRQ
*/
__STATIC_FORCEINLINE uint32_t __ECLIC_GetShvIRQ(IRQn_Type IRQn)
{
return ((int32_t)(((ECLIC->CTRL[IRQn].INTATTR) & CLIC_INTATTR_SHV_Msk)>>CLIC_INTATTR_SHV_Pos));
}
/**
* \brief Modify ECLIC Interrupt Input Control Register for a specific interrupt
* \details
* This function modify ECLIC Interrupt Input Control(CLICINTCTL[i]) register of the specific interrupt \em IRQn.
* \param [in] IRQn Interrupt number
* \param [in] intctrl Set value for CLICINTCTL[i] register
* \remarks
* - IRQn must not be negative.
* \sa
* - \ref ECLIC_GetCtrlIRQ
*/
__STATIC_FORCEINLINE void __ECLIC_SetCtrlIRQ(IRQn_Type IRQn, uint8_t intctrl)
{
ECLIC->CTRL[IRQn].INTCTRL = intctrl;
}
/**
* \brief Get ECLIC Interrupt Input Control Register value for a specific interrupt
* \details
* This function modify ECLIC Interrupt Input Control register of the specific interrupt \em IRQn.
* \param [in] IRQn Interrupt number
* \return value of ECLIC Interrupt Input Control register
* \remarks
* - IRQn must not be negative.
* \sa
* - \ref ECLIC_SetCtrlIRQ
*/
__STATIC_FORCEINLINE uint8_t __ECLIC_GetCtrlIRQ(IRQn_Type IRQn)
{
return (ECLIC->CTRL[IRQn].INTCTRL);
}
/**
* \brief Set ECLIC Interrupt level of a specific interrupt
* \details
* This function set interrupt level of the specific interrupt \em IRQn.
* \param [in] IRQn Interrupt number
* \param [in] lvl_abs Interrupt level
* \remarks
* - IRQn must not be negative.
* - If lvl_abs to be set is larger than the max level allowed, it will be force to be max level.
* - When you set level value you need use clciinfo.nlbits to get the width of level.
* Then we could know the maximum of level. CLICINTCTLBITS is how many total bits are
* present in the CLICINTCTL register.
* \sa
* - \ref ECLIC_GetLevelIRQ
*/
__STATIC_FORCEINLINE void __ECLIC_SetLevelIRQ(IRQn_Type IRQn, uint8_t lvl_abs)
{
uint8_t nlbits = __ECLIC_GetCfgNlbits();
uint8_t intctlbits = (uint8_t)__ECLIC_INTCTLBITS;
if (nlbits == 0) {
return;
}
if (nlbits > intctlbits) {
nlbits = intctlbits;
}
uint8_t maxlvl = ((1 << nlbits) - 1);
if (lvl_abs > maxlvl) {
lvl_abs = maxlvl;
}
uint8_t lvl = lvl_abs << (ECLIC_MAX_NLBITS - nlbits);
uint8_t cur_ctrl = __ECLIC_GetCtrlIRQ(IRQn);
cur_ctrl = cur_ctrl << nlbits;
cur_ctrl = cur_ctrl >> nlbits;
__ECLIC_SetCtrlIRQ(IRQn, (cur_ctrl | lvl));
}
/**
* \brief Get ECLIC Interrupt level of a specific interrupt
* \details
* This function get interrupt level of the specific interrupt \em IRQn.
* \param [in] IRQn Interrupt number
* \return Interrupt level
* \remarks
* - IRQn must not be negative.
* \sa
* - \ref ECLIC_SetLevelIRQ
*/
__STATIC_FORCEINLINE uint8_t __ECLIC_GetLevelIRQ(IRQn_Type IRQn)
{
uint8_t nlbits = __ECLIC_GetCfgNlbits();
uint8_t intctlbits = (uint8_t)__ECLIC_INTCTLBITS;
if (nlbits == 0) {
return 0;
}
if (nlbits > intctlbits) {
nlbits = intctlbits;
}
uint8_t intctrl = __ECLIC_GetCtrlIRQ(IRQn);
uint8_t lvl_abs = intctrl >> (ECLIC_MAX_NLBITS - nlbits);
return lvl_abs;
}
/**
* \brief Get ECLIC Interrupt priority of a specific interrupt
* \details
* This function get interrupt priority of the specific interrupt \em IRQn.
* \param [in] IRQn Interrupt number
* \param [in] pri Interrupt priority
* \remarks
* - IRQn must not be negative.
* - If pri to be set is larger than the max priority allowed, it will be force to be max priority.
* - Priority width is CLICINTCTLBITS minus clciinfo.nlbits if clciinfo.nlbits
* is less than CLICINTCTLBITS. Otherwise priority width is 0.
* \sa
* - \ref ECLIC_GetPriorityIRQ
*/
__STATIC_FORCEINLINE void __ECLIC_SetPriorityIRQ(IRQn_Type IRQn, uint8_t pri)
{
uint8_t nlbits = __ECLIC_GetCfgNlbits();
uint8_t intctlbits = (uint8_t)__ECLIC_INTCTLBITS;
if (nlbits < intctlbits) {
uint8_t maxpri = ((1 << (intctlbits - nlbits)) - 1);
if (pri > maxpri) {
pri = maxpri;
}
pri = pri << (ECLIC_MAX_NLBITS - intctlbits);
uint8_t mask = ((uint8_t)(-1)) >> intctlbits;
pri = pri | mask;
uint8_t cur_ctrl = __ECLIC_GetCtrlIRQ(IRQn);
cur_ctrl = cur_ctrl >> (ECLIC_MAX_NLBITS - nlbits);
cur_ctrl = cur_ctrl << (ECLIC_MAX_NLBITS - nlbits);
__ECLIC_SetCtrlIRQ(IRQn, (cur_ctrl | pri));
}
}
/**
* \brief Get ECLIC Interrupt priority of a specific interrupt
* \details
* This function get interrupt priority of the specific interrupt \em IRQn.
* \param [in] IRQn Interrupt number
* \return Interrupt priority
* \remarks
* - IRQn must not be negative.
* \sa
* - \ref ECLIC_SetPriorityIRQ
*/
__STATIC_FORCEINLINE uint8_t __ECLIC_GetPriorityIRQ(IRQn_Type IRQn)
{
uint8_t nlbits = __ECLIC_GetCfgNlbits();
uint8_t intctlbits = (uint8_t)__ECLIC_INTCTLBITS;
if (nlbits < intctlbits) {
uint8_t cur_ctrl = __ECLIC_GetCtrlIRQ(IRQn);
uint8_t pri = cur_ctrl << nlbits;
pri = pri >> nlbits;
pri = pri >> (ECLIC_MAX_NLBITS - intctlbits);
return pri;
} else {
return 0;
}
}
/**
* \brief Set Interrupt Vector of a specific interrupt
* \details
* This function set interrupt handler address of the specific interrupt \em IRQn.
* \param [in] IRQn Interrupt number
* \param [in] vector Interrupt handler address
* \remarks
* - IRQn must not be negative.
* - You can set the \ref CSR_CSR_MTVT to set interrupt vector table entry address.
* - If your vector table is placed in readonly section, the vector for IRQn will not be modified.
* For this case, you need to use the correct irq handler name defined in your vector table as
* your irq handler function name.
* - This function will only work correctly when the vector table is placed in an read-write enabled section.
* \sa
* - \ref ECLIC_GetVector
*/
__STATIC_FORCEINLINE void __ECLIC_SetVector(IRQn_Type IRQn, rv_csr_t vector)
{
#if __RISCV_XLEN == 32
volatile uint32_t vec_base;
vec_base = ((uint32_t)__RV_CSR_READ(CSR_MTVT));
(* (unsigned long *) (vec_base + ((int32_t)IRQn) * 4)) = vector;
#elif __RISCV_XLEN == 64
volatile uint64_t vec_base;
vec_base = ((uint64_t)__RV_CSR_READ(CSR_MTVT));
(* (unsigned long *) (vec_base + ((int32_t)IRQn) * 8)) = vector;
#else // TODO Need cover for XLEN=128 case in future
volatile uint64_t vec_base;
vec_base = ((uint64_t)__RV_CSR_READ(CSR_MTVT));
(* (unsigned long *) (vec_base + ((int32_t)IRQn) * 8)) = vector;
#endif
}
/**
* \brief Get Interrupt Vector of a specific interrupt
* \details
* This function get interrupt handler address of the specific interrupt \em IRQn.
* \param [in] IRQn Interrupt number
* \return Interrupt handler address
* \remarks
* - IRQn must not be negative.
* - You can read \ref CSR_CSR_MTVT to get interrupt vector table entry address.
* \sa
* - \ref ECLIC_SetVector
*/
__STATIC_FORCEINLINE rv_csr_t __ECLIC_GetVector(IRQn_Type IRQn)
{
#if __RISCV_XLEN == 32
return (*(uint32_t *)(__RV_CSR_READ(CSR_MTVT)+IRQn*4));
#elif __RISCV_XLEN == 64
return (*(uint64_t *)(__RV_CSR_READ(CSR_MTVT)+IRQn*8));
#else // TODO Need cover for XLEN=128 case in future
return (*(uint64_t *)(__RV_CSR_READ(CSR_MTVT)+IRQn*8));
#endif
}
/**
* \brief Set Exception entry address
* \details
* This function set exception handler address to 'CSR_MTVEC'.
* \param [in] addr Exception handler address
* \remarks
* - This function use to set exception handler address to 'CSR_MTVEC'. Address is 4 bytes align.
* \sa
* - \ref __get_exc_entry
*/
__STATIC_FORCEINLINE void __set_exc_entry(rv_csr_t addr)
{
addr &= (rv_csr_t)(~0x3F);
addr |= ECLIC_MODE_MTVEC_Msk;
__RV_CSR_WRITE(CSR_MTVEC, addr);
}
/**
* \brief Get Exception entry address
* \details
* This function get exception handler address from 'CSR_MTVEC'.
* \return Exception handler address
* \remarks
* - This function use to get exception handler address from 'CSR_MTVEC'. Address is 4 bytes align
* \sa
* - \ref __set_exc_entry
*/
__STATIC_FORCEINLINE rv_csr_t __get_exc_entry(void)
{
unsigned long addr = __RV_CSR_READ(CSR_MTVEC);
return (addr & ~ECLIC_MODE_MTVEC_Msk);
}
/**
* \brief Set Non-vector interrupt entry address
* \details
* This function set Non-vector interrupt address.
* \param [in] addr Non-vector interrupt entry address
* \remarks
* - This function use to set non-vector interrupt entry address to 'CSR_MTVT2' if
* - CSR_MTVT2 bit0 is 1. If 'CSR_MTVT2' bit0 is 0 then set address to 'CSR_MTVEC'
* \sa
* - \ref __get_nonvec_entry
*/
__STATIC_FORCEINLINE void __set_nonvec_entry(rv_csr_t addr)
{
if (__RV_CSR_READ(CSR_MTVT2) & 0x1){
__RV_CSR_WRITE(CSR_MTVT2, addr | 0x01);
} else {
addr &= (rv_csr_t)(~0x3F);
addr |= ECLIC_MODE_MTVEC_Msk;
__RV_CSR_WRITE(CSR_MTVEC, addr);
}
}
/**
* \brief Get Non-vector interrupt entry address
* \details
* This function get Non-vector interrupt address.
* \return Non-vector interrupt handler address
* \remarks
* - This function use to get non-vector interrupt entry address from 'CSR_MTVT2' if
* - CSR_MTVT2 bit0 is 1. If 'CSR_MTVT2' bit0 is 0 then get address from 'CSR_MTVEC'.
* \sa
* - \ref __set_nonvec_entry
*/
__STATIC_FORCEINLINE rv_csr_t __get_nonvec_entry(void)
{
if (__RV_CSR_READ(CSR_MTVT2) & 0x1) {
return __RV_CSR_READ(CSR_MTVT2) & (~(rv_csr_t)(0x1));
} else {
rv_csr_t addr = __RV_CSR_READ(CSR_MTVEC);
return (addr & ~ECLIC_MODE_MTVEC_Msk);
}
}
/**
* \brief Get NMI interrupt entry from 'CSR_MNVEC'
* \details
* This function get NMI interrupt address from 'CSR_MNVEC'.
* \return NMI interrupt handler address
* \remarks
* - This function use to get NMI interrupt handler address from 'CSR_MNVEC'. If CSR_MMISC_CTL[9] = 1 'CSR_MNVEC'
* - will be equal as mtvec. If CSR_MMISC_CTL[9] = 0 'CSR_MNVEC' will be equal as reset vector.
* - NMI entry is defined via \ref CSR_MMISC_CTL, writing to \ref CSR_MNVEC will be ignored.
*/
__STATIC_FORCEINLINE rv_csr_t __get_nmi_entry(void)
{
return __RV_CSR_READ(CSR_MNVEC);
}
/**
* \brief Save necessary CSRs into variables for vector interrupt nesting
* \details
* This macro is used to declare variables which are used for saving
* CSRs(MCAUSE, MEPC, MSUB), and it will read these CSR content into
* these variables, it need to be used in a vector-interrupt if nesting
* is required.
* \remarks
* - Interrupt will be enabled after this macro is called
* - It need to be used together with \ref RESTORE_IRQ_CSR_CONTEXT
* - Don't use variable names __mcause, __mpec, __msubm in your ISR code
* - If you want to enable interrupt nesting feature for vector interrupt,
* you can do it like this:
* \code
* // __INTERRUPT attribute will generates function entry and exit sequences suitable
* // for use in an interrupt handler when this attribute is present
* __INTERRUPT void eclic_mtip_handler(void)
* {
* // Must call this to save CSRs
* SAVE_IRQ_CSR_CONTEXT();
* // !!!Interrupt is enabled here!!!
* // !!!Higher priority interrupt could nest it!!!
*
* // put you own interrupt handling code here
*
* // Must call this to restore CSRs
* RESTORE_IRQ_CSR_CONTEXT();
* }
* \endcode
*/
#define SAVE_IRQ_CSR_CONTEXT() \
rv_csr_t __mcause = __RV_CSR_READ(CSR_MCAUSE); \
rv_csr_t __mepc = __RV_CSR_READ(CSR_MEPC); \
rv_csr_t __msubm = __RV_CSR_READ(CSR_MSUBM); \
__enable_irq();
/**
* \brief Restore necessary CSRs from variables for vector interrupt nesting
* \details
* This macro is used restore CSRs(MCAUSE, MEPC, MSUB) from pre-defined variables
* in \ref SAVE_IRQ_CSR_CONTEXT macro.
* \remarks
* - Interrupt will be disabled after this macro is called
* - It need to be used together with \ref SAVE_IRQ_CSR_CONTEXT
*/
#define RESTORE_IRQ_CSR_CONTEXT() \
__disable_irq(); \
__RV_CSR_WRITE(CSR_MSUBM, __msubm); \
__RV_CSR_WRITE(CSR_MEPC, __mepc); \
__RV_CSR_WRITE(CSR_MCAUSE, __mcause);
/** @} */ /* End of Doxygen Group NMSIS_Core_IntExc */
#endif /* defined(__ECLIC_PRESENT) && (__ECLIC_PRESENT == 1) */
#ifdef __cplusplus
}
#endif
#endif /** __CORE_FEATURE_ECLIC__ */

View File

@@ -0,0 +1,304 @@
/*
* Copyright (c) 2019 Nuclei Limited. All rights reserved.
*
* SPDX-License-Identifier: Apache-2.0
*
* Licensed under the Apache License, Version 2.0 (the License); you may
* not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an AS IS BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*/
#ifndef __CORE_FEATURE_FPU_H__
#define __CORE_FEATURE_FPU_H__
/*!
* @file core_feature_fpu.h
* @brief FPU feature API header file for Nuclei N/NX Core
*/
/*
* FPU Feature Configuration Macro:
* 1. __FPU_PRESENT: Define whether Floating Point Unit(FPU) is present or not
* * 0: Not present
* * 1: Single precision FPU present, __RISCV_FLEN == 32
* * 2: Double precision FPU present, __RISCV_FLEN == 64
*/
#ifdef __cplusplus
extern "C" {
#endif
/* ===== FPU Operations ===== */
/**
* \defgroup NMSIS_Core_FPU_Functions FPU Functions
* \ingroup NMSIS_Core
* \brief Functions that related to the RISC-V FPU (F and D extension).
* \details
*
* Nuclei provided floating point unit by RISC-V F and D extension.
* * `F extension` adds single-precision floating-point computational
* instructions compliant with the IEEE 754-2008 arithmetic standard, __RISCV_FLEN = 32.
* The F extension adds 32 floating-point registers, f0-f31, each 32 bits wide,
* and a floating-point control and status register fcsr, which contains the
* operating mode and exception status of the floating-point unit.
* * `D extension` adds double-precision floating-point computational instructions
* compliant with the IEEE 754-2008 arithmetic standard.
* The D extension widens the 32 floating-point registers, f0-f31, to 64 bits, __RISCV_FLEN = 64
* @{
*/
#if defined(__FPU_PRESENT) && (__FPU_PRESENT > 0)
#if __FPU_PRESENT == 1
/** \brief Refer to the width of the floating point register in bits(either 32 or 64) */
#define __RISCV_FLEN 32
#elif __FPU_PRESENT == 2
#define __RISCV_FLEN 64
#else
#define __RISCV_FLEN __riscv_flen
#endif /* __FPU_PRESENT == 1 */
/** \brief Get FCSR CSR Register */
#define __get_FCSR() __RV_CSR_READ(CSR_FCSR)
/** \brief Set FCSR CSR Register with val */
#define __set_FCSR(val) __RV_CSR_WRITE(CSR_FCSR, (val))
/** \brief Get FRM CSR Register */
#define __get_FRM() __RV_CSR_READ(CSR_FRM)
/** \brief Set FRM CSR Register with val */
#define __set_FRM(val) __RV_CSR_WRITE(CSR_FRM, (val))
/** \brief Get FFLAGS CSR Register */
#define __get_FFLAGS() __RV_CSR_READ(CSR_FFLAGS)
/** \brief Set FFLAGS CSR Register with val */
#define __set_FFLAGS(val) __RV_CSR_WRITE(CSR_FFLAGS, (val))
/** \brief Enable FPU Unit */
#define __enable_FPU() __RV_CSR_SET(CSR_MSTATUS, MSTATUS_FS)
/**
* \brief Disable FPU Unit
* \details
* * We can save power by disable FPU Unit.
* * When FPU Unit is disabled, any access to FPU related CSR registers
* and FPU instructions will cause illegal Instuction Exception.
* */
#define __disable_FPU() __RV_CSR_CLEAR(CSR_MSTATUS, MSTATUS_FS)
/**
* \brief Load a single-precision value from memory into float point register freg using flw instruction
* \details The FLW instruction loads a single-precision floating point value from memory
* address (addr + ofs) into floating point register freg(f0-f31)
* \param [in] freg The floating point register, eg. FREG(0), f0
* \param [in] addr The memory base address, 4 byte aligned required
* \param [in] ofs a 12-bit immediate signed byte offset value, should be an const value
* \remarks
* * FLW and FSW operations need to make sure the address is 4 bytes aligned,
* otherwise it will cause exception code 4(Load address misaligned) or 6 (Store/AMO address misaligned)
* * FLW and FSW do not modify the bits being transferred; in particular, the payloads of non-canonical
* NaNs are preserved
*
*/
#define __RV_FLW(freg, addr, ofs) \
({ \
register rv_csr_t __addr = (rv_csr_t)(addr); \
__ASM volatile("flw " STRINGIFY(freg) ", %0(%1) " \
: : "I"(ofs), "r"(__addr) \
: "memory"); \
})
/**
* \brief Store a single-precision value from float point freg into memory using fsw instruction
* \details The FSW instruction stores a single-precision value from floating point register to memory
* \param [in] freg The floating point register(f0-f31), eg. FREG(0), f0
* \param [in] addr The memory base address, 4 byte aligned required
* \param [in] ofs a 12-bit immediate signed byte offset value, should be an const value
* \remarks
* * FLW and FSW operations need to make sure the address is 4 bytes aligned,
* otherwise it will cause exception code 4(Load address misaligned) or 6 (Store/AMO address misaligned)
* * FLW and FSW do not modify the bits being transferred; in particular, the payloads of non-canonical
* NaNs are preserved
*
*/
#define __RV_FSW(freg, addr, ofs) \
({ \
register rv_csr_t __addr = (rv_csr_t)(addr); \
__ASM volatile("fsw " STRINGIFY(freg) ", %0(%1) " \
: : "I"(ofs), "r"(__addr) \
: "memory"); \
})
/**
* \brief Load a double-precision value from memory into float point register freg using fld instruction
* \details The FLD instruction loads a double-precision floating point value from memory
* address (addr + ofs) into floating point register freg(f0-f31)
* \param [in] freg The floating point register, eg. FREG(0), f0
* \param [in] addr The memory base address, 8 byte aligned required
* \param [in] ofs a 12-bit immediate signed byte offset value, should be an const value
* \attention
* * Function only available for double precision floating point unit, FLEN = 64
* \remarks
* * FLD and FSD operations need to make sure the address is 8 bytes aligned,
* otherwise it will cause exception code 4(Load address misaligned) or 6 (Store/AMO address misaligned)
* * FLD and FSD do not modify the bits being transferred; in particular, the payloads of non-canonical
* NaNs are preserved.
*/
#define __RV_FLD(freg, addr, ofs) \
({ \
register rv_csr_t __addr = (rv_csr_t)(addr); \
__ASM volatile("fld " STRINGIFY(freg) ", %0(%1) " \
: : "I"(ofs), "r"(__addr) \
: "memory"); \
})
/**
* \brief Store a double-precision value from float point freg into memory using fsd instruction
* \details The FSD instruction stores double-precision value from floating point register to memory
* \param [in] freg The floating point register(f0-f31), eg. FREG(0), f0
* \param [in] addr The memory base address, 8 byte aligned required
* \param [in] ofs a 12-bit immediate signed byte offset value, should be an const value
* \attention
* * Function only available for double precision floating point unit, FLEN = 64
* \remarks
* * FLD and FSD operations need to make sure the address is 8 bytes aligned,
* otherwise it will cause exception code 4(Load address misaligned) or 6 (Store/AMO address misaligned)
* * FLD and FSD do not modify the bits being transferred; in particular, the payloads of non-canonical
* NaNs are preserved.
*
*/
#define __RV_FSD(freg, addr, ofs) \
({ \
register rv_csr_t __addr = (rv_csr_t)(addr); \
__ASM volatile("fsd " STRINGIFY(freg) ", %0(%1) " \
: : "I"(ofs), "r"(__addr) \
: "memory"); \
})
/**
* \def __RV_FLOAD
* \brief Load a float point value from memory into float point register freg using flw/fld instruction
* \details
* * For Single-Precison Floating-Point Mode(__FPU_PRESENT == 1, __RISCV_FLEN == 32):
* It will call \ref __RV_FLW to load a single-precision floating point value from memory to floating point register
* * For Double-Precison Floating-Point Mode(__FPU_PRESENT == 2, __RISCV_FLEN == 64):
* It will call \ref __RV_FLD to load a double-precision floating point value from memory to floating point register
*
* \attention
* Function behaviour is different for __FPU_PRESENT = 1 or 2, please see the real function this macro represent
*/
/**
* \def __RV_FSTORE
* \brief Store a float value from float point freg into memory using fsw/fsd instruction
* \details
* * For Single-Precison Floating-Point Mode(__FPU_PRESENT == 1, __RISCV_FLEN == 32):
* It will call \ref __RV_FSW to store floating point register into memory
* * For Double-Precison Floating-Point Mode(__FPU_PRESENT == 2, __RISCV_FLEN == 64):
* It will call \ref __RV_FSD to store floating point register into memory
*
* \attention
* Function behaviour is different for __FPU_PRESENT = 1 or 2, please see the real function this macro represent
*/
#if __FPU_PRESENT == 1
#define __RV_FLOAD __RV_FLW
#define __RV_FSTORE __RV_FSW
/** \brief Type of FPU register, depends on the FLEN defined in RISC-V */
typedef uint32_t rv_fpu_t;
#elif __FPU_PRESENT == 2
#define __RV_FLOAD __RV_FLD
#define __RV_FSTORE __RV_FSD
/** \brief Type of FPU register, depends on the FLEN defined in RISC-V */
typedef uint64_t rv_fpu_t;
#endif /* __FPU_PRESENT == 2 */
/**
* \brief Save FPU context into variables for interrupt nesting
* \details
* This macro is used to declare variables which are used for saving
* FPU context, and it will store the nessary fpu registers into
* these variables, it need to be used in a interrupt when in this
* interrupt fpu registers are used.
* \remarks
* - It need to be used together with \ref RESTORE_FPU_CONTEXT
* - Don't use variable names __fpu_context in your ISR code
* - If you isr code will use fpu registers, and this interrupt is nested.
* Then you can do it like this:
* \code
* void eclic_mtip_handler(void)
* {
* // !!!Interrupt is enabled here!!!
* // !!!Higher priority interrupt could nest it!!!
*
* // Necessary only when you need to use fpu registers
* // in this isr handler functions
* SAVE_FPU_CONTEXT();
*
* // put you own interrupt handling code here
*
* // pair of SAVE_FPU_CONTEXT()
* RESTORE_FPU_CONTEXT();
* }
* \endcode
*/
#define SAVE_FPU_CONTEXT() \
rv_fpu_t __fpu_context[20]; \
__RV_FSTORE(FREG(0), __fpu_context, 0 << LOG_FPREGBYTES); \
__RV_FSTORE(FREG(1), __fpu_context, 1 << LOG_FPREGBYTES); \
__RV_FSTORE(FREG(2), __fpu_context, 2 << LOG_FPREGBYTES); \
__RV_FSTORE(FREG(3), __fpu_context, 3 << LOG_FPREGBYTES); \
__RV_FSTORE(FREG(4), __fpu_context, 4 << LOG_FPREGBYTES); \
__RV_FSTORE(FREG(5), __fpu_context, 5 << LOG_FPREGBYTES); \
__RV_FSTORE(FREG(6), __fpu_context, 6 << LOG_FPREGBYTES); \
__RV_FSTORE(FREG(7), __fpu_context, 7 << LOG_FPREGBYTES); \
__RV_FSTORE(FREG(10), __fpu_context, 8 << LOG_FPREGBYTES); \
__RV_FSTORE(FREG(11), __fpu_context, 9 << LOG_FPREGBYTES); \
__RV_FSTORE(FREG(12), __fpu_context, 10 << LOG_FPREGBYTES); \
__RV_FSTORE(FREG(13), __fpu_context, 11 << LOG_FPREGBYTES); \
__RV_FSTORE(FREG(14), __fpu_context, 12 << LOG_FPREGBYTES); \
__RV_FSTORE(FREG(15), __fpu_context, 13 << LOG_FPREGBYTES); \
__RV_FSTORE(FREG(16), __fpu_context, 14 << LOG_FPREGBYTES); \
__RV_FSTORE(FREG(17), __fpu_context, 15 << LOG_FPREGBYTES); \
__RV_FSTORE(FREG(28), __fpu_context, 16 << LOG_FPREGBYTES); \
__RV_FSTORE(FREG(29), __fpu_context, 17 << LOG_FPREGBYTES); \
__RV_FSTORE(FREG(30), __fpu_context, 18 << LOG_FPREGBYTES); \
__RV_FSTORE(FREG(31), __fpu_context, 19 << LOG_FPREGBYTES);
/**
* \brief Restore necessary fpu registers from variables for interrupt nesting
* \details
* This macro is used restore necessary fpu registers from pre-defined variables
* in \ref SAVE_FPU_CONTEXT macro.
* \remarks
* - It need to be used together with \ref SAVE_FPU_CONTEXT
*/
#define RESTORE_FPU_CONTEXT() \
__RV_FLOAD(FREG(0), __fpu_context, 0 << LOG_FPREGBYTES); \
__RV_FLOAD(FREG(1), __fpu_context, 1 << LOG_FPREGBYTES); \
__RV_FLOAD(FREG(2), __fpu_context, 2 << LOG_FPREGBYTES); \
__RV_FLOAD(FREG(3), __fpu_context, 3 << LOG_FPREGBYTES); \
__RV_FLOAD(FREG(4), __fpu_context, 4 << LOG_FPREGBYTES); \
__RV_FLOAD(FREG(5), __fpu_context, 5 << LOG_FPREGBYTES); \
__RV_FLOAD(FREG(6), __fpu_context, 6 << LOG_FPREGBYTES); \
__RV_FLOAD(FREG(7), __fpu_context, 7 << LOG_FPREGBYTES); \
__RV_FLOAD(FREG(10), __fpu_context, 8 << LOG_FPREGBYTES); \
__RV_FLOAD(FREG(11), __fpu_context, 9 << LOG_FPREGBYTES); \
__RV_FLOAD(FREG(12), __fpu_context, 10 << LOG_FPREGBYTES); \
__RV_FLOAD(FREG(13), __fpu_context, 11 << LOG_FPREGBYTES); \
__RV_FLOAD(FREG(14), __fpu_context, 12 << LOG_FPREGBYTES); \
__RV_FLOAD(FREG(15), __fpu_context, 13 << LOG_FPREGBYTES); \
__RV_FLOAD(FREG(16), __fpu_context, 14 << LOG_FPREGBYTES); \
__RV_FLOAD(FREG(17), __fpu_context, 15 << LOG_FPREGBYTES); \
__RV_FLOAD(FREG(28), __fpu_context, 16 << LOG_FPREGBYTES); \
__RV_FLOAD(FREG(29), __fpu_context, 17 << LOG_FPREGBYTES); \
__RV_FLOAD(FREG(30), __fpu_context, 18 << LOG_FPREGBYTES); \
__RV_FLOAD(FREG(31), __fpu_context, 19 << LOG_FPREGBYTES);
#else
#define SAVE_FPU_CONTEXT()
#define RESTORE_FPU_CONTEXT()
#endif /* __FPU_PRESENT > 0 */
/** @} */ /* End of Doxygen Group NMSIS_Core_FPU_Functions */
#ifdef __cplusplus
}
#endif
#endif /** __RISCV_EXT_FPU_H__ */

View File

@@ -0,0 +1,260 @@
/*
* Copyright (c) 2019 Nuclei Limited. All rights reserved.
*
* SPDX-License-Identifier: Apache-2.0
*
* Licensed under the Apache License, Version 2.0 (the License); you may
* not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an AS IS BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*/
#ifndef __CORE_FEATURE_PMP_H__
#define __CORE_FEATURE_PMP_H__
/*!
* @file core_feature_pmp.h
* @brief PMP feature API header file for Nuclei N/NX Core
*/
/*
* PMP Feature Configuration Macro:
* 1. __PMP_PRESENT: Define whether Physical Memory Protection(PMP) is present or not
* * 0: Not present
* * 1: Present
* 2. __PMP_ENTRY_NUM: Define the number of PMP entries, only 8 or 16 is configurable.
*/
#ifdef __cplusplus
extern "C" {
#endif
#if defined(__PMP_PRESENT) && (__PMP_PRESENT == 1)
/* ===== PMP Operations ===== */
/**
* \defgroup NMSIS_Core_PMP_Functions PMP Functions
* \ingroup NMSIS_Core
* \brief Functions that related to the RISCV Phyiscal Memory Protection.
* \details
* Optional physical memory protection (PMP) unit provides per-hart machine-mode
* control registers to allow physical memory access privileges (read, write, execute)
* to be specified for each physical memory region.
*
* The PMP can supports region access control settings as small as four bytes.
*
* @{
*/
#ifndef __PMP_ENTRY_NUM
/* numbers of PMP entries(__PMP_ENTRY_NUM) should be defined in <Device.h> */
#error "__PMP_ENTRY_NUM is not defined, please check!"
#endif
/**
* \brief Get 8bit PMPxCFG Register by PMP entry index
* \details Return the content of the PMPxCFG Register.
* \param [in] idx PMP region index(0-15)
* \return PMPxCFG Register value
*/
__STATIC_INLINE uint8_t __get_PMPxCFG(uint32_t idx)
{
rv_csr_t pmpcfg = 0;
if (idx >= __PMP_ENTRY_NUM) return 0;
#if __RISCV_XLEN == 32
if (idx < 4) {
pmpcfg = __RV_CSR_READ(CSR_PMPCFG0);
} else if ((idx >=4) && (idx < 8)) {
idx -= 4;
pmpcfg = __RV_CSR_READ(CSR_PMPCFG1);
} else if ((idx >=8) && (idx < 12)) {
idx -= 8;
pmpcfg = __RV_CSR_READ(CSR_PMPCFG2);
} else {
idx -= 12;
pmpcfg = __RV_CSR_READ(CSR_PMPCFG3);
}
idx = idx << 3;
return (uint8_t)((pmpcfg>>idx) & 0xFF);
#elif __RISCV_XLEN == 64
if (idx < 8) {
pmpcfg = __RV_CSR_READ(CSR_PMPCFG0);
} else {
idx -= 8;
pmpcfg = __RV_CSR_READ(CSR_PMPCFG2);
}
idx = idx << 3;
return (uint8_t)((pmpcfg>>idx) & 0xFF);
#else
// TODO Add RV128 Handling
return 0;
#endif
}
/**
* \brief Set 8bit PMPxCFG by pmp entry index
* \details Set the given pmpxcfg value to the PMPxCFG Register.
* \param [in] idx PMPx region index(0-15)
* \param [in] pmpxcfg PMPxCFG register value to set
*/
__STATIC_INLINE void __set_PMPxCFG(uint32_t idx, uint8_t pmpxcfg)
{
rv_csr_t pmpcfgx = 0;
if (idx >= __PMP_ENTRY_NUM) return;
#if __RISCV_XLEN == 32
if (idx < 4) {
pmpcfgx = __RV_CSR_READ(CSR_PMPCFG0);
idx = idx << 3;
pmpcfgx = (pmpcfgx & ~(0xFFUL << idx)) | ((rv_csr_t)pmpxcfg << idx);
__RV_CSR_WRITE(CSR_PMPCFG0, pmpcfgx);
} else if ((idx >=4) && (idx < 8)) {
idx -= 4;
pmpcfgx = __RV_CSR_READ(CSR_PMPCFG1);
idx = idx << 3;
pmpcfgx = (pmpcfgx & ~(0xFFUL << idx)) | ((rv_csr_t)pmpxcfg << idx);
__RV_CSR_WRITE(CSR_PMPCFG1, pmpcfgx);
} else if ((idx >=8) && (idx < 12)) {
idx -= 8;
pmpcfgx = __RV_CSR_READ(CSR_PMPCFG2);
idx = idx << 3;
pmpcfgx = (pmpcfgx & ~(0xFFUL << idx)) | ((rv_csr_t)pmpxcfg << idx);
__RV_CSR_WRITE(CSR_PMPCFG2, pmpcfgx);
} else {
idx -= 12;
pmpcfgx = __RV_CSR_READ(CSR_PMPCFG3);
idx = idx << 3;
pmpcfgx = (pmpcfgx & ~(0xFFUL << idx)) | ((rv_csr_t)pmpxcfg << idx);
__RV_CSR_WRITE(CSR_PMPCFG3, pmpcfgx);
}
#elif __RISCV_XLEN == 64
if (idx < 8) {
pmpcfgx = __RV_CSR_READ(CSR_PMPCFG0);
idx = idx << 3;
pmpcfgx = (pmpcfgx & ~(0xFFULL << idx)) | ((rv_csr_t)pmpxcfg << idx);
__RV_CSR_WRITE(CSR_PMPCFG0, pmpcfgx);
} else {
idx -= 8;
pmpcfgx = __RV_CSR_READ(CSR_PMPCFG2);
idx = idx << 3;
pmpcfgx = (pmpcfgx & ~(0xFFULL << idx)) | ((rv_csr_t)pmpxcfg << idx);
__RV_CSR_WRITE(CSR_PMPCFG2, pmpcfgx);
}
#else
// TODO Add RV128 Handling
#endif
}
/**
* \brief Get PMPCFGx Register by index
* \details Return the content of the PMPCFGx Register.
* \param [in] idx PMPCFG CSR index(0-3)
* \return PMPCFGx Register value
* \remark
* - For RV64, only idx = 0 and idx = 2 is allowed.
* pmpcfg0 and pmpcfg2 hold the configurations
* for the 16 PMP entries, pmpcfg1 and pmpcfg3 are illegal
* - For RV32, pmpcfg0pmpcfg3, hold the configurations
* pmp0cfgpmp15cfg for the 16 PMP entries
*/
__STATIC_INLINE rv_csr_t __get_PMPCFGx(uint32_t idx)
{
switch (idx) {
case 0: return __RV_CSR_READ(CSR_PMPCFG0);
case 1: return __RV_CSR_READ(CSR_PMPCFG1);
case 2: return __RV_CSR_READ(CSR_PMPCFG2);
case 3: return __RV_CSR_READ(CSR_PMPCFG3);
default: return 0;
}
}
/**
* \brief Set PMPCFGx by index
* \details Write the given value to the PMPCFGx Register.
* \param [in] idx PMPCFG CSR index(0-3)
* \param [in] pmpcfg PMPCFGx Register value to set
* \remark
* - For RV64, only idx = 0 and idx = 2 is allowed.
* pmpcfg0 and pmpcfg2 hold the configurations
* for the 16 PMP entries, pmpcfg1 and pmpcfg3 are illegal
* - For RV32, pmpcfg0pmpcfg3, hold the configurations
* pmp0cfgpmp15cfg for the 16 PMP entries
*/
__STATIC_INLINE void __set_PMPCFGx(uint32_t idx, rv_csr_t pmpcfg)
{
switch (idx) {
case 0: __RV_CSR_WRITE(CSR_PMPCFG0, pmpcfg); break;
case 1: __RV_CSR_WRITE(CSR_PMPCFG1, pmpcfg); break;
case 2: __RV_CSR_WRITE(CSR_PMPCFG2, pmpcfg); break;
case 3: __RV_CSR_WRITE(CSR_PMPCFG3, pmpcfg); break;
default: return;
}
}
/**
* \brief Get PMPADDRx Register by index
* \details Return the content of the PMPADDRx Register.
* \param [in] idx PMP region index(0-15)
* \return PMPADDRx Register value
*/
__STATIC_INLINE rv_csr_t __get_PMPADDRx(uint32_t idx)
{
switch (idx) {
case 0: return __RV_CSR_READ(CSR_PMPADDR0);
case 1: return __RV_CSR_READ(CSR_PMPADDR1);
case 2: return __RV_CSR_READ(CSR_PMPADDR2);
case 3: return __RV_CSR_READ(CSR_PMPADDR3);
case 4: return __RV_CSR_READ(CSR_PMPADDR4);
case 5: return __RV_CSR_READ(CSR_PMPADDR5);
case 6: return __RV_CSR_READ(CSR_PMPADDR6);
case 7: return __RV_CSR_READ(CSR_PMPADDR7);
case 8: return __RV_CSR_READ(CSR_PMPADDR8);
case 9: return __RV_CSR_READ(CSR_PMPADDR9);
case 10: return __RV_CSR_READ(CSR_PMPADDR10);
case 11: return __RV_CSR_READ(CSR_PMPADDR11);
case 12: return __RV_CSR_READ(CSR_PMPADDR12);
case 13: return __RV_CSR_READ(CSR_PMPADDR13);
case 14: return __RV_CSR_READ(CSR_PMPADDR14);
case 15: return __RV_CSR_READ(CSR_PMPADDR15);
default: return 0;
}
}
/**
* \brief Set PMPADDRx by index
* \details Write the given value to the PMPADDRx Register.
* \param [in] idx PMP region index(0-15)
* \param [in] pmpaddr PMPADDRx Register value to set
*/
__STATIC_INLINE void __set_PMPADDRx(uint32_t idx, rv_csr_t pmpaddr)
{
switch (idx) {
case 0: __RV_CSR_WRITE(CSR_PMPADDR0, pmpaddr); break;
case 1: __RV_CSR_WRITE(CSR_PMPADDR1, pmpaddr); break;
case 2: __RV_CSR_WRITE(CSR_PMPADDR2, pmpaddr); break;
case 3: __RV_CSR_WRITE(CSR_PMPADDR3, pmpaddr); break;
case 4: __RV_CSR_WRITE(CSR_PMPADDR4, pmpaddr); break;
case 5: __RV_CSR_WRITE(CSR_PMPADDR5, pmpaddr); break;
case 6: __RV_CSR_WRITE(CSR_PMPADDR6, pmpaddr); break;
case 7: __RV_CSR_WRITE(CSR_PMPADDR7, pmpaddr); break;
case 8: __RV_CSR_WRITE(CSR_PMPADDR8, pmpaddr); break;
case 9: __RV_CSR_WRITE(CSR_PMPADDR9, pmpaddr); break;
case 10: __RV_CSR_WRITE(CSR_PMPADDR10, pmpaddr); break;
case 11: __RV_CSR_WRITE(CSR_PMPADDR11, pmpaddr); break;
case 12: __RV_CSR_WRITE(CSR_PMPADDR12, pmpaddr); break;
case 13: __RV_CSR_WRITE(CSR_PMPADDR13, pmpaddr); break;
case 14: __RV_CSR_WRITE(CSR_PMPADDR14, pmpaddr); break;
case 15: __RV_CSR_WRITE(CSR_PMPADDR15, pmpaddr); break;
default: return;
}
}
/** @} */ /* End of Doxygen Group NMSIS_Core_PMP_Functions */
#endif /* defined(__PMP_PRESENT) && (__PMP_PRESENT == 1) */
#ifdef __cplusplus
}
#endif
#endif /** __CORE_FEATURE_PMP_H__ */

View File

@@ -0,0 +1,364 @@
/*
* Copyright (c) 2019 Nuclei Limited. All rights reserved.
*
* SPDX-License-Identifier: Apache-2.0
*
* Licensed under the Apache License, Version 2.0 (the License); you may
* not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an AS IS BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*/
#ifndef __CORE_FEATURE_TIMER_H__
#define __CORE_FEATURE_TIMER_H__
/*!
* @file core_feature_timer.h
* @brief System Timer feature API header file for Nuclei N/NX Core
*/
/*
* System Timer Feature Configuration Macro:
* 1. __SYSTIMER_PRESENT: Define whether Private System Timer is present or not.
* * 0: Not present
* * 1: Present
* 2. __SYSTIMER_BASEADDR: Define the base address of the System Timer.
*/
#ifdef __cplusplus
extern "C" {
#endif
#if defined(__SYSTIMER_PRESENT) && (__SYSTIMER_PRESENT == 1)
/**
* \defgroup NMSIS_Core_SysTimer_Registers Register Define and Type Definitions Of System Timer
* \ingroup NMSIS_Core_Registers
* \brief Type definitions and defines for system timer registers.
*
* @{
*/
/**
* \brief Structure type to access the System Timer (SysTimer).
* \details
* Structure definition to access the system timer(SysTimer).
* \remarks
* - MSFTRST register is introduced in Nuclei N Core version 1.3(\ref __NUCLEI_N_REV >= 0x0103)
* - MSTOP register is renamed to MTIMECTL register in Nuclei N Core version 1.4(\ref __NUCLEI_N_REV >= 0x0104)
* - CMPCLREN and CLKSRC bit in MTIMECTL register is introduced in Nuclei N Core version 1.4(\ref __NUCLEI_N_REV >= 0x0104)
*/
typedef struct {
__IOM uint64_t MTIMER; /*!< Offset: 0x000 (R/W) System Timer current value 64bits Register */
__IOM uint64_t MTIMERCMP; /*!< Offset: 0x008 (R/W) System Timer compare Value 64bits Register */
__IOM uint32_t RESERVED0[0x3F8]; /*!< Offset: 0x010 - 0xFEC Reserved */
__IOM uint32_t MSFTRST; /*!< Offset: 0xFF0 (R/W) System Timer Software Core Reset Register */
__IOM uint32_t RESERVED1; /*!< Offset: 0xFF4 Reserved */
__IOM uint32_t MTIMECTL; /*!< Offset: 0xFF8 (R/W) System Timer Control Register, previously MSTOP register */
__IOM uint32_t MSIP; /*!< Offset: 0xFFC (R/W) System Timer SW interrupt Register */
} SysTimer_Type;
/* Timer Control / Status Register Definitions */
#define SysTimer_MTIMECTL_TIMESTOP_Pos 0U /*!< SysTick Timer MTIMECTL: TIMESTOP bit Position */
#define SysTimer_MTIMECTL_TIMESTOP_Msk (1UL << SysTimer_MTIMECTL_TIMESTOP_Pos) /*!< SysTick Timer MTIMECTL: TIMESTOP Mask */
#define SysTimer_MTIMECTL_CMPCLREN_Pos 1U /*!< SysTick Timer MTIMECTL: CMPCLREN bit Position */
#define SysTimer_MTIMECTL_CMPCLREN_Msk (1UL << SysTimer_MTIMECTL_CMPCLREN_Pos) /*!< SysTick Timer MTIMECTL: CMPCLREN Mask */
#define SysTimer_MTIMECTL_CLKSRC_Pos 2U /*!< SysTick Timer MTIMECTL: CLKSRC bit Position */
#define SysTimer_MTIMECTL_CLKSRC_Msk (1UL << SysTimer_MTIMECTL_CLKSRC_Pos) /*!< SysTick Timer MTIMECTL: CLKSRC Mask */
#define SysTimer_MSIP_MSIP_Pos 0U /*!< SysTick Timer MSIP: MSIP bit Position */
#define SysTimer_MSIP_MSIP_Msk (1UL << SysTimer_MSIP_MSIP_Pos) /*!< SysTick Timer MSIP: MSIP Mask */
#define SysTimer_MTIMER_Msk (0xFFFFFFFFFFFFFFFFULL) /*!< SysTick Timer MTIMER value Mask */
#define SysTimer_MTIMERCMP_Msk (0xFFFFFFFFFFFFFFFFULL) /*!< SysTick Timer MTIMERCMP value Mask */
#define SysTimer_MTIMECTL_Msk (0xFFFFFFFFUL) /*!< SysTick Timer MTIMECTL/MSTOP value Mask */
#define SysTimer_MSIP_Msk (0xFFFFFFFFUL) /*!< SysTick Timer MSIP value Mask */
#define SysTimer_MSFTRST_Msk (0xFFFFFFFFUL) /*!< SysTick Timer MSFTRST value Mask */
#define SysTimer_MSFRST_KEY (0x80000A5FUL) /*!< SysTick Timer Software Reset Request Key */
#ifndef __SYSTIMER_BASEADDR
/* Base address of SYSTIMER(__SYSTIMER_BASEADDR) should be defined in <Device.h> */
#error "__SYSTIMER_BASEADDR is not defined, please check!"
#endif
/* System Timer Memory mapping of Device */
#define SysTimer_BASE __SYSTIMER_BASEADDR /*!< SysTick Base Address */
#define SysTimer ((SysTimer_Type *) SysTimer_BASE) /*!< SysTick configuration struct */
/** @} */ /* end of group NMSIS_Core_SysTimer_Registers */
/* ################################## SysTimer function ############################################ */
/**
* \defgroup NMSIS_Core_SysTimer SysTimer Functions
* \brief Functions that configure the Core System Timer.
* @{
*/
/**
* \brief Set system timer load value
* \details
* This function set the system timer load value in MTIMER register.
* \param [in] value value to set system timer MTIMER register.
* \remarks
* - Load value is 64bits wide.
* - \ref SysTimer_GetLoadValue
*/
__STATIC_FORCEINLINE void SysTimer_SetLoadValue(uint64_t value)
{
SysTimer->MTIMER = value;
}
/**
* \brief Get system timer load value
* \details
* This function get the system timer current value in MTIMER register.
* \return current value(64bit) of system timer MTIMER register.
* \remarks
* - Load value is 64bits wide.
* - \ref SysTimer_SetLoadValue
*/
__STATIC_FORCEINLINE uint64_t SysTimer_GetLoadValue(void)
{
return SysTimer->MTIMER;
}
/**
* \brief Set system timer compare value
* \details
* This function set the system Timer compare value in MTIMERCMP register.
* \param [in] value compare value to set system timer MTIMERCMP register.
* \remarks
* - Compare value is 64bits wide.
* - If compare value is larger than current value timer interrupt generate.
* - Modify the load value or compare value less to clear the interrupt.
* - \ref SysTimer_GetCompareValue
*/
__STATIC_FORCEINLINE void SysTimer_SetCompareValue(uint64_t value)
{
SysTimer->MTIMERCMP = value;
}
/**
* \brief Get system timer compare value
* \details
* This function get the system timer compare value in MTIMERCMP register.
* \return compare value of system timer MTIMERCMP register.
* \remarks
* - Compare value is 64bits wide.
* - \ref SysTimer_SetCompareValue
*/
__STATIC_FORCEINLINE uint64_t SysTimer_GetCompareValue(void)
{
return SysTimer->MTIMERCMP;
}
/**
* \brief Enable system timer counter running
* \details
* Enable system timer counter running by clear
* TIMESTOP bit in MTIMECTL register.
*/
__STATIC_FORCEINLINE void SysTimer_Start(void)
{
SysTimer->MTIMECTL &= ~(SysTimer_MTIMECTL_TIMESTOP_Msk);
}
/**
* \brief Stop system timer counter running
* \details
* Stop system timer counter running by set
* TIMESTOP bit in MTIMECTL register.
*/
__STATIC_FORCEINLINE void SysTimer_Stop(void)
{
SysTimer->MTIMECTL |= SysTimer_MTIMECTL_TIMESTOP_Msk;
}
/**
* \brief Set system timer control value
* \details
* This function set the system timer MTIMECTL register value.
* \param [in] mctl value to set MTIMECTL register
* \remarks
* - Bit TIMESTOP is used to start and stop timer.
* Clear TIMESTOP bit to 0 to start timer, otherwise to stop timer.
* - Bit CMPCLREN is used to enable auto MTIMER clear to zero when MTIMER >= MTIMERCMP.
* Clear CMPCLREN bit to 0 to stop auto clear MTIMER feature, otherwise to enable it.
* - Bit CLKSRC is used to select timer clock source.
* Clear CLKSRC bit to 0 to use *mtime_toggle_a*, otherwise use *core_clk_aon*
* - \ref SysTimer_GetControlValue
*/
__STATIC_FORCEINLINE void SysTimer_SetControlValue(uint32_t mctl)
{
SysTimer->MTIMECTL = (mctl & SysTimer_MTIMECTL_Msk);
}
/**
* \brief Get system timer control value
* \details
* This function get the system timer MTIMECTL register value.
* \return MTIMECTL register value
* \remarks
* - \ref SysTimer_SetControlValue
*/
__STATIC_FORCEINLINE uint32_t SysTimer_GetControlValue(void)
{
return (SysTimer->MTIMECTL & SysTimer_MTIMECTL_Msk);
}
/**
* \brief Trigger or set software interrupt via system timer
* \details
* This function set the system timer MSIP bit in MSIP register.
* \remarks
* - Set system timer MSIP bit and generate a SW interrupt.
* - \ref SysTimer_ClearSWIRQ
* - \ref SysTimer_GetMsipValue
*/
__STATIC_FORCEINLINE void SysTimer_SetSWIRQ(void)
{
SysTimer->MSIP |= SysTimer_MSIP_MSIP_Msk;
}
/**
* \brief Clear system timer software interrupt pending request
* \details
* This function clear the system timer MSIP bit in MSIP register.
* \remarks
* - Clear system timer MSIP bit in MSIP register to clear the software interrupt pending.
* - \ref SysTimer_SetSWIRQ
* - \ref SysTimer_GetMsipValue
*/
__STATIC_FORCEINLINE void SysTimer_ClearSWIRQ(void)
{
SysTimer->MSIP &= ~SysTimer_MSIP_MSIP_Msk;
}
/**
* \brief Get system timer MSIP register value
* \details
* This function get the system timer MSIP register value.
* \return Value of Timer MSIP register.
* \remarks
* - Bit0 is SW interrupt flag.
* Bit0 is 1 then SW interrupt set. Bit0 is 0 then SW interrupt clear.
* - \ref SysTimer_SetSWIRQ
* - \ref SysTimer_ClearSWIRQ
*/
__STATIC_FORCEINLINE uint32_t SysTimer_GetMsipValue(void)
{
return (uint32_t)(SysTimer->MSIP & SysTimer_MSIP_Msk);
}
/**
* \brief Set system timer MSIP register value
* \details
* This function set the system timer MSIP register value.
* \param [in] msip value to set MSIP register
*/
__STATIC_FORCEINLINE void SysTimer_SetMsipValue(uint32_t msip)
{
SysTimer->MSIP = (msip & SysTimer_MSIP_Msk);
}
/**
* \brief Do software reset request
* \details
* This function will do software reset request through MTIMER
* - Software need to write \ref SysTimer_MSFRST_KEY to generate software reset request
* - The software request flag can be cleared by reset operation to clear
* \remarks
* - The software reset is sent to SoC, SoC need to generate reset signal and send back to Core
* - This function will not return, it will do while(1) to wait the Core reset happened
*/
__STATIC_FORCEINLINE void SysTimer_SoftwareReset(void)
{
SysTimer->MSFTRST = SysTimer_MSFRST_KEY;
while(1);
}
#if defined (__Vendor_SysTickConfig) && (__Vendor_SysTickConfig == 0U) && defined(__ECLIC_PRESENT) && (__ECLIC_PRESENT == 1)
/**
* \brief System Tick Configuration
* \details Initializes the System Timer and its non-vector interrupt, and starts the System Tick Timer.
*
* In our default implementation, the timer counter will be set to zero, and it will start a timer compare non-vector interrupt
* when it matchs the ticks user set, during the timer interrupt user should reload the system tick using \ref SysTick_Reload function
* or similar function written by user, so it can produce period timer interrupt.
* \param [in] ticks Number of ticks between two interrupts.
* \return 0 Function succeeded.
* \return 1 Function failed.
* \remarks
* - For \ref __NUCLEI_N_REV >= 0x0104, the CMPCLREN bit in MTIMECTL is introduced,
* but we assume that the CMPCLREN bit is set to 0, so MTIMER register will not be
* auto cleared to 0 when MTIMER >= MTIMERCMP.
* - When the variable \ref __Vendor_SysTickConfig is set to 1, then the
* function \ref SysTick_Config is not included.
* - In this case, the file <b><Device>.h</b> must contain a vendor-specific implementation
* of this function.
* - If user need this function to start a period timer interrupt, then in timer interrupt handler
* routine code, user should call \ref SysTick_Reload with ticks to reload the timer.
* - This function only available when __SYSTIMER_PRESENT == 1 and __ECLIC_PRESENT == 1 and __Vendor_SysTickConfig == 0
* \sa
* - \ref SysTimer_SetCompareValue; SysTimer_SetLoadValue
*/
__STATIC_INLINE uint32_t SysTick_Config(uint64_t ticks)
{
SysTimer_SetLoadValue(0);
SysTimer_SetCompareValue(ticks);
ECLIC_SetShvIRQ(SysTimer_IRQn, ECLIC_NON_VECTOR_INTERRUPT);
ECLIC_SetLevelIRQ(SysTimer_IRQn, 0);
ECLIC_EnableIRQ(SysTimer_IRQn);
return (0UL);
}
/**
* \brief System Tick Reload
* \details Reload the System Timer Tick when the MTIMECMP reached TIME value
*
* \param [in] ticks Number of ticks between two interrupts.
* \return 0 Function succeeded.
* \return 1 Function failed.
* \remarks
* - For \ref __NUCLEI_N_REV >= 0x0104, the CMPCLREN bit in MTIMECTL is introduced,
* but for this \ref SysTick_Config function, we assume this CMPCLREN bit is set to 0,
* so in interrupt handler function, user still need to set the MTIMERCMP or MTIMER to reload
* the system tick, if vendor want to use this timer's auto clear feature, they can define
* \ref __Vendor_SysTickConfig to 1, and implement \ref SysTick_Config and \ref SysTick_Reload functions.
* - When the variable \ref __Vendor_SysTickConfig is set to 1, then the
* function \ref SysTick_Reload is not included.
* - In this case, the file <b><Device>.h</b> must contain a vendor-specific implementation
* of this function.
* - This function only available when __SYSTIMER_PRESENT == 1 and __ECLIC_PRESENT == 1 and __Vendor_SysTickConfig == 0
* - Since the MTIMERCMP value might overflow, if overflowed, MTIMER will be set to 0, and MTIMERCMP set to ticks
* \sa
* - \ref SysTimer_SetCompareValue
* - \ref SysTimer_SetLoadValue
*/
__STATIC_FORCEINLINE uint32_t SysTick_Reload(uint64_t ticks)
{
uint64_t cur_ticks = SysTimer->MTIMER;
uint64_t reload_ticks = ticks + cur_ticks;
if (__USUALLY(reload_ticks > cur_ticks)) {
SysTimer->MTIMERCMP = reload_ticks;
} else {
/* When added the ticks value, then the MTIMERCMP < TIMER,
* which means the MTIMERCMP is overflowed,
* so we need to reset the counter to zero */
SysTimer->MTIMER = 0;
SysTimer->MTIMERCMP = ticks;
}
return (0UL);
}
#endif /* defined(__Vendor_SysTickConfig) && (__Vendor_SysTickConfig == 0U) */
/** @} */ /* End of Doxygen Group NMSIS_Core_SysTimer */
#endif /* defined(__SYSTIMER_PRESENT) && (__SYSTIMER_PRESENT == 1) */
#ifdef __cplusplus
}
#endif
#endif /** __CORE_FEATURE_TIMER_H__ */

View File

@@ -0,0 +1,37 @@
/*
* Copyright (c) 2019 Nuclei Limited. All rights reserved.
*
* SPDX-License-Identifier: Apache-2.0
*
* Licensed under the Apache License, Version 2.0 (the License); you may
* not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an AS IS BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*/
#ifndef __NMSIS_COMPILER_H
#define __NMSIS_COMPILER_H
#include <stdint.h>
/*!
* @file nmsis_compiler.h
* @brief NMSIS compiler generic header file
*/
#if defined ( __GNUC__ )
/** GNU GCC Compiler */
#include "nmsis_gcc.h"
#else
#error Unknown compiler.
#endif
#endif /* __NMSIS_COMPILER_H */

View File

@@ -0,0 +1,87 @@
/*
* Copyright (c) 2009-2019 Arm Limited. All rights reserved.
* -- Adaptable modifications made for Nuclei Processors. --
* Copyright (c) 2019 Nuclei Limited. All rights reserved.
*
* SPDX-License-Identifier: Apache-2.0
*
* Licensed under the Apache License, Version 2.0 (the License); you may
* not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an AS IS BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*/
#ifndef __NMSIS_CORE_H__
#define __NMSIS_CORE_H__
#include <stdint.h>
#ifdef __cplusplus
extern "C" {
#endif
#include "nmsis_version.h"
/**
* \ingroup NMSIS_Core_VersionControl
* @{
*/
/* The following enum __NUCLEI_N_REV/__NUCLEI_NX_REV definition in this file
* is only used for doxygen documentation generation,
* The <device>.h is the real file to define it by vendor
*/
#if defined(__ONLY_FOR_DOXYGEN_DOCUMENT_GENERATION__)
/**
* \brief Nuclei N class core revision number
* \details
* Reversion number format: [15:8] revision number, [7:0] patch number
* \attention
* This define is exclusive with \ref __NUCLEI_NX_REV
*/
#define __NUCLEI_N_REV (0x0104)
/**
* \brief Nuclei NX class core revision number
* \details
* Reversion number format: [15:8] revision number, [7:0] patch number
* \attention
* This define is exclusive with \ref __NUCLEI_N_REV
*/
#define __NUCLEI_NX_REV (0x0100)
#endif /* __ONLY_FOR_DOXYGEN_DOCUMENT_GENERATION__ */
/** @} */ /* End of Group NMSIS_Core_VersionControl */
#include "nmsis_compiler.h" /* NMSIS compiler specific defines */
/* === Include Nuclei Core Related Headers === */
/* Include core base feature header file */
#include "core_feature_base.h"
#ifndef __NMSIS_GENERIC
/* Include core eclic feature header file */
#include "core_feature_eclic.h"
/* Include core systimer feature header file */
#include "core_feature_timer.h"
#endif
/* Include core fpu feature header file */
#include "core_feature_fpu.h"
/* Include core dsp feature header file */
#include "core_feature_dsp.h"
/* Include core pmp feature header file */
#include "core_feature_pmp.h"
/* Include core cache feature header file */
#include "core_feature_cache.h"
/* Include compatiable functions header file */
#include "core_compatiable.h"
#ifdef __cplusplus
}
#endif
#endif /* __NMSIS_CORE_H__ */

View File

@@ -0,0 +1,269 @@
/*
* Copyright (c) 2019 Nuclei Limited. All rights reserved.
*
* SPDX-License-Identifier: Apache-2.0
*
* Licensed under the Apache License, Version 2.0 (the License); you may
* not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an AS IS BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*/
#ifndef __NMSIS_GCC_H__
#define __NMSIS_GCC_H__
/*!
* @file nmsis_gcc.h
* @brief NMSIS compiler GCC header file
*/
#include <stdint.h>
#include "riscv_encoding.h"
#ifdef __cplusplus
extern "C" {
#endif
/* ######################### Startup and Lowlevel Init ######################## */
/**
* \defgroup NMSIS_Core_CompilerControl Compiler Control
* \ingroup NMSIS_Core
* \brief Compiler agnostic \#define symbols for generic c/c++ source code
* \details
*
* The NMSIS-Core provides the header file <b>nmsis_compiler.h</b> with consistent \#define symbols for generate C or C++ source files that should be compiler agnostic.
* Each NMSIS compliant compiler should support the functionality described in this section.
*
* The header file <b>nmsis_compiler.h</b> is also included by each Device Header File <device.h> so that these definitions are available.
* @{
*/
/* ignore some GCC warnings */
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wsign-conversion"
#pragma GCC diagnostic ignored "-Wconversion"
#pragma GCC diagnostic ignored "-Wunused-parameter"
/* Fallback for __has_builtin */
#ifndef __has_builtin
#define __has_builtin(x) (0)
#endif
/* NMSIS compiler specific defines */
/** \brief Pass information from the compiler to the assembler. */
#ifndef __ASM
#define __ASM __asm
#endif
/** \brief Recommend that function should be inlined by the compiler. */
#ifndef __INLINE
#define __INLINE inline
#endif
/** \brief Define a static function that may be inlined by the compiler. */
#ifndef __STATIC_INLINE
#define __STATIC_INLINE static inline
#endif
/** \brief Define a static function that should be always inlined by the compiler. */
#ifndef __STATIC_FORCEINLINE
#define __STATIC_FORCEINLINE __attribute__((always_inline)) static inline
#endif
/** \brief Inform the compiler that a function does not return. */
#ifndef __NO_RETURN
#define __NO_RETURN __attribute__((__noreturn__))
#endif
/** \brief Inform that a variable shall be retained in executable image. */
#ifndef __USED
#define __USED __attribute__((used))
#endif
/** \brief restrict pointer qualifier to enable additional optimizations. */
#ifndef __WEAK
#define __WEAK __attribute__((weak))
#endif
/** \brief specified the vector size of the variable, measured in bytes */
#ifndef __VECTOR_SIZE
#define __VECTOR_SIZE(x) __attribute__((vector_size(x)))
#endif
/** \brief Request smallest possible alignment. */
#ifndef __PACKED
#define __PACKED __attribute__((packed, aligned(1)))
#endif
/** \brief Request smallest possible alignment for a structure. */
#ifndef __PACKED_STRUCT
#define __PACKED_STRUCT struct __attribute__((packed, aligned(1)))
#endif
/** \brief Request smallest possible alignment for a union. */
#ifndef __PACKED_UNION
#define __PACKED_UNION union __attribute__((packed, aligned(1)))
#endif
#ifndef __UNALIGNED_UINT16_WRITE
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wpacked"
#pragma GCC diagnostic ignored "-Wattributes"
/** \brief Packed struct for unaligned uint16_t write access */
__PACKED_STRUCT T_UINT16_WRITE
{
uint16_t v;
};
#pragma GCC diagnostic pop
/** \brief Pointer for unaligned write of a uint16_t variable. */
#define __UNALIGNED_UINT16_WRITE(addr, val) (void)((((struct T_UINT16_WRITE *)(void *)(addr))->v) = (val))
#endif
#ifndef __UNALIGNED_UINT16_READ
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wpacked"
#pragma GCC diagnostic ignored "-Wattributes"
/** \brief Packed struct for unaligned uint16_t read access */
__PACKED_STRUCT T_UINT16_READ
{
uint16_t v;
};
#pragma GCC diagnostic pop
/** \brief Pointer for unaligned read of a uint16_t variable. */
#define __UNALIGNED_UINT16_READ(addr) (((const struct T_UINT16_READ *)(const void *)(addr))->v)
#endif
#ifndef __UNALIGNED_UINT32_WRITE
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wpacked"
#pragma GCC diagnostic ignored "-Wattributes"
/** \brief Packed struct for unaligned uint32_t write access */
__PACKED_STRUCT T_UINT32_WRITE
{
uint32_t v;
};
#pragma GCC diagnostic pop
/** \brief Pointer for unaligned write of a uint32_t variable. */
#define __UNALIGNED_UINT32_WRITE(addr, val) (void)((((struct T_UINT32_WRITE *)(void *)(addr))->v) = (val))
#endif
#ifndef __UNALIGNED_UINT32_READ
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wpacked"
#pragma GCC diagnostic ignored "-Wattributes"
/** \brief Packed struct for unaligned uint32_t read access */
__PACKED_STRUCT T_UINT32_READ
{
uint32_t v;
};
#pragma GCC diagnostic pop
/** \brief Pointer for unaligned read of a uint32_t variable. */
#define __UNALIGNED_UINT32_READ(addr) (((const struct T_UINT32_READ *)(const void *)(addr))->v)
#endif
/** \brief Minimum `x` bytes alignment for a variable. */
#ifndef __ALIGNED
#define __ALIGNED(x) __attribute__((aligned(x)))
#endif
/** \brief restrict pointer qualifier to enable additional optimizations. */
#ifndef __RESTRICT
#define __RESTRICT __restrict
#endif
/** \brief Barrier to prevent compiler from reordering instructions. */
#ifndef __COMPILER_BARRIER
#define __COMPILER_BARRIER() __ASM volatile("" :: \
: "memory")
#endif
/** \brief provide the compiler with branch prediction information, the branch is usually true */
#ifndef __USUALLY
#define __USUALLY(exp) __builtin_expect((exp), 1)
#endif
/** \brief provide the compiler with branch prediction information, the branch is rarely true */
#ifndef __RARELY
#define __RARELY(exp) __builtin_expect((exp), 0)
#endif
/** \brief Use this attribute to indicate that the specified function is an interrupt handler. */
#ifndef __INTERRUPT
#define __INTERRUPT __attribute__((interrupt))
#endif
/** @} */ /* End of Doxygen Group NMSIS_Core_CompilerControl */
/* IO definitions (access restrictions to peripheral registers) */
/**
* \defgroup NMSIS_Core_PeriphAccess Peripheral Access
* \brief Naming conventions and optional features for accessing peripherals.
*
* The section below describes the naming conventions, requirements, and optional features
* for accessing device specific peripherals.
* Most of the rules also apply to the core peripherals.
*
* The **Device Header File <device.h>** contains typically these definition
* and also includes the core specific header files.
*
* @{
*/
/** \brief Defines 'read only' permissions */
#ifdef __cplusplus
#define __I volatile
#else
#define __I volatile const
#endif
/** \brief Defines 'write only' permissions */
#define __O volatile
/** \brief Defines 'read / write' permissions */
#define __IO volatile
/* following defines should be used for structure members */
/** \brief Defines 'read only' structure member permissions */
#define __IM volatile const
/** \brief Defines 'write only' structure member permissions */
#define __OM volatile
/** \brief Defines 'read/write' structure member permissions */
#define __IOM volatile
/**
* \brief Mask and shift a bit field value for use in a register bit range.
* \details The macro \ref _VAL2FLD uses the #define's _Pos and _Msk of the related bit
* field to shift bit-field values for assigning to a register.
*
* **Example**:
* \code
* ECLIC->CFG = _VAL2FLD(CLIC_CLICCFG_NLBIT, 3);
* \endcode
* \param[in] field Name of the register bit field.
* \param[in] value Value of the bit field. This parameter is interpreted as an uint32_t type.
* \return Masked and shifted value.
*/
#define _VAL2FLD(field, value) (((uint32_t)(value) << field##_Pos) & field##_Msk)
/**
* \brief Mask and shift a register value to extract a bit filed value.
* \details The macro \ref _FLD2VAL uses the #define's _Pos and _Msk of the related bit
* field to extract the value of a bit field from a register.
*
* **Example**:
* \code
* nlbits = _FLD2VAL(CLIC_CLICCFG_NLBIT, ECLIC->CFG);
* \endcode
* \param[in] field Name of the register bit field.
* \param[in] value Value of register. This parameter is interpreted as an uint32_t type.
* \return Masked and shifted bit field value.
*/
#define _FLD2VAL(field, value) (((uint32_t)(value)&field##_Msk) >> field##_Pos)
/** @} */ /* end of group NMSIS_Core_PeriphAccess */
#ifdef __cplusplus
}
#endif
#endif /* __NMSIS_GCC_H__ */

View File

@@ -0,0 +1,87 @@
/*
* Copyright (c) 2019 Nuclei Limited. All rights reserved.
*
* SPDX-License-Identifier: Apache-2.0
*
* Licensed under the Apache License, Version 2.0 (the License); you may
* not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an AS IS BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*/
#ifndef __NMSIS_VERSION_H
#define __NMSIS_VERSION_H
/**
* \defgroup NMSIS_Core_VersionControl Version Control
* \ingroup NMSIS_Core
* \brief Version \#define symbols for NMSIS release specific C/C++ source code
* \details
*
* We followed the [semantic versioning 2.0.0](https://semver.org/) to control NMSIS version.
* The version format is **MAJOR.MINOR.PATCH**, increment the:
* 1. MAJOR version when you make incompatible API changes,
* 2. MINOR version when you add functionality in a backwards compatible manner, and
* 3. PATCH version when you make backwards compatible bug fixes.
*
* The header file `nmsis_version.h` is included by each core header so that these definitions are available.
*
* **Example Usage for NMSIS Version Check**:
* \code
* #if defined(__NMSIS_VERSION) && (__NMSIS_VERSION >= 0x00010105)
* #warning "Yes, we have NMSIS 1.1.5 or later"
* #else
* #error "We need NMSIS 1.1.5 or later!"
* #endif
* \endcode
*
* @{
*/
/*!
* \file nmsis_version.h
* \brief NMSIS Version definitions
**/
/**
* \brief Represent the NMSIS major version
* \details
* The NMSIS major version can be used to
* differentiate between NMSIS major releases.
* */
#define __NMSIS_VERSION_MAJOR (1U)
/**
* \brief Represent the NMSIS minor version
* \details
* The NMSIS minor version can be used to
* query a NMSIS release update including new features.
*
**/
#define __NMSIS_VERSION_MINOR (0U)
/**
* \brief Represent the NMSIS patch version
* \details
* The NMSIS patch version can be used to
* show bug fixes in this package.
**/
#define __NMSIS_VERSION_PATCH (1U)
/**
* \brief Represent the NMSIS Version
* \details
* NMSIS Version format: **MAJOR.MINOR.PATCH**
* * MAJOR: \ref __NMSIS_VERSION_MAJOR, stored in `bits [31:16]` of \ref __NMSIS_VERSION
* * MINOR: \ref __NMSIS_VERSION_MINOR, stored in `bits [15:8]` of \ref __NMSIS_VERSION
* * PATCH: \ref __NMSIS_VERSION_PATCH, stored in `bits [7:0]` of \ref __NMSIS_VERSION
**/
#define __NMSIS_VERSION ((__NMSIS_VERSION_MAJOR << 16U) | (__NMSIS_VERSION_MINOR << 8) | __NMSIS_VERSION_PATCH)
/** @} */ /* End of Doxygen Group NMSIS_Core_VersionControl */
#endif

View File

@@ -0,0 +1,94 @@
/*
* Copyright (c) 2019 Nuclei Limited. All rights reserved.
*
* SPDX-License-Identifier: Apache-2.0
*
* Licensed under the Apache License, Version 2.0 (the License); you may
* not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an AS IS BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*/
#ifndef __RISCV_BITS_H__
#define __RISCV_BITS_H__
#ifdef __cplusplus
extern "C" {
#endif
#if __riscv_xlen == 64
# define SLL32 sllw
# define STORE sd
# define LOAD ld
# define LWU lwu
# define LOG_REGBYTES 3
#else
# define SLL32 sll
# define STORE sw
# define LOAD lw
# define LWU lw
# define LOG_REGBYTES 2
#endif /* __riscv_xlen */
#define REGBYTES (1 << LOG_REGBYTES)
#if defined(__riscv_flen)
#if __riscv_flen == 64
# define FPSTORE fsd
# define FPLOAD fld
# define LOG_FPREGBYTES 3
#else
# define FPSTORE fsw
# define FPLOAD flw
# define LOG_FPREGBYTES 2
#endif /* __riscv_flen == 64 */
#define FPREGBYTES (1 << LOG_FPREGBYTES)
#endif /* __riscv_flen */
#define __rv_likely(x) __builtin_expect((x), 1)
#define __rv_unlikely(x) __builtin_expect((x), 0)
#define __RV_ROUNDUP(a, b) ((((a)-1)/(b)+1)*(b))
#define __RV_ROUNDDOWN(a, b) ((a)/(b)*(b))
#define __RV_MAX(a, b) ((a) > (b) ? (a) : (b))
#define __RV_MIN(a, b) ((a) < (b) ? (a) : (b))
#define __RV_CLAMP(a, lo, hi) MIN(MAX(a, lo), hi)
#define __RV_EXTRACT_FIELD(val, which) (((val) & (which)) / ((which) & ~((which)-1)))
#define __RV_INSERT_FIELD(val, which, fieldval) (((val) & ~(which)) | ((fieldval) * ((which) & ~((which)-1))))
#ifdef __ASSEMBLY__
#define _AC(X,Y) X
#define _AT(T,X) X
#else
#define __AC(X,Y) (X##Y)
#define _AC(X,Y) __AC(X,Y)
#define _AT(T,X) ((T)(X))
#endif /* __ASSEMBLY__ */
#define _UL(x) (_AC(x, UL))
#define _ULL(x) (_AC(x, ULL))
#define _BITUL(x) (_UL(1) << (x))
#define _BITULL(x) (_ULL(1) << (x))
#define UL(x) (_UL(x))
#define ULL(x) (_ULL(x))
#define STR(x) XSTR(x)
#define XSTR(x) #x
#define __STR(s) #s
#define STRINGIFY(s) __STR(s)
#ifdef __cplusplus
}
#endif
#endif /** __RISCV_BITS_H__ */

View File

@@ -0,0 +1,690 @@
/*
* Copyright (c) 2019 Nuclei Limited. All rights reserved.
*
* SPDX-License-Identifier: Apache-2.0
*
* Licensed under the Apache License, Version 2.0 (the License); you may
* not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an AS IS BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*/
#ifndef __RISCV_ENCODING_H__
#define __RISCV_ENCODING_H__
#include "riscv_bits.h"
#ifdef __cplusplus
extern "C" {
#endif
/**
* \defgroup NMSIS_Core_CSR_Encoding Core CSR Encodings
* \ingroup NMSIS_Core
* \brief NMSIS Core CSR Encodings
* \details
*
* The following macros are used for CSR encodings
* @{
*/
/* === Standard CSR bit mask === */
#define MSTATUS_UIE 0x00000001
#define MSTATUS_SIE 0x00000002
#define MSTATUS_HIE 0x00000004
#define MSTATUS_MIE 0x00000008
#define MSTATUS_UPIE 0x00000010
#define MSTATUS_SPIE 0x00000020
#define MSTATUS_HPIE 0x00000040
#define MSTATUS_MPIE 0x00000080
#define MSTATUS_SPP 0x00000100
#define MSTATUS_MPP 0x00001800
#define MSTATUS_FS 0x00006000
#define MSTATUS_XS 0x00018000
#define MSTATUS_MPRV 0x00020000
#define MSTATUS_PUM 0x00040000
#define MSTATUS_MXR 0x00080000
#define MSTATUS_VM 0x1F000000
#define MSTATUS32_SD 0x80000000
#define MSTATUS64_SD 0x8000000000000000
#define MSTATUS_FS_INITIAL 0x00002000
#define MSTATUS_FS_CLEAN 0x00004000
#define MSTATUS_FS_DIRTY 0x00006000
#define SSTATUS_UIE 0x00000001
#define SSTATUS_SIE 0x00000002
#define SSTATUS_UPIE 0x00000010
#define SSTATUS_SPIE 0x00000020
#define SSTATUS_SPP 0x00000100
#define SSTATUS_FS 0x00006000
#define SSTATUS_XS 0x00018000
#define SSTATUS_PUM 0x00040000
#define SSTATUS32_SD 0x80000000
#define SSTATUS64_SD 0x8000000000000000
#define CSR_MCACHE_CTL_IE 0x00000001
#define CSR_MCACHE_CTL_DE 0x00010000
#define DCSR_XDEBUGVER (3U<<30)
#define DCSR_NDRESET (1<<29)
#define DCSR_FULLRESET (1<<28)
#define DCSR_EBREAKM (1<<15)
#define DCSR_EBREAKH (1<<14)
#define DCSR_EBREAKS (1<<13)
#define DCSR_EBREAKU (1<<12)
#define DCSR_STOPCYCLE (1<<10)
#define DCSR_STOPTIME (1<<9)
#define DCSR_CAUSE (7<<6)
#define DCSR_DEBUGINT (1<<5)
#define DCSR_HALT (1<<3)
#define DCSR_STEP (1<<2)
#define DCSR_PRV (3<<0)
#define DCSR_CAUSE_NONE 0
#define DCSR_CAUSE_SWBP 1
#define DCSR_CAUSE_HWBP 2
#define DCSR_CAUSE_DEBUGINT 3
#define DCSR_CAUSE_STEP 4
#define DCSR_CAUSE_HALT 5
#define MCONTROL_TYPE(xlen) (0xfULL<<((xlen)-4))
#define MCONTROL_DMODE(xlen) (1ULL<<((xlen)-5))
#define MCONTROL_MASKMAX(xlen) (0x3fULL<<((xlen)-11))
#define MCONTROL_SELECT (1<<19)
#define MCONTROL_TIMING (1<<18)
#define MCONTROL_ACTION (0x3f<<12)
#define MCONTROL_CHAIN (1<<11)
#define MCONTROL_MATCH (0xf<<7)
#define MCONTROL_M (1<<6)
#define MCONTROL_H (1<<5)
#define MCONTROL_S (1<<4)
#define MCONTROL_U (1<<3)
#define MCONTROL_EXECUTE (1<<2)
#define MCONTROL_STORE (1<<1)
#define MCONTROL_LOAD (1<<0)
#define MCONTROL_TYPE_NONE 0
#define MCONTROL_TYPE_MATCH 2
#define MCONTROL_ACTION_DEBUG_EXCEPTION 0
#define MCONTROL_ACTION_DEBUG_MODE 1
#define MCONTROL_ACTION_TRACE_START 2
#define MCONTROL_ACTION_TRACE_STOP 3
#define MCONTROL_ACTION_TRACE_EMIT 4
#define MCONTROL_MATCH_EQUAL 0
#define MCONTROL_MATCH_NAPOT 1
#define MCONTROL_MATCH_GE 2
#define MCONTROL_MATCH_LT 3
#define MCONTROL_MATCH_MASK_LOW 4
#define MCONTROL_MATCH_MASK_HIGH 5
#define MIP_SSIP (1 << IRQ_S_SOFT)
#define MIP_HSIP (1 << IRQ_H_SOFT)
#define MIP_MSIP (1 << IRQ_M_SOFT)
#define MIP_STIP (1 << IRQ_S_TIMER)
#define MIP_HTIP (1 << IRQ_H_TIMER)
#define MIP_MTIP (1 << IRQ_M_TIMER)
#define MIP_SEIP (1 << IRQ_S_EXT)
#define MIP_HEIP (1 << IRQ_H_EXT)
#define MIP_MEIP (1 << IRQ_M_EXT)
#define MIE_SSIE MIP_SSIP
#define MIE_HSIE MIP_HSIP
#define MIE_MSIE MIP_MSIP
#define MIE_STIE MIP_STIP
#define MIE_HTIE MIP_HTIP
#define MIE_MTIE MIP_MTIP
#define MIE_SEIE MIP_SEIP
#define MIE_HEIE MIP_HEIP
#define MIE_MEIE MIP_MEIP
/* === P-ext CSR bit mask === */
#define UCODE_OV (0x1)
/* === Nuclei custom CSR bit mask === */
#define WFE_WFE (0x1)
#define TXEVT_TXEVT (0x1)
#define SLEEPVALUE_SLEEPVALUE (0x1)
#define MCOUNTINHIBIT_IR (1<<2)
#define MCOUNTINHIBIT_CY (1<<0)
#define MILM_CTL_ILM_BPA (((1ULL<<((__riscv_xlen)-10))-1)<<10)
#define MILM_CTL_ILM_RWECC (1<<3)
#define MILM_CTL_ILM_ECC_EXCP_EN (1<<2)
#define MILM_CTL_ILM_ECC_EN (1<<1)
#define MILM_CTL_ILM_EN (1<<0)
#define MDLM_CTL_DLM_BPA (((1ULL<<((__riscv_xlen)-10))-1)<<10)
#define MDLM_CTL_DLM_RWECC (1<<3)
#define MDLM_CTL_DLM_ECC_EXCP_EN (1<<2)
#define MDLM_CTL_DLM_ECC_EN (1<<1)
#define MDLM_CTL_DLM_EN (1<<0)
#define MSUBM_PTYP (0x3<<8)
#define MSUBM_TYP (0x3<<6)
#define MDCAUSE_MDCAUSE (0x3)
#define MMISC_CTL_NMI_CAUSE_FFF (1<<9)
#define MMISC_CTL_MISALIGN (1<<6)
#define MMISC_CTL_BPU (1<<3)
#define MCACHE_CTL_IC_EN (1<<0)
#define MCACHE_CTL_IC_SCPD_MOD (1<<1)
#define MCACHE_CTL_IC_ECC_EN (1<<2)
#define MCACHE_CTL_IC_ECC_EXCP_EN (1<<3)
#define MCACHE_CTL_IC_RWTECC (1<<4)
#define MCACHE_CTL_IC_RWDECC (1<<5)
#define MCACHE_CTL_DC_EN (1<<16)
#define MCACHE_CTL_DC_ECC_EN (1<<17)
#define MCACHE_CTL_DC_ECC_EXCP_EN (1<<18)
#define MCACHE_CTL_DC_RWTECC (1<<19)
#define MCACHE_CTL_DC_RWDECC (1<<20)
#define MTVT2_MTVT2EN (1<<0)
#define MTVT2_COMMON_CODE_ENTRY (((1ULL<<((__riscv_xlen)-2))-1)<<2)
#define MCFG_INFO_TEE (1<<0)
#define MCFG_INFO_ECC (1<<1)
#define MCFG_INFO_CLIC (1<<2)
#define MCFG_INFO_PLIC (1<<3)
#define MCFG_INFO_FIO (1<<4)
#define MCFG_INFO_PPI (1<<5)
#define MCFG_INFO_NICE (1<<6)
#define MCFG_INFO_ILM (1<<7)
#define MCFG_INFO_DLM (1<<8)
#define MCFG_INFO_ICACHE (1<<9)
#define MCFG_INFO_DCACHE (1<<10)
#define MICFG_IC_SET (0xF<<0)
#define MICFG_IC_WAY (0x7<<4)
#define MICFG_IC_LSIZE (0x7<<7)
#define MICFG_IC_ECC (0x1<<10)
#define MICFG_ILM_SIZE (0x1F<<16)
#define MICFG_ILM_XONLY (0x1<<21)
#define MICFG_ILM_ECC (0x1<<22)
#define MDCFG_DC_SET (0xF<<0)
#define MDCFG_DC_WAY (0x7<<4)
#define MDCFG_DC_LSIZE (0x7<<7)
#define MDCFG_DC_ECC (0x1<<10)
#define MDCFG_DLM_SIZE (0x1F<<16)
#define MDCFG_DLM_ECC (0x1<<21)
#define MPPICFG_INFO_PPI_SIZE (0x1F<<1)
#define MPPICFG_INFO_PPI_BPA (((1ULL<<((__riscv_xlen)-10))-1)<<10)
#define MFIOCFG_INFO_FIO_SIZE (0x1F<<1)
#define MFIOCFG_INFO_FIO_BPA (((1ULL<<((__riscv_xlen)-10))-1)<<10)
#define MECC_LOCK_ECC_LOCK (0x1)
#define MECC_CODE_CODE (0x1FF)
#define MECC_CODE_RAMID (0x1F<<16)
#define MECC_CODE_SRAMID (0x1F<<24)
#define CCM_SUEN_SUEN (0x1<<0)
#define CCM_DATA_DATA (0x7<<0)
#define CCM_COMMAND_COMMAND (0x1F<<0)
#define SIP_SSIP MIP_SSIP
#define SIP_STIP MIP_STIP
#define PRV_U 0
#define PRV_S 1
#define PRV_H 2
#define PRV_M 3
#define VM_MBARE 0
#define VM_MBB 1
#define VM_MBBID 2
#define VM_SV32 8
#define VM_SV39 9
#define VM_SV48 10
#define IRQ_S_SOFT 1
#define IRQ_H_SOFT 2
#define IRQ_M_SOFT 3
#define IRQ_S_TIMER 5
#define IRQ_H_TIMER 6
#define IRQ_M_TIMER 7
#define IRQ_S_EXT 9
#define IRQ_H_EXT 10
#define IRQ_M_EXT 11
#define IRQ_COP 12
#define IRQ_HOST 13
/* === FPU FRM Rounding Mode === */
/** FPU Round to Nearest, ties to Even*/
#define FRM_RNDMODE_RNE 0x0
/** FPU Round Towards Zero */
#define FRM_RNDMODE_RTZ 0x1
/** FPU Round Down (towards -inf) */
#define FRM_RNDMODE_RDN 0x2
/** FPU Round Up (towards +inf) */
#define FRM_RNDMODE_RUP 0x3
/** FPU Round to nearest, ties to Max Magnitude */
#define FRM_RNDMODE_RMM 0x4
/**
* In instruction's rm, selects dynamic rounding mode.
* In Rounding Mode register, Invalid */
#define FRM_RNDMODE_DYN 0x7
/* === FPU FFLAGS Accrued Exceptions === */
/** FPU Inexact */
#define FFLAGS_AE_NX (1<<0)
/** FPU Underflow */
#define FFLAGS_AE_UF (1<<1)
/** FPU Overflow */
#define FFLAGS_AE_OF (1<<2)
/** FPU Divide by Zero */
#define FFLAGS_AE_DZ (1<<3)
/** FPU Invalid Operation */
#define FFLAGS_AE_NV (1<<4)
/** Floating Point Register f0-f31, eg. f0 -> FREG(0) */
#define FREG(idx) f##idx
/* === PMP CFG Bits === */
#define PMP_R 0x01
#define PMP_W 0x02
#define PMP_X 0x04
#define PMP_A 0x18
#define PMP_A_TOR 0x08
#define PMP_A_NA4 0x10
#define PMP_A_NAPOT 0x18
#define PMP_L 0x80
#define PMP_SHIFT 2
#define PMP_COUNT 16
// page table entry (PTE) fields
#define PTE_V 0x001 // Valid
#define PTE_R 0x002 // Read
#define PTE_W 0x004 // Write
#define PTE_X 0x008 // Execute
#define PTE_U 0x010 // User
#define PTE_G 0x020 // Global
#define PTE_A 0x040 // Accessed
#define PTE_D 0x080 // Dirty
#define PTE_SOFT 0x300 // Reserved for Software
#define PTE_PPN_SHIFT 10
#define PTE_TABLE(PTE) (((PTE) & (PTE_V | PTE_R | PTE_W | PTE_X)) == PTE_V)
#ifdef __riscv
#ifdef __riscv64
# define MSTATUS_SD MSTATUS64_SD
# define SSTATUS_SD SSTATUS64_SD
# define RISCV_PGLEVEL_BITS 9
#else
# define MSTATUS_SD MSTATUS32_SD
# define SSTATUS_SD SSTATUS32_SD
# define RISCV_PGLEVEL_BITS 10
#endif /* __riscv64 */
#define RISCV_PGSHIFT 12
#define RISCV_PGSIZE (1 << RISCV_PGSHIFT)
#endif /* __riscv */
/**
* \defgroup NMSIS_Core_CSR_Registers Core CSR Registers
* \ingroup NMSIS_Core
* \brief NMSIS Core CSR Register Definitions
* \details
*
* The following macros are used for CSR Register Defintions.
* @{
*/
/* === Standard RISC-V CSR Registers === */
#define CSR_USTATUS 0x0
#define CSR_FFLAGS 0x1
#define CSR_FRM 0x2
#define CSR_FCSR 0x3
#define CSR_CYCLE 0xc00
#define CSR_TIME 0xc01
#define CSR_INSTRET 0xc02
#define CSR_HPMCOUNTER3 0xc03
#define CSR_HPMCOUNTER4 0xc04
#define CSR_HPMCOUNTER5 0xc05
#define CSR_HPMCOUNTER6 0xc06
#define CSR_HPMCOUNTER7 0xc07
#define CSR_HPMCOUNTER8 0xc08
#define CSR_HPMCOUNTER9 0xc09
#define CSR_HPMCOUNTER10 0xc0a
#define CSR_HPMCOUNTER11 0xc0b
#define CSR_HPMCOUNTER12 0xc0c
#define CSR_HPMCOUNTER13 0xc0d
#define CSR_HPMCOUNTER14 0xc0e
#define CSR_HPMCOUNTER15 0xc0f
#define CSR_HPMCOUNTER16 0xc10
#define CSR_HPMCOUNTER17 0xc11
#define CSR_HPMCOUNTER18 0xc12
#define CSR_HPMCOUNTER19 0xc13
#define CSR_HPMCOUNTER20 0xc14
#define CSR_HPMCOUNTER21 0xc15
#define CSR_HPMCOUNTER22 0xc16
#define CSR_HPMCOUNTER23 0xc17
#define CSR_HPMCOUNTER24 0xc18
#define CSR_HPMCOUNTER25 0xc19
#define CSR_HPMCOUNTER26 0xc1a
#define CSR_HPMCOUNTER27 0xc1b
#define CSR_HPMCOUNTER28 0xc1c
#define CSR_HPMCOUNTER29 0xc1d
#define CSR_HPMCOUNTER30 0xc1e
#define CSR_HPMCOUNTER31 0xc1f
#define CSR_SSTATUS 0x100
#define CSR_SIE 0x104
#define CSR_STVEC 0x105
#define CSR_SSCRATCH 0x140
#define CSR_SEPC 0x141
#define CSR_SCAUSE 0x142
#define CSR_SBADADDR 0x143
#define CSR_SIP 0x144
#define CSR_SPTBR 0x180
#define CSR_MSTATUS 0x300
#define CSR_MISA 0x301
#define CSR_MEDELEG 0x302
#define CSR_MIDELEG 0x303
#define CSR_MIE 0x304
#define CSR_MTVEC 0x305
#define CSR_MCOUNTEREN 0x306
#define CSR_MSCRATCH 0x340
#define CSR_MEPC 0x341
#define CSR_MCAUSE 0x342
#define CSR_MBADADDR 0x343
#define CSR_MTVAL 0x343
#define CSR_MIP 0x344
#define CSR_PMPCFG0 0x3a0
#define CSR_PMPCFG1 0x3a1
#define CSR_PMPCFG2 0x3a2
#define CSR_PMPCFG3 0x3a3
#define CSR_PMPADDR0 0x3b0
#define CSR_PMPADDR1 0x3b1
#define CSR_PMPADDR2 0x3b2
#define CSR_PMPADDR3 0x3b3
#define CSR_PMPADDR4 0x3b4
#define CSR_PMPADDR5 0x3b5
#define CSR_PMPADDR6 0x3b6
#define CSR_PMPADDR7 0x3b7
#define CSR_PMPADDR8 0x3b8
#define CSR_PMPADDR9 0x3b9
#define CSR_PMPADDR10 0x3ba
#define CSR_PMPADDR11 0x3bb
#define CSR_PMPADDR12 0x3bc
#define CSR_PMPADDR13 0x3bd
#define CSR_PMPADDR14 0x3be
#define CSR_PMPADDR15 0x3bf
#define CSR_TSELECT 0x7a0
#define CSR_TDATA1 0x7a1
#define CSR_TDATA2 0x7a2
#define CSR_TDATA3 0x7a3
#define CSR_DCSR 0x7b0
#define CSR_DPC 0x7b1
#define CSR_DSCRATCH 0x7b2
#define CSR_MCYCLE 0xb00
#define CSR_MINSTRET 0xb02
#define CSR_MHPMCOUNTER3 0xb03
#define CSR_MHPMCOUNTER4 0xb04
#define CSR_MHPMCOUNTER5 0xb05
#define CSR_MHPMCOUNTER6 0xb06
#define CSR_MHPMCOUNTER7 0xb07
#define CSR_MHPMCOUNTER8 0xb08
#define CSR_MHPMCOUNTER9 0xb09
#define CSR_MHPMCOUNTER10 0xb0a
#define CSR_MHPMCOUNTER11 0xb0b
#define CSR_MHPMCOUNTER12 0xb0c
#define CSR_MHPMCOUNTER13 0xb0d
#define CSR_MHPMCOUNTER14 0xb0e
#define CSR_MHPMCOUNTER15 0xb0f
#define CSR_MHPMCOUNTER16 0xb10
#define CSR_MHPMCOUNTER17 0xb11
#define CSR_MHPMCOUNTER18 0xb12
#define CSR_MHPMCOUNTER19 0xb13
#define CSR_MHPMCOUNTER20 0xb14
#define CSR_MHPMCOUNTER21 0xb15
#define CSR_MHPMCOUNTER22 0xb16
#define CSR_MHPMCOUNTER23 0xb17
#define CSR_MHPMCOUNTER24 0xb18
#define CSR_MHPMCOUNTER25 0xb19
#define CSR_MHPMCOUNTER26 0xb1a
#define CSR_MHPMCOUNTER27 0xb1b
#define CSR_MHPMCOUNTER28 0xb1c
#define CSR_MHPMCOUNTER29 0xb1d
#define CSR_MHPMCOUNTER30 0xb1e
#define CSR_MHPMCOUNTER31 0xb1f
#define CSR_MUCOUNTEREN 0x320
#define CSR_MSCOUNTEREN 0x321
#define CSR_MHPMEVENT3 0x323
#define CSR_MHPMEVENT4 0x324
#define CSR_MHPMEVENT5 0x325
#define CSR_MHPMEVENT6 0x326
#define CSR_MHPMEVENT7 0x327
#define CSR_MHPMEVENT8 0x328
#define CSR_MHPMEVENT9 0x329
#define CSR_MHPMEVENT10 0x32a
#define CSR_MHPMEVENT11 0x32b
#define CSR_MHPMEVENT12 0x32c
#define CSR_MHPMEVENT13 0x32d
#define CSR_MHPMEVENT14 0x32e
#define CSR_MHPMEVENT15 0x32f
#define CSR_MHPMEVENT16 0x330
#define CSR_MHPMEVENT17 0x331
#define CSR_MHPMEVENT18 0x332
#define CSR_MHPMEVENT19 0x333
#define CSR_MHPMEVENT20 0x334
#define CSR_MHPMEVENT21 0x335
#define CSR_MHPMEVENT22 0x336
#define CSR_MHPMEVENT23 0x337
#define CSR_MHPMEVENT24 0x338
#define CSR_MHPMEVENT25 0x339
#define CSR_MHPMEVENT26 0x33a
#define CSR_MHPMEVENT27 0x33b
#define CSR_MHPMEVENT28 0x33c
#define CSR_MHPMEVENT29 0x33d
#define CSR_MHPMEVENT30 0x33e
#define CSR_MHPMEVENT31 0x33f
#define CSR_MVENDORID 0xf11
#define CSR_MARCHID 0xf12
#define CSR_MIMPID 0xf13
#define CSR_MHARTID 0xf14
#define CSR_CYCLEH 0xc80
#define CSR_TIMEH 0xc81
#define CSR_INSTRETH 0xc82
#define CSR_HPMCOUNTER3H 0xc83
#define CSR_HPMCOUNTER4H 0xc84
#define CSR_HPMCOUNTER5H 0xc85
#define CSR_HPMCOUNTER6H 0xc86
#define CSR_HPMCOUNTER7H 0xc87
#define CSR_HPMCOUNTER8H 0xc88
#define CSR_HPMCOUNTER9H 0xc89
#define CSR_HPMCOUNTER10H 0xc8a
#define CSR_HPMCOUNTER11H 0xc8b
#define CSR_HPMCOUNTER12H 0xc8c
#define CSR_HPMCOUNTER13H 0xc8d
#define CSR_HPMCOUNTER14H 0xc8e
#define CSR_HPMCOUNTER15H 0xc8f
#define CSR_HPMCOUNTER16H 0xc90
#define CSR_HPMCOUNTER17H 0xc91
#define CSR_HPMCOUNTER18H 0xc92
#define CSR_HPMCOUNTER19H 0xc93
#define CSR_HPMCOUNTER20H 0xc94
#define CSR_HPMCOUNTER21H 0xc95
#define CSR_HPMCOUNTER22H 0xc96
#define CSR_HPMCOUNTER23H 0xc97
#define CSR_HPMCOUNTER24H 0xc98
#define CSR_HPMCOUNTER25H 0xc99
#define CSR_HPMCOUNTER26H 0xc9a
#define CSR_HPMCOUNTER27H 0xc9b
#define CSR_HPMCOUNTER28H 0xc9c
#define CSR_HPMCOUNTER29H 0xc9d
#define CSR_HPMCOUNTER30H 0xc9e
#define CSR_HPMCOUNTER31H 0xc9f
#define CSR_MCYCLEH 0xb80
#define CSR_MINSTRETH 0xb82
#define CSR_MHPMCOUNTER3H 0xb83
#define CSR_MHPMCOUNTER4H 0xb84
#define CSR_MHPMCOUNTER5H 0xb85
#define CSR_MHPMCOUNTER6H 0xb86
#define CSR_MHPMCOUNTER7H 0xb87
#define CSR_MHPMCOUNTER8H 0xb88
#define CSR_MHPMCOUNTER9H 0xb89
#define CSR_MHPMCOUNTER10H 0xb8a
#define CSR_MHPMCOUNTER11H 0xb8b
#define CSR_MHPMCOUNTER12H 0xb8c
#define CSR_MHPMCOUNTER13H 0xb8d
#define CSR_MHPMCOUNTER14H 0xb8e
#define CSR_MHPMCOUNTER15H 0xb8f
#define CSR_MHPMCOUNTER16H 0xb90
#define CSR_MHPMCOUNTER17H 0xb91
#define CSR_MHPMCOUNTER18H 0xb92
#define CSR_MHPMCOUNTER19H 0xb93
#define CSR_MHPMCOUNTER20H 0xb94
#define CSR_MHPMCOUNTER21H 0xb95
#define CSR_MHPMCOUNTER22H 0xb96
#define CSR_MHPMCOUNTER23H 0xb97
#define CSR_MHPMCOUNTER24H 0xb98
#define CSR_MHPMCOUNTER25H 0xb99
#define CSR_MHPMCOUNTER26H 0xb9a
#define CSR_MHPMCOUNTER27H 0xb9b
#define CSR_MHPMCOUNTER28H 0xb9c
#define CSR_MHPMCOUNTER29H 0xb9d
#define CSR_MHPMCOUNTER30H 0xb9e
#define CSR_MHPMCOUNTER31H 0xb9f
/* === TEE CSR Registers === */
#define CSR_SPMPCFG0 0x1A0
#define CSR_SPMPCFG1 0x1A1
#define CSR_SPMPCFG2 0x1A2
#define CSR_SPMPCFG3 0x1A3
#define CSR_SPMPADDR0 0x1B0
#define CSR_SPMPADDR1 0x1B1
#define CSR_SPMPADDR2 0x1B2
#define CSR_SPMPADDR3 0x1B3
#define CSR_SPMPADDR4 0x1B4
#define CSR_SPMPADDR5 0x1B5
#define CSR_SPMPADDR6 0x1B6
#define CSR_SPMPADDR7 0x1B7
#define CSR_SPMPADDR8 0x1B8
#define CSR_SPMPADDR9 0x1B9
#define CSR_SPMPADDR10 0x1BA
#define CSR_SPMPADDR11 0x1BB
#define CSR_SPMPADDR12 0x1BC
#define CSR_SPMPADDR13 0x1BD
#define CSR_SPMPADDR14 0x1BE
#define CSR_SPMPADDR15 0x1BF
#define CSR_JALSNXTI 0x947
#define CSR_STVT2 0x948
#define CSR_PUSHSCAUSE 0x949
#define CSR_PUSHSEPC 0x94A
/* === CLIC CSR Registers === */
#define CSR_MTVT 0x307
#define CSR_MNXTI 0x345
#define CSR_MINTSTATUS 0x346
#define CSR_MSCRATCHCSW 0x348
#define CSR_MSCRATCHCSWL 0x349
#define CSR_MCLICBASE 0x350
/* === P-Extension Registers === */
#define CSR_UCODE 0x801
/* === Nuclei custom CSR Registers === */
#define CSR_MCOUNTINHIBIT 0x320
#define CSR_MILM_CTL 0x7C0
#define CSR_MDLM_CTL 0x7C1
#define CSR_MECC_CODE 0x7C2
#define CSR_MNVEC 0x7C3
#define CSR_MSUBM 0x7C4
#define CSR_MDCAUSE 0x7C9
#define CSR_MCACHE_CTL 0x7CA
#define CSR_MMISC_CTL 0x7D0
#define CSR_MSAVESTATUS 0x7D6
#define CSR_MSAVEEPC1 0x7D7
#define CSR_MSAVECAUSE1 0x7D8
#define CSR_MSAVEEPC2 0x7D9
#define CSR_MSAVECAUSE2 0x7DA
#define CSR_MSAVEDCAUSE1 0x7DB
#define CSR_MSAVEDCAUSE2 0x7DC
#define CSR_MTLB_CTL 0x7DD
#define CSR_MECC_LOCK 0x7DE
#define CSR_MFP16MODE 0x7E2
#define CSR_LSTEPFORC 0x7E9
#define CSR_PUSHMSUBM 0x7EB
#define CSR_MTVT2 0x7EC
#define CSR_JALMNXTI 0x7ED
#define CSR_PUSHMCAUSE 0x7EE
#define CSR_PUSHMEPC 0x7EF
#define CSR_MPPICFG_INFO 0x7F0
#define CSR_MFIOCFG_INFO 0x7F1
#define CSR_MSMPCFG_INFO 0x7F7
#define CSR_SLEEPVALUE 0x811
#define CSR_TXEVT 0x812
#define CSR_WFE 0x810
#define CSR_MICFG_INFO 0xFC0
#define CSR_MDCFG_INFO 0xFC1
#define CSR_MCFG_INFO 0xFC2
#define CSR_MTLBCFG_INFO 0xFC3
/* === Nuclei CCM Registers === */
#define CSR_CCM_MBEGINADDR 0x7CB
#define CSR_CCM_MCOMMAND 0x7CC
#define CSR_CCM_MDATA 0x7CD
#define CSR_CCM_SUEN 0x7CE
#define CSR_CCM_SBEGINADDR 0x5CB
#define CSR_CCM_SCOMMAND 0x5CC
#define CSR_CCM_SDATA 0x5CD
#define CSR_CCM_UBEGINADDR 0x4CB
#define CSR_CCM_UCOMMAND 0x4CC
#define CSR_CCM_UDATA 0x4CD
#define CSR_CCM_FPIPE 0x4CF
/** @} */ /** End of Doxygen Group NMSIS_Core_CSR_Registers **/
/* Exception Code in MCAUSE CSR */
#define CAUSE_MISALIGNED_FETCH 0x0
#define CAUSE_FAULT_FETCH 0x1
#define CAUSE_ILLEGAL_INSTRUCTION 0x2
#define CAUSE_BREAKPOINT 0x3
#define CAUSE_MISALIGNED_LOAD 0x4
#define CAUSE_FAULT_LOAD 0x5
#define CAUSE_MISALIGNED_STORE 0x6
#define CAUSE_FAULT_STORE 0x7
#define CAUSE_USER_ECALL 0x8
#define CAUSE_SUPERVISOR_ECALL 0x9
#define CAUSE_HYPERVISOR_ECALL 0xa
#define CAUSE_MACHINE_ECALL 0xb
/* Exception Subcode in MDCAUSE CSR */
#define DCAUSE_FAULT_FETCH_PMP 0x1
#define DCAUSE_FAULT_FETCH_INST 0x2
#define DCAUSE_FAULT_LOAD_PMP 0x1
#define DCAUSE_FAULT_LOAD_INST 0x2
#define DCAUSE_FAULT_LOAD_NICE 0x3
#define DCAUSE_FAULT_STORE_PMP 0x1
#define DCAUSE_FAULT_STORE_INST 0x2
/** @} */ /** End of Doxygen Group NMSIS_Core_CSR_Encoding **/
#ifdef __cplusplus
}
#endif
#endif /* __RISCV_ENCODING_H__ */

View File

@@ -0,0 +1,52 @@
################# Add global include #################
list(APPEND ADD_INCLUDE
"${CMAKE_CURRENT_SOURCE_DIR}/core"
"${CMAKE_CURRENT_SOURCE_DIR}/common"
"${CMAKE_CURRENT_SOURCE_DIR}/class/cdc"
"${CMAKE_CURRENT_SOURCE_DIR}/class/hid"
"${CMAKE_CURRENT_SOURCE_DIR}/class/msc"
"${CMAKE_CURRENT_SOURCE_DIR}/class/video"
"${CMAKE_CURRENT_SOURCE_DIR}/class/audio"
"${CMAKE_CURRENT_SOURCE_DIR}/class/winusb"
)
#######################################################
################# Add private include #################
# list(APPEND ADD_PRIVATE_INCLUDE
# )
#######################################################
############## Add current dir source files ###########
file(GLOB_RECURSE sources "${CMAKE_CURRENT_SOURCE_DIR}/core/*.c"
"${CMAKE_CURRENT_SOURCE_DIR}/class/*.c"
)
list(APPEND ADD_SRCS ${sources})
# aux_source_directory(src ADD_SRCS)
#######################################################
########### Add required/dependent components #########
#list(APPEND ADD_REQUIREMENTS xxx)
#######################################################
############ Add static libs ##########################
#list(APPEND ADD_STATIC_LIB "libxxx.a")
#######################################################
############ Add dynamic libs #########################
# list(APPEND ADD_DYNAMIC_LIB "libxxx.so"
# )
#######################################################
############ Add global compile option ################
#add components denpend on this component
if(CONFIG_USB_HS)
list(APPEND ADD_DEFINITIONS -DCONFIG_USB_HS)
endif()
#######################################################
############ Add private compile option ################
#add compile option for this component that won't affect other modules
# list(APPEND ADD_PRIVATE_DEFINITIONS -Dxxx)
#######################################################
generate_library()

View File

@@ -0,0 +1,114 @@
#include "usbd_core.h"
#include "usbd_audio.h"
struct usbd_audio_control_info audio_control_info = { 0xdb00, 0x0000, 0x0100, 0xf600, 0 };
int audio_class_request_handler(struct usb_setup_packet *setup, uint8_t **data, uint32_t *len)
{
USBD_LOG_DBG("AUDIO Class request: "
"bRequest 0x%02x\r\n",
setup->bRequest);
switch (setup->bRequest) {
case AUDIO_REQUEST_SET_CUR:
if (setup->wValueL == 0x01) {
if (setup->wValueH == AUDIO_FU_CONTROL_MUTE) {
memcpy(&audio_control_info.mute, *data, *len);
} else if (setup->wValueH == AUDIO_FU_CONTROL_VOLUME) {
memcpy(&audio_control_info.vol_current, *data, *len);
uint32_t vol;
if (audio_control_info.vol_current == 0) {
vol = 100;
} else {
vol = (audio_control_info.vol_current - 0xDB00 + 1) * 100 / (0xFFFF - 0xDB00);
}
usbd_audio_set_volume(vol);
USBD_LOG_INFO("current audio volume:%d\r\n", vol);
}
}
break;
case AUDIO_REQUEST_GET_CUR:
if (setup->wValueH == AUDIO_FU_CONTROL_MUTE) {
*data = (uint8_t *)&audio_control_info.mute;
*len = 1;
} else if (setup->wValueH == AUDIO_FU_CONTROL_VOLUME) {
*data = (uint8_t *)&audio_control_info.vol_current;
*len = 2;
}
break;
case AUDIO_REQUEST_SET_RES:
break;
case AUDIO_REQUEST_SET_MEM:
break;
case AUDIO_REQUEST_GET_MIN:
*data = (uint8_t *)&audio_control_info.vol_min;
*len = 2;
break;
case AUDIO_REQUEST_GET_MAX:
*data = (uint8_t *)&audio_control_info.vol_max;
*len = 2;
break;
case AUDIO_REQUEST_GET_RES:
*data = (uint8_t *)&audio_control_info.vol_res;
*len = 2;
break;
case AUDIO_REQUEST_GET_MEM:
*data[0] = 0;
*len = 1;
break;
default:
USBD_LOG_WRN("Unhandled Audio Class bRequest 0x%02x\r\n", setup->bRequest);
return -1;
}
return 0;
}
void audio_notify_handler(uint8_t event, void *arg)
{
switch (event) {
case USB_EVENT_RESET:
break;
case USB_EVENT_SOF:
break;
case USB_EVENT_SET_INTERFACE:
usbd_audio_set_interface_callback(((uint8_t *)arg)[3]);
break;
default:
break;
}
}
__weak void usbd_audio_set_volume(uint8_t vol)
{
}
void usbd_audio_add_interface(usbd_class_t *class, usbd_interface_t *intf)
{
static usbd_class_t *last_class = NULL;
if (last_class != class) {
last_class = class;
usbd_class_register(class);
}
intf->class_handler = audio_class_request_handler;
intf->custom_handler = NULL;
intf->vendor_handler = NULL;
intf->notify_handler = audio_notify_handler;
usbd_class_add_interface(class, intf);
}

View File

@@ -0,0 +1,277 @@
/**
* @file
* @brief USB Audio Device Class public header
*
* Header follows below documentation:
* - USB Device Class Definition for Audio Devices (audio10.pdf)
*
* Additional documentation considered a part of USB Audio v1.0:
* - USB Device Class Definition for Audio Data Formats (frmts10.pdf)
* - USB Device Class Definition for Terminal Types (termt10.pdf)
*/
#ifndef _USBD_AUDIO_H_
#define _USBD_AUDIO_H_
#ifdef __cplusplus
extern "C" {
#endif
/** Audio Interface Subclass Codes
* Refer to Table A-2 from audio10.pdf
*/
#define AUDIO_SUBCLASS_UNDEFINED 0x00
#define AUDIO_SUBCLASS_AUDIOCONTROL 0x01
#define AUDIO_SUBCLASS_AUDIOSTREAMING 0x02
#define AUDIO_SUBCLASS_MIDISTREAMING 0x03
#define AUDIO_PROTOCOL_UNDEFINED 0x00U
#define AUDIO_ENDPOINT_GENERAL 0x01U
/** Audio Class-Specific Control Interface Descriptor Subtypes
* Refer to Table A-5 from audio10.pdf
*/
#define AUDIO_CONTROL_UNDEFINED 0x01U
#define AUDIO_CONTROL_HEADER 0x01U
#define AUDIO_CONTROL_INPUT_TERMINAL 0x02U
#define AUDIO_CONTROL_OUTPUT_TERMINAL 0x03U
#define AUDIO_CONTROL_MIXER_UNIT 0x04U
#define AUDIO_CONTROL_SELECTOR_UNIT 0x05U
#define AUDIO_CONTROL_FEATURE_UNIT 0x06U
#define AUDIO_CONTROL_PROCESSING_UNIT 0x07U
#define AUDIO_CONTROL_EXTENSION_UNIT 0x08U
/** Audio Class-Specific AS Interface Descriptor Subtypes
* Refer to Table A-6 from audio10.pdf
*/
#define AUDIO_STREAMING_UNDEFINED 0x00U
#define AUDIO_STREAMING_GENERAL 0x01U
#define AUDIO_STREAMING_FORMAT_TYPE 0x02U
#define AUDIO_STREAMING_FORMAT_SPECIFIC 0x03U
/** Audio Class-Specific Request Codes
* Refer to Table A-9 from audio10.pdf
*/
#define AUDIO_REQUEST_UNDEFINED 0x00
#define AUDIO_REQUEST_SET_CUR 0x01
#define AUDIO_REQUEST_GET_CUR 0x81
#define AUDIO_REQUEST_SET_MIN 0x02
#define AUDIO_REQUEST_GET_MIN 0x82
#define AUDIO_REQUEST_SET_MAX 0x03
#define AUDIO_REQUEST_GET_MAX 0x83
#define AUDIO_REQUEST_SET_RES 0x04
#define AUDIO_REQUEST_GET_RES 0x84
#define AUDIO_REQUEST_SET_MEM 0x05
#define AUDIO_REQUEST_GET_MEM 0x85
#define AUDIO_REQUEST_GET_STAT 0xFF
/* Feature Unit Control Bits */
#define AUDIO_CONTROL_MUTE 0x0001
#define AUDIO_CONTROL_VOLUME 0x0002
#define AUDIO_CONTROL_BASS 0x0004
#define AUDIO_CONTROL_MID 0x0008
#define AUDIO_CONTROL_TREBLE 0x0010
#define AUDIO_CONTROL_GRAPHIC_EQUALIZER 0x0020
#define AUDIO_CONTROL_AUTOMATIC_GAIN 0x0040
#define AUDIO_CONTROL_DEALY 0x0080
#define AUDIO_CONTROL_BASS_BOOST 0x0100
#define AUDIO_CONTROL_LOUDNESS 0x0200
/** Feature Unit Control Selectors
* Refer to Table A-11 from audio10.pdf
*/
#define AUDIO_FU_CONTROL_MUTE 0x01
#define AUDIO_FU_CONTROL_VOLUME 0x02
#define AUDIO_FU_CONTROL_BASS 0x03
#define AUDIO_FU_CONTROL_MID 0x04
#define AUDIO_FU_CONTROL_TREBLE 0x05
#define AUDIO_FU_CONTROL_GRAPHIC_EQUALIZER 0x06
#define AUDIO_FU_CONTROL_AUTOMATIC_GAIN 0x07
#define AUDIO_FU_CONTROL_DELAY 0x08
#define AUDIO_FU_CONTROL_BASS_BOOST 0x09
#define AUDIO_FU_CONTROL_LOUDNESS 0x0A
/* Audio Descriptor Types */
#define AUDIO_UNDEFINED_DESCRIPTOR_TYPE 0x20
#define AUDIO_DEVICE_DESCRIPTOR_TYPE 0x21
#define AUDIO_CONFIGURATION_DESCRIPTOR_TYPE 0x22
#define AUDIO_STRING_DESCRIPTOR_TYPE 0x23
#define AUDIO_INTERFACE_DESCRIPTOR_TYPE 0x24
#define AUDIO_ENDPOINT_DESCRIPTOR_TYPE 0x25
/* Audio Data Format Type I Codes */
#define AUDIO_FORMAT_TYPE_I_UNDEFINED 0x0000
#define AUDIO_FORMAT_PCM 0x0001
#define AUDIO_FORMAT_PCM8 0x0002
#define AUDIO_FORMAT_IEEE_FLOAT 0x0003
#define AUDIO_FORMAT_ALAW 0x0004
#define AUDIO_FORMAT_MULAW 0x0005
/* Predefined Audio Channel Configuration Bits */
#define AUDIO_CHANNEL_M 0x0000 /* Mono */
#define AUDIO_CHANNEL_L 0x0001 /* Left Front */
#define AUDIO_CHANNEL_R 0x0002 /* Right Front */
#define AUDIO_CHANNEL_C 0x0004 /* Center Front */
#define AUDIO_CHANNEL_LFE 0x0008 /* Low Freq. Enhance. */
#define AUDIO_CHANNEL_LS 0x0010 /* Left Surround */
#define AUDIO_CHANNEL_RS 0x0020 /* Right Surround */
#define AUDIO_CHANNEL_LC 0x0040 /* Left of Center */
#define AUDIO_CHANNEL_RC 0x0080 /* Right of Center */
#define AUDIO_CHANNEL_S 0x0100 /* Surround */
#define AUDIO_CHANNEL_SL 0x0200 /* Side Left */
#define AUDIO_CHANNEL_SR 0x0400 /* Side Right */
#define AUDIO_CHANNEL_T 0x0800 /* Top */
#define AUDIO_FORMAT_TYPE_I 0x01
#define AUDIO_FORMAT_TYPE_II 0x02
#define AUDIO_FORMAT_TYPE_III 0x03
/** USB Terminal Types
* Refer to Table 2-1 - Table 2-4 from termt10.pdf
*/
enum usb_audio_terminal_types {
/* USB Terminal Types */
USB_AUDIO_USB_UNDEFINED = 0x0100,
USB_AUDIO_USB_STREAMING = 0x0101,
USB_AUDIO_USB_VENDOR_SPEC = 0x01FF,
/* Input Terminal Types */
USB_AUDIO_IN_UNDEFINED = 0x0200,
USB_AUDIO_IN_MICROPHONE = 0x0201,
USB_AUDIO_IN_DESKTOP_MIC = 0x0202,
USB_AUDIO_IN_PERSONAL_MIC = 0x0203,
USB_AUDIO_IN_OM_DIR_MIC = 0x0204,
USB_AUDIO_IN_MIC_ARRAY = 0x0205,
USB_AUDIO_IN_PROC_MIC_ARRAY = 0x0205,
/* Output Terminal Types */
USB_AUDIO_OUT_UNDEFINED = 0x0300,
USB_AUDIO_OUT_SPEAKER = 0x0301,
USB_AUDIO_OUT_HEADPHONES = 0x0302,
USB_AUDIO_OUT_HEAD_AUDIO = 0x0303,
USB_AUDIO_OUT_DESKTOP_SPEAKER = 0x0304,
USB_AUDIO_OUT_ROOM_SPEAKER = 0x0305,
USB_AUDIO_OUT_COMM_SPEAKER = 0x0306,
USB_AUDIO_OUT_LOW_FREQ_SPEAKER = 0x0307,
/* Bi-directional Terminal Types */
USB_AUDIO_IO_UNDEFINED = 0x0400,
USB_AUDIO_IO_HANDSET = 0x0401,
USB_AUDIO_IO_HEADSET = 0x0402,
USB_AUDIO_IO_SPEAKERPHONE_ECHO_NONE = 0x0403,
USB_AUDIO_IO_SPEAKERPHONE_ECHO_SUP = 0x0404,
USB_AUDIO_IO_SPEAKERPHONE_ECHO_CAN = 0x0405,
};
/**
* @warning Size of baInterface is 2 just to make it useable
* for all kind of devices: headphones, microphone and headset.
* Actual size of the struct should be checked by reading
* .bLength.
*/
struct cs_ac_if_descriptor {
uint8_t bLength;
uint8_t bDescriptorType;
uint8_t bDescriptorSubtype;
uint16_t bcdADC;
uint16_t wTotalLength;
uint8_t bInCollection;
uint8_t baInterfaceNr[2];
} __packed;
struct input_terminal_descriptor {
uint8_t bLength;
uint8_t bDescriptorType;
uint8_t bDescriptorSubtype;
uint8_t bTerminalID;
uint16_t wTerminalType;
uint8_t bAssocTerminal;
uint8_t bNrChannels;
uint16_t wChannelConfig;
uint8_t iChannelNames;
uint8_t iTerminal;
} __packed;
/**
* @note Size of Feature unit descriptor is not fixed.
* This structure is just a helper not a common type.
*/
struct feature_unit_descriptor {
uint8_t bLength;
uint8_t bDescriptorType;
uint8_t bDescriptorSubtype;
uint8_t bUnitID;
uint8_t bSourceID;
uint8_t bControlSize;
uint16_t bmaControls[1];
} __packed;
struct output_terminal_descriptor {
uint8_t bLength;
uint8_t bDescriptorType;
uint8_t bDescriptorSubtype;
uint8_t bTerminalID;
uint16_t wTerminalType;
uint8_t bAssocTerminal;
uint8_t bSourceID;
uint8_t iTerminal;
} __packed;
struct as_cs_interface_descriptor {
uint8_t bLength;
uint8_t bDescriptorType;
uint8_t bDescriptorSubtype;
uint8_t bTerminalLink;
uint8_t bDelay;
uint16_t wFormatTag;
} __packed;
struct format_type_i_descriptor {
uint8_t bLength;
uint8_t bDescriptorType;
uint8_t bDescriptorSubtype;
uint8_t bFormatType;
uint8_t bNrChannels;
uint8_t bSubframeSize;
uint8_t bBitResolution;
uint8_t bSamFreqType;
uint8_t tSamFreq[3];
} __packed;
struct std_as_ad_endpoint_descriptor {
uint8_t bLength;
uint8_t bDescriptorType;
uint8_t bEndpointAddress;
uint8_t bmAttributes;
uint16_t wMaxPacketSize;
uint8_t bInterval;
uint8_t bRefresh;
uint8_t bSynchAddress;
} __packed;
struct cs_as_ad_ep_descriptor {
uint8_t bLength;
uint8_t bDescriptorType;
uint8_t bDescriptorSubtype;
uint8_t bmAttributes;
uint8_t bLockDelayUnits;
uint16_t wLockDelay;
} __packed;
struct usbd_audio_control_info {
uint16_t vol_min;
uint16_t vol_max;
uint16_t vol_res;
uint16_t vol_current;
uint8_t mute;
};
void usbd_audio_add_interface(usbd_class_t *class, usbd_interface_t *intf);
void usbd_audio_set_interface_callback(uint8_t value);
void usbd_audio_set_volume(uint8_t vol);
#ifdef __cplusplus
}
#endif
#endif /* _USB_AUDIO_H_ */

View File

@@ -0,0 +1,171 @@
/**
* @file usbd_cdc.c
* @brief
*
* Copyright (c) 2021 Bouffalolab team
*
* Licensed to the Apache Software Foundation (ASF) under one or more
* contributor license agreements. See the NOTICE file distributed with
* this work for additional information regarding copyright ownership. The
* ASF licenses this file to you under the Apache License, Version 2.0 (the
* "License"); you may not use this file except in compliance with the
* License. You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
* License for the specific language governing permissions and limitations
* under the License.
*
*/
#include "usbd_core.h"
#include "usbd_cdc.h"
const char *stop_name[] = { "1", "1.5", "2" };
const char *parity_name[] = { "N", "O", "E", "M", "S" };
/* Device data structure */
struct cdc_acm_cfg_private {
/* CDC ACM line coding properties. LE order */
struct cdc_line_coding line_coding;
/* CDC ACM line state bitmap, DTE side */
uint8_t line_state;
/* CDC ACM serial state bitmap, DCE side */
uint8_t serial_state;
/* CDC ACM notification sent status */
uint8_t notification_sent;
/* CDC ACM configured flag */
bool configured;
/* CDC ACM suspended flag */
bool suspended;
uint32_t uart_first_init_flag;
} usbd_cdc_acm_cfg;
static void usbd_cdc_acm_reset(void)
{
usbd_cdc_acm_cfg.line_coding.dwDTERate = 2000000;
usbd_cdc_acm_cfg.line_coding.bDataBits = 8;
usbd_cdc_acm_cfg.line_coding.bParityType = 0;
usbd_cdc_acm_cfg.line_coding.bCharFormat = 0;
usbd_cdc_acm_cfg.configured = false;
usbd_cdc_acm_cfg.uart_first_init_flag = 0;
}
/**
* @brief Handler called for Class requests not handled by the USB stack.
*
* @param setup Information about the request to execute.
* @param len Size of the buffer.
* @param data Buffer containing the request result.
*
* @return 0 on success, negative errno code on fail.
*/
static int cdc_acm_class_request_handler(struct usb_setup_packet *setup, uint8_t **data, uint32_t *len)
{
USBD_LOG_DBG("CDC Class request: "
"bRequest 0x%02x\r\n",
setup->bRequest);
switch (setup->bRequest) {
case CDC_REQUEST_SET_LINE_CODING:
/*******************************************************************************/
/* Line Coding Structure */
/*-----------------------------------------------------------------------------*/
/* Offset | Field | Size | Value | Description */
/* 0 | dwDTERate | 4 | Number |Data terminal rate, in bits per second*/
/* 4 | bCharFormat | 1 | Number | Stop bits */
/* 0 - 1 Stop bit */
/* 1 - 1.5 Stop bits */
/* 2 - 2 Stop bits */
/* 5 | bParityType | 1 | Number | Parity */
/* 0 - None */
/* 1 - Odd */
/* 2 - Even */
/* 3 - Mark */
/* 4 - Space */
/* 6 | bDataBits | 1 | Number Data bits (5, 6, 7, 8 or 16). */
/*******************************************************************************/
if (usbd_cdc_acm_cfg.uart_first_init_flag == 0) {
usbd_cdc_acm_cfg.uart_first_init_flag = 1;
return 0;
}
memcpy(&usbd_cdc_acm_cfg.line_coding, *data, sizeof(usbd_cdc_acm_cfg.line_coding));
USBD_LOG_DBG("CDC_SET_LINE_CODING <%d %d %s %s>\r\n",
usbd_cdc_acm_cfg.line_coding.dwDTERate,
usbd_cdc_acm_cfg.line_coding.bDataBits,
parity_name[usbd_cdc_acm_cfg.line_coding.bParityType],
stop_name[usbd_cdc_acm_cfg.line_coding.bCharFormat]);
usbd_cdc_acm_set_line_coding(usbd_cdc_acm_cfg.line_coding.dwDTERate, usbd_cdc_acm_cfg.line_coding.bDataBits,
usbd_cdc_acm_cfg.line_coding.bParityType, usbd_cdc_acm_cfg.line_coding.bCharFormat);
break;
case CDC_REQUEST_SET_CONTROL_LINE_STATE:
usbd_cdc_acm_cfg.line_state = (uint8_t)setup->wValue;
bool dtr = (setup->wValue & 0x01);
bool rts = (setup->wValue & 0x02);
USBD_LOG_DBG("DTR 0x%x,RTS 0x%x\r\n",
dtr, rts);
usbd_cdc_acm_set_dtr(dtr);
usbd_cdc_acm_set_rts(rts);
break;
case CDC_REQUEST_GET_LINE_CODING:
*data = (uint8_t *)(&usbd_cdc_acm_cfg.line_coding);
*len = sizeof(usbd_cdc_acm_cfg.line_coding);
USBD_LOG_DBG("CDC_GET_LINE_CODING %d %d %d %d\r\n",
usbd_cdc_acm_cfg.line_coding.dwDTERate,
usbd_cdc_acm_cfg.line_coding.bCharFormat,
usbd_cdc_acm_cfg.line_coding.bParityType,
usbd_cdc_acm_cfg.line_coding.bDataBits);
break;
default:
USBD_LOG_WRN("Unhandled CDC Class bRequest 0x%02x\r\n", setup->bRequest);
return -1;
}
return 0;
}
static void cdc_notify_handler(uint8_t event, void *arg)
{
switch (event) {
case USB_EVENT_RESET:
usbd_cdc_acm_reset();
break;
default:
break;
}
}
__weak void usbd_cdc_acm_set_line_coding(uint32_t baudrate, uint8_t databits, uint8_t parity, uint8_t stopbits)
{
}
__weak void usbd_cdc_acm_set_dtr(bool dtr)
{
}
__weak void usbd_cdc_acm_set_rts(bool rts)
{
}
void usbd_cdc_add_acm_interface(usbd_class_t *class, usbd_interface_t *intf)
{
static usbd_class_t *last_class = NULL;
if (last_class != class) {
last_class = class;
usbd_class_register(class);
}
intf->class_handler = cdc_acm_class_request_handler;
intf->custom_handler = NULL;
intf->vendor_handler = NULL;
intf->notify_handler = cdc_notify_handler;
usbd_class_add_interface(class, intf);
}

View File

@@ -0,0 +1,442 @@
/**
* @file
* @brief USB Communications Device Class (CDC) public header
*
* Header follows the Class Definitions for
* Communications Devices Specification (CDC120-20101103-track.pdf),
* PSTN Devices Specification (PSTN120.pdf) and
* Ethernet Control Model Devices Specification (ECM120.pdf).
* Header is limited to ACM and ECM Subclasses.
*/
#ifndef _USBD_CDC_H
#define _USBD_CDC_H
#ifdef __cplusplus
extern "C" {
#endif
/*------------------------------------------------------------------------------
* Definitions based on usbcdc11.pdf (www.usb.org)
*----------------------------------------------------------------------------*/
/* Communication device class specification version 1.10 */
#define CDC_V1_10 0x0110U
// Communication device class specification version 1.2
#define CDC_V1_2_0 0x0120U
/* Communication interface class code */
/* (usbcdc11.pdf, 4.2, Table 15) */
#define CDC_COMMUNICATION_INTERFACE_CLASS 0x02U
/* Communication interface class subclass codes */
/* (usbcdc11.pdf, 4.3, Table 16) */
#define CDC_DIRECT_LINE_CONTROL_MODEL 0x01U
#define CDC_ABSTRACT_CONTROL_MODEL 0x02U
#define CDC_TELEPHONE_CONTROL_MODEL 0x03U
#define CDC_MULTI_CHANNEL_CONTROL_MODEL 0x04U
#define CDC_CAPI_CONTROL_MODEL 0x05U
#define CDC_ETHERNET_NETWORKING_CONTROL_MODEL 0x06U
#define CDC_ATM_NETWORKING_CONTROL_MODEL 0x07U
#define CDC_WIRELESS_HANDSET_CONTROL_MODEL 0x08U
#define CDC_DEVICE_MANAGEMENT 0x09U
#define CDC_MOBILE_DIRECT_LINE_MODEL 0x0AU
#define CDC_OBEX 0x0BU
#define CDC_ETHERNET_EMULATION_MODEL 0x0CU
#define CDC_NETWORK_CONTROL_MODEL 0x0DU
/* Communication interface class control protocol codes */
/* (usbcdc11.pdf, 4.4, Table 17) */
#define CDC_COMMON_PROTOCOL_NONE 0x00U
#define CDC_COMMON_PROTOCOL_AT_COMMANDS 0x01U
#define CDC_COMMON_PROTOCOL_AT_COMMANDS_PCCA_101 0x02U
#define CDC_COMMON_PROTOCOL_AT_COMMANDS_PCCA_101_AND_ANNEXO 0x03U
#define CDC_COMMON_PROTOCOL_AT_COMMANDS_GSM_707 0x04U
#define CDC_COMMON_PROTOCOL_AT_COMMANDS_3GPP_27007 0x05U
#define CDC_COMMON_PROTOCOL_AT_COMMANDS_CDMA 0x06U
#define CDC_COMMON_PROTOCOL_ETHERNET_EMULATION_MODEL 0x07U
// NCM Communication Interface Protocol Codes
// (usbncm10.pdf, 4.2, Table 4-2)
#define CDC_NCM_PROTOCOL_NONE 0x00U
#define CDC_NCM_PROTOCOL_OEM 0xFEU
/* Data interface class code */
/* (usbcdc11.pdf, 4.5, Table 18) */
#define CDC_DATA_INTERFACE_CLASS 0x0A
/* Data interface class protocol codes */
/* (usbcdc11.pdf, 4.7, Table 19) */
#define CDC_DATA_PROTOCOL_ISDN_BRI 0x30
#define CDC_DATA_PROTOCOL_HDLC 0x31
#define CDC_DATA_PROTOCOL_TRANSPARENT 0x32
#define CDC_DATA_PROTOCOL_Q921_MANAGEMENT 0x50
#define CDC_DATA_PROTOCOL_Q921_DATA_LINK 0x51
#define CDC_DATA_PROTOCOL_Q921_MULTIPLEXOR 0x52
#define CDC_DATA_PROTOCOL_V42 0x90
#define CDC_DATA_PROTOCOL_EURO_ISDN 0x91
#define CDC_DATA_PROTOCOL_V24_RATE_ADAPTATION 0x92
#define CDC_DATA_PROTOCOL_CAPI 0x93
#define CDC_DATA_PROTOCOL_HOST_BASED_DRIVER 0xFD
#define CDC_DATA_PROTOCOL_DESCRIBED_IN_PUFD 0xFE
/* Type values for bDescriptorType field of functional descriptors */
/* (usbcdc11.pdf, 5.2.3, Table 24) */
#define CDC_CS_INTERFACE 0x24
#define CDC_CS_ENDPOINT 0x25
/* Type values for bDescriptorSubtype field of functional descriptors */
/* (usbcdc11.pdf, 5.2.3, Table 25) */
#define CDC_FUNC_DESC_HEADER 0x00
#define CDC_FUNC_DESC_CALL_MANAGEMENT 0x01
#define CDC_FUNC_DESC_ABSTRACT_CONTROL_MANAGEMENT 0x02
#define CDC_FUNC_DESC_DIRECT_LINE_MANAGEMENT 0x03
#define CDC_FUNC_DESC_TELEPHONE_RINGER 0x04
#define CDC_FUNC_DESC_REPORTING_CAPABILITIES 0x05
#define CDC_FUNC_DESC_UNION 0x06
#define CDC_FUNC_DESC_COUNTRY_SELECTION 0x07
#define CDC_FUNC_DESC_TELEPHONE_OPERATIONAL_MODES 0x08
#define CDC_FUNC_DESC_USB_TERMINAL 0x09
#define CDC_FUNC_DESC_NETWORK_CHANNEL 0x0A
#define CDC_FUNC_DESC_PROTOCOL_UNIT 0x0B
#define CDC_FUNC_DESC_EXTENSION_UNIT 0x0C
#define CDC_FUNC_DESC_MULTI_CHANNEL_MANAGEMENT 0x0D
#define CDC_FUNC_DESC_CAPI_CONTROL_MANAGEMENT 0x0E
#define CDC_FUNC_DESC_ETHERNET_NETWORKING 0x0F
#define CDC_FUNC_DESC_ATM_NETWORKING 0x10
#define CDC_FUNC_DESC_WIRELESS_HANDSET_CONTROL_MODEL 0x11
#define CDC_FUNC_DESC_MOBILE_DIRECT_LINE_MODEL 0x12
#define CDC_FUNC_DESC_MOBILE_DIRECT_LINE_MODEL_DETAIL 0x13
#define CDC_FUNC_DESC_DEVICE_MANAGEMENT_MODEL 0x14
#define CDC_FUNC_DESC_OBEX 0x15
#define CDC_FUNC_DESC_COMMAND_SET 0x16
#define CDC_FUNC_DESC_COMMAND_SET_DETAIL 0x17
#define CDC_FUNC_DESC_TELEPHONE_CONTROL_MODEL 0x18
#define CDC_FUNC_DESC_OBEX_SERVICE_IDENTIFIER 0x19
/* CDC class-specific request codes */
/* (usbcdc11.pdf, 6.2, Table 46) */
/* see Table 45 for info about the specific requests. */
#define CDC_REQUEST_SEND_ENCAPSULATED_COMMAND 0x00
#define CDC_REQUEST_GET_ENCAPSULATED_RESPONSE 0x01
#define CDC_REQUEST_SET_COMM_FEATURE 0x02
#define CDC_REQUEST_GET_COMM_FEATURE 0x03
#define CDC_REQUEST_CLEAR_COMM_FEATURE 0x04
#define CDC_REQUEST_SET_AUX_LINE_STATE 0x10
#define CDC_REQUEST_SET_HOOK_STATE 0x11
#define CDC_REQUEST_PULSE_SETUP 0x12
#define CDC_REQUEST_SEND_PULSE 0x13
#define CDC_REQUEST_SET_PULSE_TIME 0x14
#define CDC_REQUEST_RING_AUX_JACK 0x15
#define CDC_REQUEST_SET_LINE_CODING 0x20
#define CDC_REQUEST_GET_LINE_CODING 0x21
#define CDC_REQUEST_SET_CONTROL_LINE_STATE 0x22
#define CDC_REQUEST_SEND_BREAK 0x23
#define CDC_REQUEST_SET_RINGER_PARMS 0x30
#define CDC_REQUEST_GET_RINGER_PARMS 0x31
#define CDC_REQUEST_SET_OPERATION_PARMS 0x32
#define CDC_REQUEST_GET_OPERATION_PARMS 0x33
#define CDC_REQUEST_SET_LINE_PARMS 0x34
#define CDC_REQUEST_GET_LINE_PARMS 0x35
#define CDC_REQUEST_DIAL_DIGITS 0x36
#define CDC_REQUEST_SET_UNIT_PARAMETER 0x37
#define CDC_REQUEST_GET_UNIT_PARAMETER 0x38
#define CDC_REQUEST_CLEAR_UNIT_PARAMETER 0x39
#define CDC_REQUEST_GET_PROFILE 0x3A
#define CDC_REQUEST_SET_ETHERNET_MULTICAST_FILTERS 0x40
#define CDC_REQUEST_SET_ETHERNET_PMP_FILTER 0x41
#define CDC_REQUEST_GET_ETHERNET_PMP_FILTER 0x42
#define CDC_REQUEST_SET_ETHERNET_PACKET_FILTER 0x43
#define CDC_REQUEST_GET_ETHERNET_STATISTIC 0x44
#define CDC_REQUEST_SET_ATM_DATA_FORMAT 0x50
#define CDC_REQUEST_GET_ATM_DEVICE_STATISTICS 0x51
#define CDC_REQUEST_SET_ATM_DEFAULT_VC 0x52
#define CDC_REQUEST_GET_ATM_VC_STATISTICS 0x53
/* Communication feature selector codes */
/* (usbcdc11.pdf, 6.2.2..6.2.4, Table 47) */
#define CDC_ABSTRACT_STATE 0x01
#define CDC_COUNTRY_SETTING 0x02
/** Control Signal Bitmap Values for SetControlLineState */
#define SET_CONTROL_LINE_STATE_RTS 0x02
#define SET_CONTROL_LINE_STATE_DTR 0x01
/* Feature Status returned for ABSTRACT_STATE Selector */
/* (usbcdc11.pdf, 6.2.3, Table 48) */
#define CDC_IDLE_SETTING (1 << 0)
#define CDC_DATA_MULTPLEXED_STATE (1 << 1)
/* Control signal bitmap values for the SetControlLineState request */
/* (usbcdc11.pdf, 6.2.14, Table 51) */
#define CDC_DTE_PRESENT (1 << 0)
#define CDC_ACTIVATE_CARRIER (1 << 1)
/* CDC class-specific notification codes */
/* (usbcdc11.pdf, 6.3, Table 68) */
/* see Table 67 for Info about class-specific notifications */
#define CDC_NOTIFICATION_NETWORK_CONNECTION 0x00
#define CDC_RESPONSE_AVAILABLE 0x01
#define CDC_AUX_JACK_HOOK_STATE 0x08
#define CDC_RING_DETECT 0x09
#define CDC_NOTIFICATION_SERIAL_STATE 0x20
#define CDC_CALL_STATE_CHANGE 0x28
#define CDC_LINE_STATE_CHANGE 0x29
#define CDC_CONNECTION_SPEED_CHANGE 0x2A
/* UART state bitmap values (Serial state notification). */
/* (usbcdc11.pdf, 6.3.5, Table 69) */
#define CDC_SERIAL_STATE_OVERRUN (1 << 6) /* receive data overrun error has occurred */
#define CDC_SERIAL_STATE_OVERRUN_Pos (6)
#define CDC_SERIAL_STATE_OVERRUN_Msk (1 << CDC_SERIAL_STATE_OVERRUN_Pos)
#define CDC_SERIAL_STATE_PARITY (1 << 5) /* parity error has occurred */
#define CDC_SERIAL_STATE_PARITY_Pos (5)
#define CDC_SERIAL_STATE_PARITY_Msk (1 << CDC_SERIAL_STATE_PARITY_Pos)
#define CDC_SERIAL_STATE_FRAMING (1 << 4) /* framing error has occurred */
#define CDC_SERIAL_STATE_FRAMING_Pos (4)
#define CDC_SERIAL_STATE_FRAMING_Msk (1 << CDC_SERIAL_STATE_FRAMING_Pos)
#define CDC_SERIAL_STATE_RING (1 << 3) /* state of ring signal detection */
#define CDC_SERIAL_STATE_RING_Pos (3)
#define CDC_SERIAL_STATE_RING_Msk (1 << CDC_SERIAL_STATE_RING_Pos)
#define CDC_SERIAL_STATE_BREAK (1 << 2) /* state of break detection */
#define CDC_SERIAL_STATE_BREAK_Pos (2)
#define CDC_SERIAL_STATE_BREAK_Msk (1 << CDC_SERIAL_STATE_BREAK_Pos)
#define CDC_SERIAL_STATE_TX_CARRIER (1 << 1) /* state of transmission carrier */
#define CDC_SERIAL_STATE_TX_CARRIER_Pos (1)
#define CDC_SERIAL_STATE_TX_CARRIER_Msk (1 << CDC_SERIAL_STATE_TX_CARRIER_Pos)
#define CDC_SERIAL_STATE_RX_CARRIER (1 << 0) /* state of receiver carrier */
#define CDC_SERIAL_STATE_RX_CARRIER_Pos (0)
#define CDC_SERIAL_STATE_RX_CARRIER_Msk (1 << CDC_SERIAL_STATE_RX_CARRIER_Pos)
/*------------------------------------------------------------------------------
* Structures based on usbcdc11.pdf (www.usb.org)
*----------------------------------------------------------------------------*/
/* Header functional descriptor */
/* (usbcdc11.pdf, 5.2.3.1) */
/* This header must precede any list of class-specific descriptors. */
struct cdc_header_descriptor {
uint8_t bFunctionLength; /* size of this descriptor in bytes */
uint8_t bDescriptorType; /* CS_INTERFACE descriptor type */
uint8_t bDescriptorSubtype; /* Header functional descriptor subtype */
uint16_t bcdCDC; /* USB CDC specification release version */
} __packed;
/* Call management functional descriptor */
/* (usbcdc11.pdf, 5.2.3.2) */
/* Describes the processing of calls for the communication class interface. */
struct cdc_call_management_descriptor {
uint8_t bFunctionLength; /* size of this descriptor in bytes */
uint8_t bDescriptorType; /* CS_INTERFACE descriptor type */
uint8_t bDescriptorSubtype; /* call management functional descriptor subtype */
uint8_t bmCapabilities; /* capabilities that this configuration supports */
uint8_t bDataInterface; /* interface number of the data class interface used for call management (optional) */
} __packed;
/* Abstract control management functional descriptor */
/* (usbcdc11.pdf, 5.2.3.3) */
/* Describes the command supported by the communication interface class with the Abstract Control Model subclass code. */
struct cdc_abstract_control_management_descriptor {
uint8_t bFunctionLength; /* size of this descriptor in bytes */
uint8_t bDescriptorType; /* CS_INTERFACE descriptor type */
uint8_t bDescriptorSubtype; /* abstract control management functional descriptor subtype */
uint8_t bmCapabilities; /* capabilities supported by this configuration */
} __packed;
/* Union functional descriptors */
/* (usbcdc11.pdf, 5.2.3.8) */
/* Describes the relationship between a group of interfaces that can be considered to form a functional unit. */
struct cdc_union_descriptor {
uint8_t bFunctionLength; /* size of this descriptor in bytes */
uint8_t bDescriptorType; /* CS_INTERFACE descriptor type */
uint8_t bDescriptorSubtype; /* union functional descriptor subtype */
uint8_t bMasterInterface; /* interface number designated as master */
} __packed;
/* Union functional descriptors with one slave interface */
/* (usbcdc11.pdf, 5.2.3.8) */
struct cdc_union_1slave_descriptor {
uint8_t bFunctionLength;
uint8_t bDescriptorType;
uint8_t bDescriptorSubtype;
uint8_t bControlInterface;
uint8_t bSubordinateInterface0;
} __packed;
/* Line coding structure for GET_LINE_CODING / SET_LINE_CODING class requests*/
/* Format of the data returned when a GetLineCoding request is received */
/* (usbcdc11.pdf, 6.2.13) */
struct cdc_line_coding {
uint32_t dwDTERate; /* Data terminal rate in bits per second */
uint8_t bCharFormat; /* Number of stop bits */
uint8_t bParityType; /* Parity bit type */
uint8_t bDataBits; /* Number of data bits */
} __packed;
/** Data structure for the notification about SerialState */
struct cdc_acm_notification {
uint8_t bmRequestType;
uint8_t bNotificationType;
uint16_t wValue;
uint16_t wIndex;
uint16_t wLength;
uint16_t data;
} __packed;
/** Ethernet Networking Functional Descriptor */
struct cdc_ecm_descriptor {
uint8_t bFunctionLength;
uint8_t bDescriptorType;
uint8_t bDescriptorSubtype;
uint8_t iMACAddress;
uint32_t bmEthernetStatistics;
uint16_t wMaxSegmentSize;
uint16_t wNumberMCFilters;
uint8_t bNumberPowerFilters;
} __packed;
/*Length of template descriptor: 66 bytes*/
#define CDC_ACM_DESCRIPTOR_LEN (8 + 9 + 5 + 5 + 4 + 5 + 7 + 9 + 7 + 7)
// clang-format off
#ifndef CONFIG_USB_HS
#define CDC_ACM_DESCRIPTOR_INIT(bFirstInterface, int_ep, out_ep, in_ep, str_idx) \
/* Interface Associate */ \
0x08, /* bLength */ \
USB_DESCRIPTOR_TYPE_INTERFACE_ASSOCIATION, /* bDescriptorType */ \
bFirstInterface, /* bFirstInterface */ \
0x02, /* bInterfaceCount */ \
USB_DEVICE_CLASS_CDC, /* bFunctionClass */ \
CDC_ABSTRACT_CONTROL_MODEL, /* bFunctionSubClass */ \
CDC_COMMON_PROTOCOL_AT_COMMANDS, /* bFunctionProtocol */ \
0x00, /* iFunction */ \
0x09, /* bLength */ \
USB_DESCRIPTOR_TYPE_INTERFACE, /* bDescriptorType */ \
bFirstInterface, /* bInterfaceNumber */ \
0x00, /* bAlternateSetting */ \
0x01, /* bNumEndpoints */ \
USB_DEVICE_CLASS_CDC, /* bInterfaceClass */ \
CDC_ABSTRACT_CONTROL_MODEL, /* bInterfaceSubClass */ \
CDC_COMMON_PROTOCOL_AT_COMMANDS, /* bInterfaceProtocol */ \
str_idx, /* iInterface */ \
0x05, /* bLength */ \
CDC_CS_INTERFACE, /* bDescriptorType */ \
CDC_FUNC_DESC_HEADER, /* bDescriptorSubtype */ \
WBVAL(CDC_V1_10), /* bcdCDC */ \
0x05, /* bLength */ \
CDC_CS_INTERFACE, /* bDescriptorType */ \
CDC_FUNC_DESC_CALL_MANAGEMENT, /* bDescriptorSubtype */ \
bFirstInterface, /* bmCapabilities */ \
(uint8_t)(bFirstInterface + 1), /* bDataInterface */ \
0x04, /* bLength */ \
CDC_CS_INTERFACE, /* bDescriptorType */ \
CDC_FUNC_DESC_ABSTRACT_CONTROL_MANAGEMENT, /* bDescriptorSubtype */ \
0x02, /* bmCapabilities */ \
0x05, /* bLength */ \
CDC_CS_INTERFACE, /* bDescriptorType */ \
CDC_FUNC_DESC_UNION, /* bDescriptorSubtype */ \
bFirstInterface, /* bMasterInterface */ \
(uint8_t)(bFirstInterface + 1), /* bSlaveInterface0 */ \
0x07, /* bLength */ \
USB_DESCRIPTOR_TYPE_ENDPOINT, /* bDescriptorType */ \
int_ep, /* bEndpointAddress */ \
0x03, /* bmAttributes */ \
0x40, 0x00, /* wMaxPacketSize */ \
0x00, /* bInterval */ \
0x09, /* bLength */ \
USB_DESCRIPTOR_TYPE_INTERFACE, /* bDescriptorType */ \
(uint8_t)(bFirstInterface + 1), /* bInterfaceNumber */ \
0x00, /* bAlternateSetting */ \
0x02, /* bNumEndpoints */ \
CDC_DATA_INTERFACE_CLASS, /* bInterfaceClass */ \
0x00, /* bInterfaceSubClass */ \
0x00, /* bInterfaceProtocol */ \
0x00, /* iInterface */ \
0x07, /* bLength */ \
USB_DESCRIPTOR_TYPE_ENDPOINT, /* bDescriptorType */ \
out_ep, /* bEndpointAddress */ \
0x02, /* bmAttributes */ \
0x40, 0x00, /* wMaxPacketSize */ \
0x00, /* bInterval */ \
0x07, /* bLength */ \
USB_DESCRIPTOR_TYPE_ENDPOINT, /* bDescriptorType */ \
in_ep, /* bEndpointAddress */ \
0x02, /* bmAttributes */ \
0x40, 0x00, /* wMaxPacketSize */ \
0x00 /* bInterval */
#else
#define CDC_ACM_DESCRIPTOR_INIT(bFirstInterface, int_ep, out_ep, in_ep, str_idx) \
/* Interface Associate */ \
0x08, /* bLength */ \
USB_DESCRIPTOR_TYPE_INTERFACE_ASSOCIATION, /* bDescriptorType */ \
bFirstInterface, /* bFirstInterface */ \
0x02, /* bInterfaceCount */ \
USB_DEVICE_CLASS_CDC, /* bFunctionClass */ \
CDC_ABSTRACT_CONTROL_MODEL, /* bFunctionSubClass */ \
CDC_COMMON_PROTOCOL_AT_COMMANDS, /* bFunctionProtocol */ \
0x00, /* iFunction */ \
0x09, /* bLength */ \
USB_DESCRIPTOR_TYPE_INTERFACE, /* bDescriptorType */ \
bFirstInterface, /* bInterfaceNumber */ \
0x00, /* bAlternateSetting */ \
0x01, /* bNumEndpoints */ \
USB_DEVICE_CLASS_CDC, /* bInterfaceClass */ \
CDC_ABSTRACT_CONTROL_MODEL, /* bInterfaceSubClass */ \
CDC_COMMON_PROTOCOL_AT_COMMANDS, /* bInterfaceProtocol */ \
str_idx, /* iInterface */ \
0x05, /* bLength */ \
CDC_CS_INTERFACE, /* bDescriptorType */ \
CDC_FUNC_DESC_HEADER, /* bDescriptorSubtype */ \
WBVAL(CDC_V1_10), /* bcdCDC */ \
0x05, /* bLength */ \
CDC_CS_INTERFACE, /* bDescriptorType */ \
CDC_FUNC_DESC_CALL_MANAGEMENT, /* bDescriptorSubtype */ \
bFirstInterface, /* bmCapabilities */ \
(uint8_t)(bFirstInterface + 1), /* bDataInterface */ \
0x04, /* bLength */ \
CDC_CS_INTERFACE, /* bDescriptorType */ \
CDC_FUNC_DESC_ABSTRACT_CONTROL_MANAGEMENT, /* bDescriptorSubtype */ \
0x02, /* bmCapabilities */ \
0x05, /* bLength */ \
CDC_CS_INTERFACE, /* bDescriptorType */ \
CDC_FUNC_DESC_UNION, /* bDescriptorSubtype */ \
bFirstInterface, /* bMasterInterface */ \
(uint8_t)(bFirstInterface + 1), /* bSlaveInterface0 */ \
0x07, /* bLength */ \
USB_DESCRIPTOR_TYPE_ENDPOINT, /* bDescriptorType */ \
int_ep, /* bEndpointAddress */ \
0x03, /* bmAttributes */ \
0x00, 0x02, /* wMaxPacketSize */ \
0x00, /* bInterval */ \
0x09, /* bLength */ \
USB_DESCRIPTOR_TYPE_INTERFACE, /* bDescriptorType */ \
(uint8_t)(bFirstInterface + 1), /* bInterfaceNumber */ \
0x00, /* bAlternateSetting */ \
0x02, /* bNumEndpoints */ \
CDC_DATA_INTERFACE_CLASS, /* bInterfaceClass */ \
0x00, /* bInterfaceSubClass */ \
0x00, /* bInterfaceProtocol */ \
0x00, /* iInterface */ \
0x07, /* bLength */ \
USB_DESCRIPTOR_TYPE_ENDPOINT, /* bDescriptorType */ \
out_ep, /* bEndpointAddress */ \
0x02, /* bmAttributes */ \
0x00, 0x02, /* wMaxPacketSize */ \
0x00, /* bInterval */ \
0x07, /* bLength */ \
USB_DESCRIPTOR_TYPE_ENDPOINT, /* bDescriptorType */ \
in_ep, /* bEndpointAddress */ \
0x02, /* bmAttributes */ \
0x00, 0x02, /* wMaxPacketSize */ \
0x00 /* bInterval */
#endif
// clang-format on
void usbd_cdc_add_acm_interface(usbd_class_t *class, usbd_interface_t *intf);
void usbd_cdc_acm_set_line_coding(uint32_t baudrate, uint8_t databits, uint8_t parity, uint8_t stopbits);
void usbd_cdc_acm_set_dtr(bool dtr);
void usbd_cdc_acm_set_rts(bool rts);
#ifdef __cplusplus
}
#endif
#endif /* USB_CDC_H_ */

View File

@@ -0,0 +1,286 @@
/**
* @file usbd_hid.c
* @brief
*
* Copyright (c) 2021 Bouffalolab team
*
* Licensed to the Apache Software Foundation (ASF) under one or more
* contributor license agreements. See the NOTICE file distributed with
* this work for additional information regarding copyright ownership. The
* ASF licenses this file to you under the Apache License, Version 2.0 (the
* "License"); you may not use this file except in compliance with the
* License. You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
* License for the specific language governing permissions and limitations
* under the License.
*
*/
#include "usbd_core.h"
#include "usbd_hid.h"
#define HID_STATE_IDLE 0
#define HID_STATE_BUSY 1
struct usbd_hid_cfg_private {
const uint8_t *hid_descriptor;
const uint8_t *hid_report_descriptor;
uint32_t hid_report_descriptor_len;
uint8_t current_intf_num;
uint8_t hid_state;
uint8_t report;
uint8_t idle_state;
uint8_t protocol;
uint8_t (*get_report_callback)(uint8_t report_id, uint8_t report_type);
void (*set_report_callback)(uint8_t report_id, uint8_t report_type, uint8_t *report, uint8_t report_len);
uint8_t (*get_idle_callback)(uint8_t report_id);
void (*set_idle_callback)(uint8_t report_id, uint8_t duration);
void (*set_protocol_callback)(uint8_t protocol);
uint8_t (*get_protocol_callback)(void);
usb_slist_t list;
} usbd_hid_cfg[4];
static usb_slist_t usbd_hid_class_head = USB_SLIST_OBJECT_INIT(usbd_hid_class_head);
static void usbd_hid_reset(void)
{
usb_slist_t *i;
usb_slist_for_each(i, &usbd_hid_class_head)
{
struct usbd_hid_cfg_private *hid_intf = usb_slist_entry(i, struct usbd_hid_cfg_private, list);
hid_intf->hid_state = HID_STATE_IDLE;
hid_intf->report = 0;
hid_intf->idle_state = 0;
hid_intf->protocol = 0;
}
}
int hid_custom_request_handler(struct usb_setup_packet *setup, uint8_t **data, uint32_t *len)
{
USBD_LOG_DBG("HID Custom request: "
"bRequest 0x%02x\r\n",
setup->bRequest);
if (REQTYPE_GET_DIR(setup->bmRequestType) == USB_REQUEST_DEVICE_TO_HOST &&
setup->bRequest == USB_REQUEST_GET_DESCRIPTOR) {
uint8_t value = (uint8_t)(setup->wValue >> 8);
uint8_t intf_num = (uint8_t)setup->wIndex;
struct usbd_hid_cfg_private *current_hid_intf = NULL;
usb_slist_t *i;
usb_slist_for_each(i, &usbd_hid_class_head)
{
struct usbd_hid_cfg_private *hid_intf = usb_slist_entry(i, struct usbd_hid_cfg_private, list);
if (hid_intf->current_intf_num == intf_num) {
current_hid_intf = hid_intf;
break;
}
}
if (current_hid_intf == NULL) {
return -2;
}
switch (value) {
case HID_DESCRIPTOR_TYPE_HID:
USBD_LOG_INFO("get HID Descriptor\r\n");
*data = (uint8_t *)current_hid_intf->hid_descriptor;
*len = current_hid_intf->hid_descriptor[0];
break;
case HID_DESCRIPTOR_TYPE_HID_REPORT:
USBD_LOG_INFO("get Report Descriptor\r\n");
*data = (uint8_t *)current_hid_intf->hid_report_descriptor;
*len = current_hid_intf->hid_report_descriptor_len;
break;
case HID_DESCRIPTOR_TYPE_HID_PHYSICAL:
USBD_LOG_INFO("get PHYSICAL Descriptor\r\n");
break;
default:
return -2;
}
return 0;
}
return -1;
}
int hid_class_request_handler(struct usb_setup_packet *setup, uint8_t **data, uint32_t *len)
{
USBD_LOG_DBG("HID Class request: "
"bRequest 0x%02x\r\n",
setup->bRequest);
struct usbd_hid_cfg_private *current_hid_intf = NULL;
usb_slist_t *i;
usb_slist_for_each(i, &usbd_hid_class_head)
{
struct usbd_hid_cfg_private *hid_intf = usb_slist_entry(i, struct usbd_hid_cfg_private, list);
uint8_t intf_num = (uint8_t)setup->wIndex;
if (hid_intf->current_intf_num == intf_num) {
current_hid_intf = hid_intf;
break;
}
}
if (current_hid_intf == NULL) {
return -2;
}
switch (setup->bRequest) {
case HID_REQUEST_GET_REPORT:
if (current_hid_intf->get_report_callback)
current_hid_intf->report = current_hid_intf->get_report_callback(setup->wValueL, setup->wValueH); /*report id ,report type*/
*data = (uint8_t *)&current_hid_intf->report;
*len = 1;
break;
case HID_REQUEST_GET_IDLE:
if (current_hid_intf->get_idle_callback)
current_hid_intf->idle_state = current_hid_intf->get_idle_callback(setup->wValueL);
*data = (uint8_t *)&current_hid_intf->idle_state;
*len = 1;
break;
case HID_REQUEST_GET_PROTOCOL:
if (current_hid_intf->get_protocol_callback)
current_hid_intf->protocol = current_hid_intf->get_protocol_callback();
*data = (uint8_t *)&current_hid_intf->protocol;
*len = 1;
break;
case HID_REQUEST_SET_REPORT:
if (current_hid_intf->set_report_callback)
current_hid_intf->set_report_callback(setup->wValueL, setup->wValueH, *data, *len); /*report id ,report type,report,report len*/
current_hid_intf->report = **data;
break;
case HID_REQUEST_SET_IDLE:
if (current_hid_intf->set_idle_callback)
current_hid_intf->set_idle_callback(setup->wValueL, setup->wIndexH); /*report id ,duration*/
current_hid_intf->idle_state = setup->wIndexH;
break;
case HID_REQUEST_SET_PROTOCOL:
if (current_hid_intf->set_protocol_callback)
current_hid_intf->set_protocol_callback(setup->wValueL); /*protocol*/
current_hid_intf->protocol = setup->wValueL;
break;
default:
USBD_LOG_WRN("Unhandled HID Class bRequest 0x%02x\r\n", setup->bRequest);
return -1;
}
return 0;
}
static void hid_notify_handler(uint8_t event, void *arg)
{
switch (event) {
case USB_EVENT_RESET:
usbd_hid_reset();
break;
default:
break;
}
}
void usbd_hid_reset_state(void)
{
// usbd_hid_cfg.hid_state = HID_STATE_IDLE;
}
void usbd_hid_send_report(uint8_t ep, uint8_t *data, uint8_t len)
{
// if(usbd_hid_cfg.hid_state == HID_STATE_IDLE)
// {
// usbd_hid_cfg.hid_state = HID_STATE_BUSY;
// usbd_ep_write(ep, data, len, NULL);
// }
}
void usbd_hid_descriptor_register(uint8_t intf_num, const uint8_t *desc)
{
// usbd_hid_cfg.hid_descriptor = desc;
}
void usbd_hid_report_descriptor_register(uint8_t intf_num, const uint8_t *desc, uint32_t desc_len)
{
usb_slist_t *i;
usb_slist_for_each(i, &usbd_hid_class_head)
{
struct usbd_hid_cfg_private *hid_intf = usb_slist_entry(i, struct usbd_hid_cfg_private, list);
if (hid_intf->current_intf_num == intf_num) {
hid_intf->hid_report_descriptor = desc;
hid_intf->hid_report_descriptor_len = desc_len;
return;
}
}
}
// clang-format off
void usbd_hid_set_request_callback( uint8_t intf_num,
uint8_t (*get_report_callback)(uint8_t report_id, uint8_t report_type),
void (*set_report_callback)(uint8_t report_id, uint8_t report_type, uint8_t *report, uint8_t report_len),
uint8_t (*get_idle_callback)(uint8_t report_id),
void (*set_idle_callback)(uint8_t report_id, uint8_t duration),
void (*set_protocol_callback)(uint8_t protocol),
uint8_t (*get_protocol_callback)(void))
// clang-format on
{
usb_slist_t *i;
usb_slist_for_each(i, &usbd_hid_class_head)
{
struct usbd_hid_cfg_private *hid_intf = usb_slist_entry(i, struct usbd_hid_cfg_private, list);
if (hid_intf->current_intf_num == intf_num) {
if (get_report_callback)
hid_intf->get_report_callback = get_report_callback;
if (set_report_callback)
hid_intf->set_report_callback = set_report_callback;
if (get_idle_callback)
hid_intf->get_idle_callback = get_idle_callback;
if (set_idle_callback)
hid_intf->set_idle_callback = set_idle_callback;
if (set_protocol_callback)
hid_intf->set_protocol_callback = set_protocol_callback;
if (get_protocol_callback)
hid_intf->get_protocol_callback = get_protocol_callback;
return;
}
}
}
void usbd_hid_add_interface(usbd_class_t *class, usbd_interface_t *intf)
{
static usbd_class_t *last_class = NULL;
static uint8_t hid_num = 0;
if (last_class != class) {
last_class = class;
usbd_class_register(class);
}
intf->class_handler = hid_class_request_handler;
intf->custom_handler = hid_custom_request_handler;
intf->vendor_handler = NULL;
intf->notify_handler = hid_notify_handler;
usbd_class_add_interface(class, intf);
usbd_hid_cfg[hid_num].current_intf_num = intf->intf_num;
usb_slist_add_tail(&usbd_hid_class_head, &usbd_hid_cfg[hid_num].list);
hid_num++;
}

View File

@@ -0,0 +1,360 @@
/**
* @file
* @brief USB Human Interface Device (HID) Class public header
*
* Header follows Device Class Definition for Human Interface Devices (HID)
* Version 1.11 document (HID1_11-1.pdf).
*/
#ifndef _USBD_HID_H_
#define _USBD_HID_H_
#ifdef __cplusplus
extern "C" {
#endif
/* HID Protocol Codes */
#define HID_PROTOCOL_NONE 0x00
#define HID_PROTOCOL_BOOT 0x00
#define HID_PROTOCOL_KEYBOARD 0x01
#define HID_PROTOCOL_REPORT 0x01
#define HID_PROTOCOL_MOUSE 0x02
/* HID Class Descriptor Types */
#define HID_DESCRIPTOR_TYPE_HID 0x21
#define HID_DESCRIPTOR_TYPE_HID_REPORT 0x22
#define HID_DESCRIPTOR_TYPE_HID_PHYSICAL 0x23
/* HID Class Specific Requests */
#define HID_REQUEST_GET_REPORT 0x01
#define HID_REQUEST_GET_IDLE 0x02
#define HID_REQUEST_GET_PROTOCOL 0x03
#define HID_REQUEST_SET_REPORT 0x09
#define HID_REQUEST_SET_IDLE 0x0A
#define HID_REQUEST_SET_PROTOCOL 0x0B
/* HID Report Types */
#define HID_REPORT_INPUT 0x01
#define HID_REPORT_OUTPUT 0x02
#define HID_REPORT_FEATURE 0x03
/* HID Report Definitions */
struct usb_hid_class_subdescriptor {
uint8_t bDescriptorType;
uint16_t wDescriptorLength;
} __packed;
struct usb_hid_descriptor {
uint8_t bLength;
uint8_t bDescriptorType;
uint16_t bcdHID;
uint8_t bCountryCode;
uint8_t bNumDescriptors;
/*
* Specification says at least one Class Descriptor needs to
* be present (Report Descriptor).
*/
struct usb_hid_class_subdescriptor subdesc[1];
} __packed;
/* HID Items types */
#define ITEM_MAIN 0x0
#define ITEM_GLOBAL 0x1
#define ITEM_LOCAL 0x2
/* HID Main Items tags */
#define ITEM_TAG_INPUT 0x8
#define ITEM_TAG_OUTPUT 0x9
#define ITEM_TAG_COLLECTION 0xA
#define ITEM_TAG_COLLECTION_END 0xC
/* HID Global Items tags */
#define ITEM_TAG_USAGE_PAGE 0x0
#define ITEM_TAG_LOGICAL_MIN 0x1
#define ITEM_TAG_LOGICAL_MAX 0x2
#define ITEM_TAG_REPORT_SIZE 0x7
#define ITEM_TAG_REPORT_ID 0x8
#define ITEM_TAG_REPORT_COUNT 0x9
/* HID Local Items tags */
#define ITEM_TAG_USAGE 0x0
#define ITEM_TAG_USAGE_MIN 0x1
#define ITEM_TAG_USAGE_MAX 0x2
#define HID_ITEM(bTag, bType, bSize) (((bTag & 0xF) << 4) | \
((bType & 0x3) << 2) | (bSize & 0x3))
#define HID_MAIN_ITEM(bTag, bSize) HID_ITEM(bTag, ITEM_MAIN, bSize)
#define HID_GLOBAL_ITEM(bTag, bSize) HID_ITEM(bTag, ITEM_GLOBAL, bSize)
#define HID_LOCAL_ITEM(bTag, bSize) HID_ITEM(bTag, ITEM_LOCAL, bSize)
#define HID_MI_COLLECTION HID_MAIN_ITEM(ITEM_TAG_COLLECTION, 1)
#define HID_MI_COLLECTION_END HID_MAIN_ITEM(ITEM_TAG_COLLECTION_END, \
0)
#define HID_MI_INPUT HID_MAIN_ITEM(ITEM_TAG_INPUT, 1)
#define HID_MI_OUTPUT HID_MAIN_ITEM(ITEM_TAG_OUTPUT, 1)
#define HID_GI_USAGE_PAGE HID_GLOBAL_ITEM(ITEM_TAG_USAGE_PAGE, 1)
#define HID_GI_LOGICAL_MIN(size) HID_GLOBAL_ITEM(ITEM_TAG_LOGICAL_MIN, \
size)
#define HID_GI_LOGICAL_MAX(size) HID_GLOBAL_ITEM(ITEM_TAG_LOGICAL_MAX, \
size)
#define HID_GI_REPORT_SIZE HID_GLOBAL_ITEM(ITEM_TAG_REPORT_SIZE, \
1)
#define HID_GI_REPORT_ID HID_GLOBAL_ITEM(ITEM_TAG_REPORT_ID, \
1)
#define HID_GI_REPORT_COUNT HID_GLOBAL_ITEM(ITEM_TAG_REPORT_COUNT, \
1)
#define HID_LI_USAGE HID_LOCAL_ITEM(ITEM_TAG_USAGE, 1)
#define HID_LI_USAGE_MIN(size) HID_LOCAL_ITEM(ITEM_TAG_USAGE_MIN, \
size)
#define HID_LI_USAGE_MAX(size) HID_LOCAL_ITEM(ITEM_TAG_USAGE_MAX, \
size)
/* Defined in Universal Serial Bus HID Usage Tables version 1.11 */
#define USAGE_GEN_DESKTOP 0x01
#define USAGE_GEN_KEYBOARD 0x07
#define USAGE_GEN_LEDS 0x08
#define USAGE_GEN_BUTTON 0x09
/* Generic Desktop Page usages */
#define USAGE_GEN_DESKTOP_UNDEFINED 0x00
#define USAGE_GEN_DESKTOP_POINTER 0x01
#define USAGE_GEN_DESKTOP_MOUSE 0x02
#define USAGE_GEN_DESKTOP_JOYSTICK 0x04
#define USAGE_GEN_DESKTOP_GAMEPAD 0x05
#define USAGE_GEN_DESKTOP_KEYBOARD 0x06
#define USAGE_GEN_DESKTOP_KEYPAD 0x07
#define USAGE_GEN_DESKTOP_X 0x30
#define USAGE_GEN_DESKTOP_Y 0x31
#define USAGE_GEN_DESKTOP_WHEEL 0x38
/* Collection types */
#define COLLECTION_PHYSICAL 0x00
#define COLLECTION_APPLICATION 0x01
/* Example HID report descriptors */
/**
* @brief Simple HID mouse report descriptor for n button mouse.
*
* @param bcnt Button count. Allowed values from 1 to 8.
*/
#define HID_MOUSE_REPORT_DESC(bcnt) \
{ \
/* USAGE_PAGE (Generic Desktop) */ \
HID_GI_USAGE_PAGE, USAGE_GEN_DESKTOP, /* USAGE (Mouse) */ \
HID_LI_USAGE, USAGE_GEN_DESKTOP_MOUSE, /* COLLECTION (Application) */ \
HID_MI_COLLECTION, COLLECTION_APPLICATION, /* USAGE (Pointer) */ \
HID_LI_USAGE, USAGE_GEN_DESKTOP_POINTER, /* COLLECTION (Physical) */ \
HID_MI_COLLECTION, COLLECTION_PHYSICAL, /* Bits used for button signalling */ /* USAGE_PAGE (Button) */ \
HID_GI_USAGE_PAGE, USAGE_GEN_BUTTON, /* USAGE_MINIMUM (Button 1) */ \
HID_LI_USAGE_MIN(1), 0x01, /* USAGE_MAXIMUM (Button bcnt) */ \
HID_LI_USAGE_MAX(1), bcnt, /* LOGICAL_MINIMUM (0) */ \
HID_GI_LOGICAL_MIN(1), 0x00, /* LOGICAL_MAXIMUM (1) */ \
HID_GI_LOGICAL_MAX(1), 0x01, /* REPORT_SIZE (1) */ \
HID_GI_REPORT_SIZE, 0x01, /* REPORT_COUNT (bcnt) */ \
HID_GI_REPORT_COUNT, bcnt, /* INPUT (Data,Var,Abs) */ \
HID_MI_INPUT, 0x02, /* Unused bits */ /* REPORT_SIZE (8 - bcnt) */ \
HID_GI_REPORT_SIZE, (8 - bcnt), /* REPORT_COUNT (1) */ \
HID_GI_REPORT_COUNT, 0x01, /* INPUT (Cnst,Ary,Abs) */ \
HID_MI_INPUT, 0x01, /* X and Y axis, scroll */ /* USAGE_PAGE (Generic Desktop) */ \
HID_GI_USAGE_PAGE, USAGE_GEN_DESKTOP, /* USAGE (X) */ \
HID_LI_USAGE, USAGE_GEN_DESKTOP_X, /* USAGE (Y) */ \
HID_LI_USAGE, USAGE_GEN_DESKTOP_Y, /* USAGE (WHEEL) */ \
HID_LI_USAGE, USAGE_GEN_DESKTOP_WHEEL, /* LOGICAL_MINIMUM (-127) */ \
HID_GI_LOGICAL_MIN(1), -127, /* LOGICAL_MAXIMUM (127) */ \
HID_GI_LOGICAL_MAX(1), 127, /* REPORT_SIZE (8) */ \
HID_GI_REPORT_SIZE, 0x08, /* REPORT_COUNT (3) */ \
HID_GI_REPORT_COUNT, 0x03, /* INPUT (Data,Var,Rel) */ \
HID_MI_INPUT, 0x06, /* END_COLLECTION */ \
HID_MI_COLLECTION_END, /* END_COLLECTION */ \
HID_MI_COLLECTION_END, \
}
/**
* @brief Simple HID keyboard report descriptor.
*/
#define HID_KEYBOARD_REPORT_DESC() \
{ \
/* USAGE_PAGE (Generic Desktop) */ \
HID_GI_USAGE_PAGE, USAGE_GEN_DESKTOP, /* USAGE (Keyboard) */ \
HID_LI_USAGE, USAGE_GEN_DESKTOP_KEYBOARD, /* COLLECTION (Application) */ \
HID_MI_COLLECTION, COLLECTION_APPLICATION, /* USAGE_PAGE (Keypad) */ \
HID_GI_USAGE_PAGE, USAGE_GEN_DESKTOP_KEYPAD, /* USAGE_MINIMUM (Keyboard LeftControl) */ \
HID_LI_USAGE_MIN(1), 0xE0, /* USAGE_MAXIMUM (Keyboard Right GUI) */ \
HID_LI_USAGE_MAX(1), 0xE7, /* LOGICAL_MINIMUM (0) */ \
HID_GI_LOGICAL_MIN(1), 0x00, /* LOGICAL_MAXIMUM (1) */ \
HID_GI_LOGICAL_MAX(1), 0x01, /* REPORT_SIZE (1) */ \
HID_GI_REPORT_SIZE, 0x01, /* REPORT_COUNT (8) */ \
HID_GI_REPORT_COUNT, 0x08, /* INPUT (Data,Var,Abs) */ \
HID_MI_INPUT, 0x02, /* REPORT_SIZE (8) */ \
HID_GI_REPORT_SIZE, 0x08, /* REPORT_COUNT (1) */ \
HID_GI_REPORT_COUNT, 0x01, /* INPUT (Cnst,Var,Abs) */ \
HID_MI_INPUT, 0x03, /* REPORT_SIZE (1) */ \
HID_GI_REPORT_SIZE, 0x01, /* REPORT_COUNT (5) */ \
HID_GI_REPORT_COUNT, 0x05, /* USAGE_PAGE (LEDs) */ \
HID_GI_USAGE_PAGE, USAGE_GEN_LEDS, /* USAGE_MINIMUM (Num Lock) */ \
HID_LI_USAGE_MIN(1), 0x01, /* USAGE_MAXIMUM (Kana) */ \
HID_LI_USAGE_MAX(1), 0x05, /* OUTPUT (Data,Var,Abs) */ \
HID_MI_OUTPUT, 0x02, /* REPORT_SIZE (3) */ \
HID_GI_REPORT_SIZE, 0x03, /* REPORT_COUNT (1) */ \
HID_GI_REPORT_COUNT, 0x01, /* OUTPUT (Cnst,Var,Abs) */ \
HID_MI_OUTPUT, 0x03, /* REPORT_SIZE (8) */ \
HID_GI_REPORT_SIZE, 0x08, /* REPORT_COUNT (6) */ \
HID_GI_REPORT_COUNT, 0x06, /* LOGICAL_MINIMUM (0) */ \
HID_GI_LOGICAL_MIN(1), 0x00, /* LOGICAL_MAXIMUM (101) */ \
HID_GI_LOGICAL_MAX(1), 0x65, /* USAGE_PAGE (Keypad) */ \
HID_GI_USAGE_PAGE, USAGE_GEN_DESKTOP_KEYPAD, /* USAGE_MINIMUM (Reserved) */ \
HID_LI_USAGE_MIN(1), 0x00, /* USAGE_MAXIMUM (Keyboard Application) */ \
HID_LI_USAGE_MAX(1), 0x65, /* INPUT (Data,Ary,Abs) */ \
HID_MI_INPUT, 0x00, /* END_COLLECTION */ \
HID_MI_COLLECTION_END, \
}
/**
* @brief HID keyboard button codes.
*/
enum hid_kbd_code {
HID_KEY_A = 4,
HID_KEY_B = 5,
HID_KEY_C = 6,
HID_KEY_D = 7,
HID_KEY_E = 8,
HID_KEY_F = 9,
HID_KEY_G = 10,
HID_KEY_H = 11,
HID_KEY_I = 12,
HID_KEY_J = 13,
HID_KEY_K = 14,
HID_KEY_L = 15,
HID_KEY_M = 16,
HID_KEY_N = 17,
HID_KEY_O = 18,
HID_KEY_P = 19,
HID_KEY_Q = 20,
HID_KEY_R = 21,
HID_KEY_S = 22,
HID_KEY_T = 23,
HID_KEY_U = 24,
HID_KEY_V = 25,
HID_KEY_W = 26,
HID_KEY_X = 27,
HID_KEY_Y = 28,
HID_KEY_Z = 29,
HID_KEY_1 = 30,
HID_KEY_2 = 31,
HID_KEY_3 = 32,
HID_KEY_4 = 33,
HID_KEY_5 = 34,
HID_KEY_6 = 35,
HID_KEY_7 = 36,
HID_KEY_8 = 37,
HID_KEY_9 = 38,
HID_KEY_0 = 39,
HID_KEY_ENTER = 40,
HID_KEY_ESC = 41,
HID_KEY_BACKSPACE = 42,
HID_KEY_TAB = 43,
HID_KEY_SPACE = 44,
HID_KEY_MINUS = 45,
HID_KEY_EQUAL = 46,
HID_KEY_LEFTBRACE = 47,
HID_KEY_RIGHTBRACE = 48,
HID_KEY_BACKSLASH = 49,
HID_KEY_HASH = 50, /* Non-US # and ~ */
HID_KEY_SEMICOLON = 51,
HID_KEY_APOSTROPHE = 52,
HID_KEY_GRAVE = 53,
HID_KEY_COMMA = 54,
HID_KEY_DOT = 55,
HID_KEY_SLASH = 56,
HID_KEY_CAPSLOCK = 57,
HID_KEY_F1 = 58,
HID_KEY_F2 = 59,
HID_KEY_F3 = 60,
HID_KEY_F4 = 61,
HID_KEY_F5 = 62,
HID_KEY_F6 = 63,
HID_KEY_F7 = 64,
HID_KEY_F8 = 65,
HID_KEY_F9 = 66,
HID_KEY_F10 = 67,
HID_KEY_F11 = 68,
HID_KEY_F12 = 69,
HID_KEY_SYSRQ = 70, /* PRINTSCREEN */
HID_KEY_SCROLLLOCK = 71,
HID_KEY_PAUSE = 72,
HID_KEY_INSERT = 73,
HID_KEY_HOME = 74,
HID_KEY_PAGEUP = 75,
HID_KEY_DELETE = 76,
HID_KEY_END = 77,
HID_KEY_PAGEDOWN = 78,
HID_KEY_RIGHT = 79,
HID_KEY_LEFT = 80,
HID_KEY_DOWN = 81,
HID_KEY_UP = 82,
HID_KEY_NUMLOCK = 83,
HID_KEY_KPSLASH = 84, /* NUMPAD DIVIDE */
HID_KEY_KPASTERISK = 85, /* NUMPAD MULTIPLY */
HID_KEY_KPMINUS = 86,
HID_KEY_KPPLUS = 87,
HID_KEY_KPENTER = 88,
HID_KEY_KP_1 = 89,
HID_KEY_KP_2 = 90,
HID_KEY_KP_3 = 91,
HID_KEY_KP_4 = 92,
HID_KEY_KP_5 = 93,
HID_KEY_KP_6 = 94,
HID_KEY_KP_7 = 95,
HID_KEY_KP_8 = 96,
HID_KEY_KP_9 = 97,
HID_KEY_KP_0 = 98,
};
/**
* @brief HID keyboard modifiers.
*/
enum hid_kbd_modifier {
HID_KBD_MODIFIER_NONE = 0x00,
HID_KBD_MODIFIER_LEFT_CTRL = 0x01,
HID_KBD_MODIFIER_LEFT_SHIFT = 0x02,
HID_KBD_MODIFIER_LEFT_ALT = 0x04,
HID_KBD_MODIFIER_LEFT_UI = 0x08,
HID_KBD_MODIFIER_RIGHT_CTRL = 0x10,
HID_KBD_MODIFIER_RIGHT_SHIFT = 0x20,
HID_KBD_MODIFIER_RIGHT_ALT = 0x40,
HID_KBD_MODIFIER_RIGHT_UI = 0x80,
};
/**
* @brief HID keyboard LEDs.
*/
enum hid_kbd_led {
HID_KBD_LED_NUM_LOCK = 0x01,
HID_KBD_LED_CAPS_LOCK = 0x02,
HID_KBD_LED_SCROLL_LOCK = 0x04,
HID_KBD_LED_COMPOSE = 0x08,
HID_KBD_LED_KANA = 0x10,
};
void usbd_hid_descriptor_register(uint8_t intf_num, const uint8_t *desc);
void usbd_hid_report_descriptor_register(uint8_t intf_num, const uint8_t *desc, uint32_t desc_len);
void usbd_hid_add_interface(usbd_class_t *class, usbd_interface_t *intf);
void usbd_hid_reset_state(void);
void usbd_hid_send_report(uint8_t ep, uint8_t *data, uint8_t len);
// clang-format off
void usbd_hid_set_request_callback( uint8_t intf_num,
uint8_t (*get_report_callback)(uint8_t report_id, uint8_t report_type),
void (*set_report_callback)(uint8_t report_id, uint8_t report_type, uint8_t *report, uint8_t report_len),
uint8_t (*get_idle_callback)(uint8_t report_id),
void (*set_idle_callback)(uint8_t report_id, uint8_t duration),
void (*set_protocol_callback)(uint8_t protocol),
uint8_t (*get_protocol_callback)(void));
// clang-format on
#ifdef __cplusplus
}
#endif
#endif /* _USB_HID_H_ */

File diff suppressed because it is too large Load Diff

View File

@@ -0,0 +1,109 @@
/**
* @file
* @brief USB Mass Storage Class public header
*
* Header follows the Mass Storage Class Specification
* (Mass_Storage_Specification_Overview_v1.4_2-19-2010.pdf) and
* Mass Storage Class Bulk-Only Transport Specification
* (usbmassbulk_10.pdf).
* Header is limited to Bulk-Only Transfer protocol.
*/
#ifndef _USBD_MSC_H__
#define _USBD_MSC_H__
#ifdef __cplusplus
extern "C" {
#endif
/* MSC Subclass Codes */
#define MSC_SUBCLASS_RBC 0x01
#define MSC_SUBCLASS_SFF8020I_MMC2 0x02
#define MSC_SUBCLASS_QIC157 0x03
#define MSC_SUBCLASS_UFI 0x04
#define MSC_SUBCLASS_SFF8070I 0x05
#define MSC_SUBCLASS_SCSI 0x06
/* MSC Protocol Codes */
#define MSC_PROTOCOL_CBI_INT 0x00
#define MSC_PROTOCOL_CBI_NOINT 0x01
#define MSC_PROTOCOL_BULK_ONLY 0x50
/* MSC Request Codes */
#define MSC_REQUEST_RESET 0xFF
#define MSC_REQUEST_GET_MAX_LUN 0xFE
/** MSC Command Block Wrapper (CBW) Signature */
#define MSC_CBW_Signature 0x43425355
/** Bulk-only Command Status Wrapper (CSW) Signature */
#define MSC_CSW_Signature 0x53425355
/** MSC Command Block Status Values */
#define CSW_STATUS_CMD_PASSED 0x00
#define CSW_STATUS_CMD_FAILED 0x01
#define CSW_STATUS_PHASE_ERROR 0x02
/*Length of template descriptor: 23 bytes*/
#define MSC_DESCRIPTOR_LEN (9 + 7 + 7)
// clang-format off
#ifndef SUPPORT_USB_HS
#define MSC_DESCRIPTOR_INIT(bFirstInterface, out_ep, in_ep,str_idx) \
/* Interface */ \
0x09, /* bLength */ \
USB_DESCRIPTOR_TYPE_INTERFACE, /* bDescriptorType */ \
bFirstInterface, /* bInterfaceNumber */ \
0x00, /* bAlternateSetting */ \
0x02, /* bNumEndpoints */ \
USB_DEVICE_CLASS_MASS_STORAGE, /* bInterfaceClass */ \
MSC_SUBCLASS_SCSI, /* bInterfaceSubClass */ \
MSC_PROTOCOL_BULK_ONLY, /* bInterfaceProtocol */ \
str_idx, /* iInterface */ \
0x07, /* bLength */ \
USB_DESCRIPTOR_TYPE_ENDPOINT, /* bDescriptorType */ \
out_ep, /* bEndpointAddress */ \
0x02, /* bmAttributes */ \
0x40, 0x00, /* wMaxPacketSize */ \
0x00, /* bInterval */ \
0x07, /* bLength */ \
USB_DESCRIPTOR_TYPE_ENDPOINT, /* bDescriptorType */ \
in_ep, /* bEndpointAddress */ \
0x02, /* bmAttributes */ \
0x40, 0x00, /* wMaxPacketSize */ \
0x00 /* bInterval */
#else
#define MSC_DESCRIPTOR_INIT(bFirstInterface, out_ep, in_ep,str_idx) \
/* Interface */ \
0x09, /* bLength */ \
USB_DESCRIPTOR_TYPE_INTERFACE, /* bDescriptorType */ \
bFirstInterface, /* bInterfaceNumber */ \
0x00, /* bAlternateSetting */ \
0x02, /* bNumEndpoints */ \
USB_DEVICE_CLASS_MASS_STORAGE, /* bInterfaceClass */ \
MSC_SUBCLASS_SCSI, /* bInterfaceSubClass */ \
MSC_PROTOCOL_BULK_ONLY, /* bInterfaceProtocol */ \
str_idx, /* iInterface */ \
0x07, /* bLength */ \
USB_DESCRIPTOR_TYPE_ENDPOINT, /* bDescriptorType */ \
out_ep, /* bEndpointAddress */ \
0x02, /* bmAttributes */ \
0x00, 0x02, /* wMaxPacketSize */ \
0x00, /* bInterval */ \
0x07, /* bLength */ \
USB_DESCRIPTOR_TYPE_ENDPOINT, /* bDescriptorType */ \
in_ep, /* bEndpointAddress */ \
0x02, /* bmAttributes */ \
0x00, 0x02, /* wMaxPacketSize */ \
0x00 /* bInterval */
#endif
// clang-format on
void usbd_msc_class_init(uint8_t out_ep, uint8_t in_ep);
void usbd_msc_get_cap(uint8_t lun, uint32_t *block_num, uint16_t *block_size);
int usbd_msc_sector_read(uint32_t sector, uint8_t *buffer, uint32_t length);
int usbd_msc_sector_write(uint32_t sector, uint8_t *buffer, uint32_t length);
#ifdef __cplusplus
}
#endif
#endif /* USB_MSC_H_ */

View File

@@ -0,0 +1,325 @@
/**
* @file
* @brief USB Mass Storage Class SCSI public header
*
* Header follows the Mass Storage Class Specification
* (Mass_Storage_Specification_Overview_v1.4_2-19-2010.pdf) and
* Mass Storage Class Bulk-Only Transport Specification
* (usbmassbulk_10.pdf).
* Header is limited to Bulk-Only Transfer protocol.
*/
#ifndef _USBD_SCSI_H_
#define _USBD_SCSI_H_
/* SCSI Commands */
#define SCSI_TEST_UNIT_READY 0x00
#define SCSI_REQUEST_SENSE 0x03
#define SCSI_FORMAT_UNIT 0x04
#define SCSI_INQUIRY 0x12
#define SCSI_MODE_SELECT6 0x15
#define SCSI_MODE_SENSE6 0x1A
#define SCSI_START_STOP_UNIT 0x1B
#define SCSI_SEND_DIAGNOSTIC 0x1D
#define SCSI_PREVENT_ALLOW_MEDIA_REMOVAL 0x1E
#define SCSI_READ_FORMAT_CAPACITIES 0x23
#define SCSI_READ_CAPACITY10 0x25
#define SCSI_READ10 0x28
#define SCSI_WRITE10 0x2A
#define SCSI_VERIFY10 0x2F
#define SCSI_SYNC_CACHE10 0x35
#define SCSI_READ12 0xA8
#define SCSI_WRITE12 0xAA
#define SCSI_MODE_SELECT10 0x55
#define SCSI_MODE_SENSE10 0x5A
#define SCSI_ATA_COMMAND_PASS_THROUGH16 0x85
#define SCSI_READ16 0x88
#define SCSI_WRITE16 0x8A
#define SCSI_VERIFY16 0x8F
#define SCSI_SYNC_CACHE16 0x91
#define SCSI_SERVICE_ACTION_IN16 0x9E
#define SCSI_READ_CAPACITY16 0x9E
#define SCSI_SERVICE_ACTION_OUT16 0x9F
#define SCSI_ATA_COMMAND_PASS_THROUGH12 0xA1
#define SCSI_REPORT_ID_INFO 0xA3
#define SCSI_READ12 0xA8
#define SCSI_SERVICE_ACTION_OUT12 0xA9
#define SCSI_SERVICE_ACTION_IN12 0xAB
#define SCSI_VERIFY12 0xAF
/* SCSI Sense Key */
#define SCSI_SENSE_NONE 0x00
#define SCSI_SENSE_RECOVERED_ERROR 0x01
#define SCSI_SENSE_NOT_READY 0x02
#define SCSI_SENSE_MEDIUM_ERROR 0x03
#define SCSI_SENSE_HARDWARE_ERROR 0x04
#define SCSI_SENSE_ILLEGAL_REQUEST 0x05
#define SCSI_SENSE_UNIT_ATTENTION 0x06
#define SCSI_SENSE_DATA_PROTECT 0x07
#define SCSI_SENSE_FIRMWARE_ERROR 0x08
#define SCSI_SENSE_ABORTED_COMMAND 0x0b
#define SCSI_SENSE_EQUAL 0x0c
#define SCSI_SENSE_VOLUME_OVERFLOW 0x0d
#define SCSI_SENSE_MISCOMPARE 0x0e
/* Additional Sense Code */
#define SCSI_ASC_INVALID_CDB 0x20U
#define SCSI_ASC_INVALID_FIELED_IN_COMMAND 0x24U
#define SCSI_ASC_PARAMETER_LIST_LENGTH_ERROR 0x1AU
#define SCSI_ASC_INVALID_FIELD_IN_PARAMETER_LIST 0x26U
#define SCSI_ASC_ADDRESS_OUT_OF_RANGE 0x21U
#define SCSI_ASC_MEDIUM_NOT_PRESENT 0x3AU
#define SCSI_ASC_MEDIUM_HAVE_CHANGED 0x28U
#define SCSI_ASC_WRITE_PROTECTED 0x27U
#define SCSI_ASC_UNRECOVERED_READ_ERROR 0x11U
#define SCSI_ASC_WRITE_FAULT 0x03U
#define READ_FORMAT_CAPACITY_DATA_LEN 0x0CU
#define READ_CAPACITY10_DATA_LEN 0x08U
#define REQUEST_SENSE_DATA_LEN 0x12U
#define STANDARD_INQUIRY_DATA_LEN 0x24U
#define MODE_SENSE6_DATA_LEN 0x17U
#define MODE_SENSE10_DATA_LEN 0x1BU
#define SCSI_MEDIUM_STATUS_UNLOCKED 0x00U
#define SCSI_MEDIUM_STATUS_LOCKED 0x01U
#define SCSI_MEDIUM_STATUS_EJECTED 0x02U
//--------------------------------------------------------------------+
// SCSI Primary Command (SPC-4)
//--------------------------------------------------------------------+
/// SCSI Test Unit Ready Command
typedef struct __packed {
uint8_t cmd_code; ///< SCSI OpCode for \ref SCSI_CMD_TEST_UNIT_READY
uint8_t lun; ///< Logical Unit
uint8_t reserved[3];
uint8_t control;
} scsi_test_unit_ready_cmd_t;
/// SCSI Inquiry Command
typedef struct __packed {
uint8_t cmd_code; ///< SCSI OpCode for \ref SCSI_CMD_INQUIRY
uint8_t reserved1;
uint8_t page_code;
uint8_t reserved2;
uint8_t alloc_length; ///< specifies the maximum number of bytes that USB host has allocated in the Data-In Buffer. An allocation length of zero specifies that no data shall be transferred.
uint8_t control;
} scsi_inquiry_cmd_t, scsi_request_sense_cmd_t;
/// SCSI Inquiry Response Data
typedef struct __packed {
uint8_t peripheral_device_type : 5;
uint8_t peripheral_qualifier : 3;
uint8_t : 7;
uint8_t is_removable : 1;
uint8_t version;
uint8_t response_data_format : 4;
uint8_t hierarchical_support : 1;
uint8_t normal_aca : 1;
uint8_t : 2;
uint8_t additional_length;
uint8_t protect : 1;
uint8_t : 2;
uint8_t third_party_copy : 1;
uint8_t target_port_group_support : 2;
uint8_t access_control_coordinator : 1;
uint8_t scc_support : 1;
uint8_t addr16 : 1;
uint8_t : 3;
uint8_t multi_port : 1;
uint8_t : 1; // vendor specific
uint8_t enclosure_service : 1;
uint8_t : 1;
uint8_t : 1; // vendor specific
uint8_t cmd_que : 1;
uint8_t : 2;
uint8_t sync : 1;
uint8_t wbus16 : 1;
uint8_t : 2;
uint8_t vendor_id[8]; ///< 8 bytes of ASCII data identifying the vendor of the product.
uint8_t product_id[16]; ///< 16 bytes of ASCII data defined by the vendor.
uint8_t product_rev[4]; ///< 4 bytes of ASCII data defined by the vendor.
} scsi_inquiry_resp_t;
typedef struct __packed {
uint8_t response_code : 7; ///< 70h - current errors, Fixed Format 71h - deferred errors, Fixed Format
uint8_t valid : 1;
uint8_t reserved;
uint8_t sense_key : 4;
uint8_t : 1;
uint8_t ili : 1; ///< Incorrect length indicator
uint8_t end_of_medium : 1;
uint8_t filemark : 1;
uint32_t information;
uint8_t add_sense_len;
uint32_t command_specific_info;
uint8_t add_sense_code;
uint8_t add_sense_qualifier;
uint8_t field_replaceable_unit_code;
uint8_t sense_key_specific[3]; ///< sense key specific valid bit is bit 7 of key[0], aka MSB in Big Endian layout
} scsi_sense_fixed_resp_t;
typedef struct __packed {
uint8_t cmd_code; ///< SCSI OpCode for \ref SCSI_CMD_MODE_SENSE_6
uint8_t : 3;
uint8_t disable_block_descriptor : 1;
uint8_t : 4;
uint8_t page_code : 6;
uint8_t page_control : 2;
uint8_t subpage_code;
uint8_t alloc_length;
uint8_t control;
} scsi_mode_sense6_cmd_t;
// This is only a Mode parameter header(6).
typedef struct __packed {
uint8_t data_len;
uint8_t medium_type;
uint8_t reserved : 7;
bool write_protected : 1;
uint8_t block_descriptor_len;
} scsi_mode_sense6_resp_t;
typedef struct
{
uint8_t cmd_code;
uint8_t reserved1 : 3;
uint8_t disable_block_descriptor : 1;
uint8_t long_LBA : 1;
uint8_t reserved2 : 3;
uint8_t page_code : 6;
uint8_t page_control : 2;
uint8_t subpage_code;
uint8_t reserved3;
uint8_t reserved4;
uint8_t reserved5;
uint8_t length[2];
uint8_t control;
} scsi_mode_sense_10_cmd_t;
typedef struct
{
uint8_t mode_data_length_high;
uint8_t mode_data_length_low;
uint8_t medium_type;
uint8_t reserved1 : 4;
uint8_t DPO_FUA : 1; /**< [Disable Page Out] and [Force Unit Access] in the SCSI_READ10 command is valid or not */
uint8_t reserved2 : 2;
uint8_t write_protect : 1;
uint8_t long_LBA : 1;
uint8_t reserved3 : 7;
uint8_t reserved4;
uint8_t block_desc_length[2];
} scsi_mode_10_resp_t;
typedef struct __packed {
uint8_t cmd_code; ///< SCSI OpCode for \ref SCSI_CMD_PREVENT_ALLOW_MEDIUM_REMOVAL
uint8_t reserved[3];
uint8_t prohibit_removal;
uint8_t control;
} scsi_prevent_allow_medium_removal_t;
typedef struct __packed {
uint8_t cmd_code;
uint8_t immded : 1;
uint8_t : 7;
uint8_t TU_RESERVED;
uint8_t power_condition_mod : 4;
uint8_t : 4;
uint8_t start : 1;
uint8_t load_eject : 1;
uint8_t no_flush : 1;
uint8_t : 1;
uint8_t power_condition : 4;
uint8_t control;
} scsi_start_stop_unit_cmd_t;
//--------------------------------------------------------------------+
// SCSI MMC
//--------------------------------------------------------------------+
/// SCSI Read Format Capacity: Write Capacity
typedef struct __packed {
uint8_t cmd_code;
uint8_t reserved[6];
uint16_t alloc_length;
uint8_t control;
} scsi_read_format_capacity_cmd_t;
typedef struct __packed {
uint8_t reserved[3];
uint8_t list_length; /// must be 8*n, length in bytes of formattable capacity descriptor followed it.
uint32_t block_num; /// Number of Logical Blocks
uint8_t descriptor_type; // 00: reserved, 01 unformatted media , 10 Formatted media, 11 No media present
uint8_t reserved2;
uint16_t block_size_u16;
} scsi_read_format_capacity_resp_t;
//--------------------------------------------------------------------+
// SCSI Block Command (SBC-3)
// NOTE: All data in SCSI command are in Big Endian
//--------------------------------------------------------------------+
/// SCSI Read Capacity 10 Command: Read Capacity
typedef struct __packed {
uint8_t cmd_code; ///< SCSI OpCode for \ref SCSI_CMD_READ_CAPACITY_10
uint8_t reserved1;
uint32_t lba; ///< The first Logical Block Address (LBA) accessed by this command
uint16_t reserved2;
uint8_t partial_medium_indicator;
uint8_t control;
} scsi_read_capacity10_cmd_t;
/// SCSI Read Capacity 10 Response Data
typedef struct
{
uint32_t last_lba; ///< The last Logical Block Address of the device
uint32_t block_size; ///< Block size in bytes
} scsi_read_capacity10_resp_t;
/// SCSI Read 10 Command
typedef struct __packed {
uint8_t cmd_code; ///< SCSI OpCode
uint8_t reserved; // has LUN according to wiki
uint32_t lba; ///< The first Logical Block Address (LBA) accessed by this command
uint8_t reserved2;
uint16_t block_count; ///< Number of Blocks used by this command
uint8_t control;
} scsi_read10_t, scsi_write10_t, scsi_read_write_10_t;
#endif /* ZEPHYR_INCLUDE_USB_CLASS_USB_CDC_H_ */

View File

@@ -0,0 +1,134 @@
/**
* @file usbd_video.c
*
* Copyright (c) 2021 Bouffalolab team
*
* Licensed to the Apache Software Foundation (ASF) under one or more
* contributor license agreements. See the NOTICE file distributed with
* this work for additional information regarding copyright ownership. The
* ASF licenses this file to you under the Apache License, Version 2.0 (the
* "License"); you may not use this file except in compliance with the
* License. You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
* License for the specific language governing permissions and limitations
* under the License.
*
*/
#include "usbd_core.h"
#include "usbd_video.h"
extern struct video_probe_and_commit_controls probe;
extern struct video_probe_and_commit_controls commit;
int video_class_request_handler(struct usb_setup_packet *setup, uint8_t **data, uint32_t *len)
{
USBD_LOG_DBG("Video Class request: "
"bRequest 0x%02x\r\n",
setup->bRequest);
switch (setup->bRequest) {
case VIDEO_REQUEST_SET_CUR:
if (setup->wValue == 256) {
memcpy((uint8_t *)&probe, *data, setup->wLength);
} else if (setup->wValue == 512) {
memcpy((uint8_t *)&commit, *data, setup->wLength);
}
break;
case VIDEO_REQUEST_GET_CUR:
if (setup->wValue == 256) {
*data = (uint8_t *)&probe;
} else if (setup->wValue == 512) {
*data = (uint8_t *)&commit;
}
break;
case VIDEO_REQUEST_GET_MIN:
if (setup->wValue == 256) {
*data = (uint8_t *)&probe;
} else if (setup->wValue == 512) {
*data = (uint8_t *)&commit;
}
break;
case VIDEO_REQUEST_GET_MAX:
if (setup->wValue == 256) {
*data = (uint8_t *)&probe;
} else if (setup->wValue == 512) {
*data = (uint8_t *)&commit;
}
break;
case VIDEO_REQUEST_GET_RES:
break;
case VIDEO_REQUEST_GET_LEN:
break;
case VIDEO_REQUEST_GET_INFO:
break;
case VIDEO_REQUEST_GET_DEF:
if (setup->wLength == 256) {
*data = (uint8_t *)&probe;
} else if (setup->wLength == 512) {
*data = (uint8_t *)&commit;
}
break;
default:
USBD_LOG_WRN("Unhandled Video Class bRequest 0x%02x\r\n", setup->bRequest);
return -1;
}
return 0;
}
void video_notify_handler(uint8_t event, void *arg)
{
switch (event) {
case USB_EVENT_RESET:
break;
case USB_EVENT_SOF:
usbd_video_sof_callback();
break;
case USB_EVENT_SET_INTERFACE:
usbd_video_set_interface_callback(((uint8_t *)arg)[3]);
break;
default:
break;
}
}
void usbd_video_add_interface(usbd_class_t *class, usbd_interface_t *intf)
{
static usbd_class_t *last_class = NULL;
if (last_class != class) {
last_class = class;
usbd_class_register(class);
}
intf->class_handler = video_class_request_handler;
intf->custom_handler = NULL;
intf->vendor_handler = NULL;
intf->notify_handler = video_notify_handler;
usbd_class_add_interface(class, intf);
}

View File

@@ -0,0 +1,821 @@
/**
* @file
* @brief USB Video Device Class public header
*
* Header follows below documentation:
* - USB Device Class Definition for Video Devices UVC 1.5 Class specification.pdf
*/
#ifndef _USBD_VIDEO_H_
#define _USBD_VIDEO_H_
#ifdef __cplusplus
extern "C" {
#endif
#define USB_DEVICE_VIDEO_CLASS_VERSION_1_5 0
/*! @brief Video device subclass code */
#define VIDEO_SC_UNDEFINED 0x00U
#define VIDEO_SC_VIDEOCONTROL 0x01U
#define VIDEO_SC_VIDEOSTREAMING 0x02U
#define VIDEO_SC_VIDEO_INTERFACE_COLLECTION 0x03U
/*! @brief Video device protocol code */
#define VIDEO_PC_PROTOCOL_UNDEFINED 0x00U
#define VIDEO_PC_PROTOCOL_15 0x01U
/*! @brief Video device class-specific descriptor type */
#define VIDEO_CS_UNDEFINED_DESCRIPTOR_TYPE 0x20U
#define VIDEO_CS_DEVICE_DESCRIPTOR_TYPE 0x21U
#define VIDEO_CS_CONFIGURATION_DESCRIPTOR_TYPE 0x22U
#define VIDEO_CS_STRING_DESCRIPTOR_TYPE 0x23U
#define VIDEO_CS_INTERFACE_DESCRIPTOR_TYPE 0x24U
#define VIDEO_CS_ENDPOINT_DESCRIPTOR_TYPE 0x25U
/*! @brief Video device class-specific VC interface descriptor subtype */
#define VIDEO_VC_DESCRIPTOR_UNDEFINED_DESCRIPTOR_SUBTYPE 0x00U
#define VIDEO_VC_HEADER_DESCRIPTOR_SUBTYPE 0x01U
#define VIDEO_VC_INPUT_TERMINAL_DESCRIPTOR_SUBTYPE 0x02U
#define VIDEO_VC_OUTPUT_TERMINAL_DESCRIPTOR_SUBTYPE 0x03U
#define VIDEO_VC_SELECTOR_UNIT_DESCRIPTOR_SUBTYPE 0x04U
#define VIDEO_VC_PROCESSING_UNIT_DESCRIPTOR_SUBTYPE 0x05U
#define VIDEO_VC_EXTENSION_UNIT_DESCRIPTOR_SUBTYPE 0x06U
#define VIDEO_VC_ENCODING_UNIT_DESCRIPTOR_SUBTYPE 0x07U
/*! @brief Video device class-specific VS interface descriptor subtype */
#define VIDEO_VS_UNDEFINED_DESCRIPTOR_SUBTYPE 0x00U
#define VIDEO_VS_INPUT_HEADER_DESCRIPTOR_SUBTYPE 0x01U
#define VIDEO_VS_OUTPUT_HEADER_DESCRIPTOR_SUBTYPE 0x02U
#define VIDEO_VS_STILL_IMAGE_FRAME_DESCRIPTOR_SUBTYPE 0x03U
#define VIDEO_VS_FORMAT_UNCOMPRESSED_DESCRIPTOR_SUBTYPE 0x04U
#define VIDEO_VS_FRAME_UNCOMPRESSED_DESCRIPTOR_SUBTYPE 0x05U
#define VIDEO_VS_FORMAT_MJPEG_DESCRIPTOR_SUBTYPE 0x06U
#define VIDEO_VS_FRAME_MJPEG_DESCRIPTOR_SUBTYPE 0x07U
#define VIDEO_VS_FORMAT_MPEG2TS_DESCRIPTOR_SUBTYPE 0x0AU
#define VIDEO_VS_FORMAT_DV_DESCRIPTOR_SUBTYPE 0x0CU
#define VIDEO_VS_COLORFORMAT_DESCRIPTOR_SUBTYPE 0x0DU
#define VIDEO_VS_FORMAT_FRAME_BASED_DESCRIPTOR_SUBTYPE 0x10U
#define VIDEO_VS_FRAME_FRAME_BASED_DESCRIPTOR_SUBTYPE 0x11U
#define VIDEO_VS_FORMAT_STREAM_BASED_DESCRIPTOR_SUBTYPE 0x12U
#define VIDEO_VS_FORMAT_H264_DESCRIPTOR_SUBTYPE 0x13U
#define VIDEO_VS_FRAME_H264_DESCRIPTOR_SUBTYPE 0x14U
#define VIDEO_VS_FORMAT_H264_SIMULCAST_DESCRIPTOR_SUBTYPE 0x15U
#define VIDEO_VS_FORMAT_VP8_DESCRIPTOR_SUBTYPE 0x16U
#define VIDEO_VS_FRAME_VP8_DESCRIPTOR_SUBTYPE 0x17U
#define VIDEO_VS_FORMAT_VP8_SIMULCAST_DESCRIPTOR_SUBTYPE 0x18U
/*! @brief Video device class-specific VC endpoint descriptor subtype */
#define VIDEO_EP_UNDEFINED_DESCRIPTOR_SUBTYPE 0x00U
#define VIDEO_EP_GENERAL_DESCRIPTOR_SUBTYPE 0x01U
#define VIDEO_EP_ENDPOINT_DESCRIPTOR_SUBTYPE 0x02U
#define VIDEO_EP_INTERRUPT_DESCRIPTOR_SUBTYPE 0x03U
/*! @brief Video device class-specific request code */
#define VIDEO_REQUEST_UNDEFINED 0x00U
#define VIDEO_REQUEST_SET_CUR 0x01U
#define VIDEO_REQUEST_SET_CUR_ALL 0x11U
#define VIDEO_REQUEST_GET_CUR 0x81U
#define VIDEO_REQUEST_GET_MIN 0x82U
#define VIDEO_REQUEST_GET_MAX 0x83U
#define VIDEO_REQUEST_GET_RES 0x84U
#define VIDEO_REQUEST_GET_LEN 0x85U
#define VIDEO_REQUEST_GET_INFO 0x86U
#define VIDEO_REQUEST_GET_DEF 0x87U
#define VIDEO_REQUEST_GET_CUR_ALL 0x91U
#define VIDEO_REQUEST_GET_MIN_ALL 0x92U
#define VIDEO_REQUEST_GET_MAX_ALL 0x93U
#define VIDEO_REQUEST_GET_RES_ALL 0x94U
#define VIDEO_REQUEST_GET_DEF_ALL 0x97U
/*! @brief Video device class-specific VideoControl interface control selector */
#define VIDEO_VC_CONTROL_UNDEFINED 0x00U
#define VIDEO_VC_VIDEO_POWER_MODE_CONTROL 0x01U
#define VIDEO_VC_REQUEST_ERROR_CODE_CONTROL 0x02U
/*! @brief Video device class-specific Terminal control selector */
#define VIDEO_TE_CONTROL_UNDEFINED 0x00U
/*! @brief Video device class-specific Selector Unit control selector */
#define VIDEO_SU_CONTROL_UNDEFINED 0x00U
#define VIDEO_SU_INPUT_SELECT_CONTROL 0x01U
/*! @brief Video device class-specific Camera Terminal control selector */
#define VIDEO_CT_CONTROL_UNDEFINED 0x00U
#define VIDEO_CT_SCANNING_MODE_CONTROL 0x01U
#define VIDEO_CT_AE_MODE_CONTROL 0x02U
#define VIDEO_CT_AE_PRIORITY_CONTROL 0x03U
#define VIDEO_CT_EXPOSURE_TIME_ABSOLUTE_CONTROL 0x04U
#define VIDEO_CT_EXPOSURE_TIME_RELATIVE_CONTROL 0x05U
#define VIDEO_CT_FOCUS_ABSOLUTE_CONTROL 0x06U
#define VIDEO_CT_FOCUS_RELATIVE_CONTROL 0x07U
#define VIDEO_CT_FOCUS_AUTO_CONTROL 0x08U
#define VIDEO_CT_IRIS_ABSOLUTE_CONTROL 0x09U
#define VIDEO_CT_IRIS_RELATIVE_CONTROL 0x0AU
#define VIDEO_CT_ZOOM_ABSOLUTE_CONTROL 0x0BU
#define VIDEO_CT_ZOOM_RELATIVE_CONTROL 0x0CU
#define VIDEO_CT_PANTILT_ABSOLUTE_CONTROL 0x0DU
#define VIDEO_CT_PANTILT_RELATIVE_CONTROL 0x0EU
#define VIDEO_CT_ROLL_ABSOLUTE_CONTROL 0x0FU
#define VIDEO_CT_ROLL_RELATIVE_CONTROL 0x10U
#define VIDEO_CT_PRIVACY_CONTROL 0x11U
#define VIDEO_CT_FOCUS_SIMPLE_CONTROL 0x12U
#define VIDEO_CT_WINDOW_CONTROL 0x13U
#define VIDEO_CT_REGION_OF_INTEREST_CONTROL 0x14U
/*! @brief Video device class-specific Processing Unit control selector */
#define VIDEO_PU_CONTROL_UNDEFINED 0x00U
#define VIDEO_PU_BACKLIGHT_COMPENSATION_CONTROL 0x01U
#define VIDEO_PU_BRIGHTNESS_CONTROL 0x02U
#define VIDEO_PU_CONTRAST_CONTROL 0x03U
#define VIDEO_PU_GAIN_CONTROL 0x04U
#define VIDEO_PU_POWER_LINE_FREQUENCY_CONTROL 0x05U
#define VIDEO_PU_HUE_CONTROL 0x06U
#define VIDEO_PU_SATURATION_CONTROL 0x07U
#define VIDEO_PU_SHARPNESS_CONTROL 0x08U
#define VIDEO_PU_GAMMA_CONTROL 0x09U
#define VIDEO_PU_WHITE_BALANCE_TEMPERATURE_CONTROL 0x0AU
#define VIDEO_PU_WHITE_BALANCE_TEMPERATURE_AUTO_CONTROL 0x0BU
#define VIDEO_PU_WHITE_BALANCE_COMPONENT_CONTROL 0x0CU
#define VIDEO_PU_WHITE_BALANCE_COMPONENT_AUTO_CONTROL 0x0DU
#define VIDEO_PU_DIGITAL_MULTIPLIER_CONTROL 0x0EU
#define VIDEO_PU_DIGITAL_MULTIPLIER_LIMIT_CONTROL 0x0FU
#define VIDEO_PU_HUE_AUTO_CONTROL 0x10U
#define VIDEO_PU_ANALOG_VIDEO_STANDARD_CONTROL 0x11U
#define VIDEO_PU_ANALOG_LOCK_STATUS_CONTROL 0x12U
#define VIDEO_PU_CONTRAST_AUTO_CONTROL 0x13U
/*! @brief Video device class-specific Encoding Unit control selector */
#define VIDEO_EU_CONTROL_UNDEFINED 0x00U
#define VIDEO_EU_SELECT_LAYER_CONTROL 0x01U
#define VIDEO_EU_PROFILE_TOOLSET_CONTROL 0x02U
#define VIDEO_EU_VIDEO_RESOLUTION_CONTROL 0x03U
#define VIDEO_EU_MIN_FRAME_INTERVAL_CONTROL 0x04U
#define VIDEO_EU_SLICE_MODE_CONTROL 0x05U
#define VIDEO_EU_RATE_CONTROL_MODE_CONTROL 0x06U
#define VIDEO_EU_AVERAGE_BITRATE_CONTROL 0x07U
#define VIDEO_EU_CPB_SIZE_CONTROL 0x08U
#define VIDEO_EU_PEAK_BIT_RATE_CONTROL 0x09U
#define VIDEO_EU_QUANTIZATION_PARAMS_CONTROL 0x0AU
#define VIDEO_EU_SYNC_REF_FRAME_CONTROL 0x0BU
#define VIDEO_EU_LTR_BUFFER_ CONTROL0x0CU
#define VIDEO_EU_LTR_PICTURE_CONTROL 0x0DU
#define VIDEO_EU_LTR_VALIDATION_CONTROL 0x0EU
#define VIDEO_EU_LEVEL_IDC_LIMIT_CONTROL 0x0FU
#define VIDEO_EU_SEI_PAYLOADTYPE_CONTROL 0x10U
#define VIDEO_EU_QP_RANGE_CONTROL 0x11U
#define VIDEO_EU_PRIORITY_CONTROL 0x12U
#define VIDEO_EU_START_OR_STOP_LAYER_CONTROL 0x13U
#define VIDEO_EU_ERROR_RESILIENCY_CONTROL 0x14U
/*! @brief Video device class-specific Extension Unit control selector */
#define VIDEO_XU_CONTROL_UNDEFINED 0x00U
/*! @brief Video device class-specific VideoStreaming Interface control selector */
#define VIDEO_VS_CONTROL_UNDEFINED 0x00U
#define VIDEO_VS_PROBE_CONTROL 0x01U
#define VIDEO_VS_COMMIT_CONTROL 0x02U
#define VIDEO_VS_STILL_PROBE_CONTROL 0x03U
#define VIDEO_VS_STILL_COMMIT_CONTROL 0x04U
#define VIDEO_VS_STILL_IMAGE_TRIGGER_CONTROL 0x05U
#define VIDEO_VS_STREAM_ERROR_CODE_CONTROL 0x06U
#define VIDEO_VS_GENERATE_KEY_FRAME_CONTROL 0x07U
#define VIDEO_VS_UPDATE_FRAME_SEGMENT_CONTROL 0x08U
#define VIDEO_VS_SYNCH_DELAY_CONTROL 0x09U
/*! @}*/
/*!
* @name USB Video class terminal types
* @{
*/
/*! @brief Video device USB terminal type */
#define VIDEO_TT_VENDOR_SPECIFIC 0x0100U
#define VIDEO_TT_STREAMING 0x0101U
/*! @brief Video device input terminal type */
#define VIDEO_ITT_VENDOR_SPECIFIC 0x0200U
#define VIDEO_ITT_CAMERA 0x0201U
#define VIDEO_ITT_MEDIA_TRANSPORT_INPUT 0x0202U
/*! @brief Video device output terminal type */
#define VIDEO_OTT_VENDOR_SPECIFIC 0x0300U
#define VIDEO_OTT_DISPLAY 0x0301U
#define VIDEO_OTT_MEDIA_TRANSPORT_OUTPUT 0x0302U
/*! @brief Video device external terminal type */
#define VIDEO_ET_VENDOR_SPECIFIC 0x0400U
#define VIDEO_ET_COMPOSITE_CONNECTOR 0x0401U
#define VIDEO_ET_SVIDEO_CONNECTOR 0x0402U
#define VIDEO_ET_COMPONENT_CONNECTOR 0x0403U
/*! @}*/
/*!
* @name USB Video class setup request types
* @{
*/
/*! @brief Video device class setup request set type */
#define VIDEO_SET_REQUEST_INTERFACE 0x21U
#define VIDEO_SET_REQUEST_ENDPOINT 0x22U
/*! @brief Video device class setup request get type */
#define VIDEO_GET_REQUEST_INTERFACE 0xA1U
#define VIDEO_GET_REQUEST_ENDPOINT 0xA2U
/*! @}*/
/*! @brief Video device still image trigger control */
#define VIDEO_STILL_IMAGE_TRIGGER_NORMAL_OPERATION 0x00U
#define VIDEO_STILL_IMAGE_TRIGGER_TRANSMIT_STILL_IMAGE 0x01U
#define VIDEO_STILL_IMAGE_TRIGGER_TRANSMIT_STILL_IMAGE_VS_DEDICATED_BULK_PIPE 0x02U
#define VIDEO_STILL_IMAGE_TRIGGER_ABORT_STILL_IMAGE_TRANSMISSION 0x03U
/*!
* @name USB Video device class-specific request commands
* @{
*/
/*! @brief Video device class-specific request GET CUR COMMAND */
#define VIDEO_GET_CUR_VC_POWER_MODE_CONTROL 0x8101U
#define VIDEO_GET_CUR_VC_ERROR_CODE_CONTROL 0x8102U
#define VIDEO_GET_CUR_PU_BACKLIGHT_COMPENSATION_CONTROL 0x8121U
#define VIDEO_GET_CUR_PU_BRIGHTNESS_CONTROL 0x8122U
#define VIDEO_GET_CUR_PU_CONTRACT_CONTROL 0x8123U
#define VIDEO_GET_CUR_PU_GAIN_CONTROL 0x8124U
#define VIDEO_GET_CUR_PU_POWER_LINE_FREQUENCY_CONTROL 0x8125U
#define VIDEO_GET_CUR_PU_HUE_CONTROL 0x8126U
#define VIDEO_GET_CUR_PU_SATURATION_CONTROL 0x8127U
#define VIDEO_GET_CUR_PU_SHARRNESS_CONTROL 0x8128U
#define VIDEO_GET_CUR_PU_GAMMA_CONTROL 0x8129U
#define VIDEO_GET_CUR_PU_WHITE_BALANCE_TEMPERATURE_CONTROL 0x812AU
#define VIDEO_GET_CUR_PU_WHITE_BALANCE_TEMPERATURE_AUTO_CONTROL 0x812BU
#define VIDEO_GET_CUR_PU_WHITE_BALANCE_COMPONENT_CONTROL 0x812CU
#define VIDEO_GET_CUR_PU_WHITE_BALANCE_COMPONENT_AUTO_CONTROL 0x812DU
#define VIDEO_GET_CUR_PU_DIGITAL_MULTIPLIER_CONTROL 0x812EU
#define VIDEO_GET_CUR_PU_DIGITAL_MULTIPLIER_LIMIT_CONTROL 0x812FU
#define VIDEO_GET_CUR_PU_HUE_AUTO_CONTROL 0x8130U
#define VIDEO_GET_CUR_PU_ANALOG_VIDEO_STANDARD_CONTROL 0x8131U
#define VIDEO_GET_CUR_PU_ANALOG_LOCK_STATUS_CONTROL 0x8132U
#if defined(USB_DEVICE_VIDEO_CLASS_VERSION_1_5) && USB_DEVICE_VIDEO_CLASS_VERSION_1_5
#define VIDEO_GET_CUR_PU_CONTRAST_AUTO_CONTROL 0x8133U
#endif
#define VIDEO_GET_CUR_CT_SCANNING_MODE_CONTROL 0x8141U
#define VIDEO_GET_CUR_CT_AE_MODE_CONTROL 0x8142U
#define VIDEO_GET_CUR_CT_AE_PRIORITY_CONTROL 0x8143U
#define VIDEO_GET_CUR_CT_EXPOSURE_TIME_ABSOLUTE_CONTROL 0x8144U
#define VIDEO_GET_CUR_CT_EXPOSURE_TIME_RELATIVE_CONTROL 0x8145U
#define VIDEO_GET_CUR_CT_FOCUS_ABSOLUTE_CONTROL 0x8146U
#define VIDEO_GET_CUR_CT_FOCUS_RELATIVE_CONTROL 0x8147U
#define VIDEO_GET_CUR_CT_FOCUS_AUTO_CONTROL 0x8148U
#define VIDEO_GET_CUR_CT_IRIS_ABSOLUTE_CONTROL 0x8149U
#define VIDEO_GET_CUR_CT_IRIS_RELATIVE_CONTROL 0x814AU
#define VIDEO_GET_CUR_CT_ZOOM_ABSOLUTE_CONTROL 0x814BU
#define VIDEO_GET_CUR_CT_ZOOM_RELATIVE_CONTROL 0x814CU
#define VIDEO_GET_CUR_CT_PANTILT_ABSOLUTE_CONTROL 0x814DU
#define VIDEO_GET_CUR_CT_PANTILT_RELATIVE_CONTROL 0x814EU
#define VIDEO_GET_CUR_CT_ROLL_ABSOLUTE_CONTROL 0x814FU
#define VIDEO_GET_CUR_CT_ROLL_RELATIVE_CONTROL 0x8150U
#define VIDEO_GET_CUR_CT_PRIVACY_CONTROL 0x8151U
#if defined(USB_DEVICE_VIDEO_CLASS_VERSION_1_5) && USB_DEVICE_VIDEO_CLASS_VERSION_1_5
#define VIDEO_GET_CUR_CT_FOCUS_SIMPLE_CONTROL 0x8152U
#define VIDEO_GET_CUR_CT_DIGITAL_WINDOW_CONTROL 0x8153U
#define VIDEO_GET_CUR_CT_REGION_OF_INTEREST_CONTROL 0x8154U
#endif
#define VIDEO_GET_CUR_VS_PROBE_CONTROL 0x8161U
#define VIDEO_GET_CUR_VS_COMMIT_CONTROL 0x8162U
#define VIDEO_GET_CUR_VS_STILL_PROBE_CONTROL 0x8163U
#define VIDEO_GET_CUR_VS_STILL_COMMIT_CONTROL 0x8164U
#define VIDEO_GET_CUR_VS_STILL_IMAGE_TRIGGER_CONTROL 0x8165U
#define VIDEO_GET_CUR_VS_STREAM_ERROR_CODE_CONTROL 0x8166U
#define VIDEO_GET_CUR_VS_GENERATE_KEY_FRAME_CONTROL 0x8167U
#define VIDEO_GET_CUR_VS_UPDATE_FRAME_SEGMENT_CONTROL 0x8168U
#define VIDEO_GET_CUR_VS_SYNCH_DELAY_CONTROL 0x8169U
#if defined(USB_DEVICE_VIDEO_CLASS_VERSION_1_5) && USB_DEVICE_VIDEO_CLASS_VERSION_1_5
#define VIDEO_GET_CUR_EU_SELECT_LAYER_CONTROL 0x8181U
#define VIDEO_GET_CUR_EU_PROFILE_TOOLSET_CONTROL 0x8182U
#define VIDEO_GET_CUR_EU_VIDEO_RESOLUTION_CONTROL 0x8183U
#define VIDEO_GET_CUR_EU_MIN_FRAME_INTERVAL_CONTROL 0x8184U
#define VIDEO_GET_CUR_EU_SLICE_MODE_CONTROL 0x8185U
#define VIDEO_GET_CUR_EU_RATE_CONTROL_MODE_CONTROL 0x8186U
#define VIDEO_GET_CUR_EU_AVERAGE_BITRATE_CONTROL 0x8187U
#define VIDEO_GET_CUR_EU_CPB_SIZE_CONTROL 0x8188U
#define VIDEO_GET_CUR_EU_PEAK_BIT_RATE_CONTROL 0x8189U
#define VIDEO_GET_CUR_EU_QUANTIZATION_PARAMS_CONTROL 0x818AU
#define VIDEO_GET_CUR_EU_SYNC_REF_FRAME_CONTROL 0x818BU
#define VIDEO_GET_CUR_EU_LTR_BUFFER_CONTROL 0x818CU
#define VIDEO_GET_CUR_EU_LTR_PICTURE_CONTROL 0x818DU
#define VIDEO_GET_CUR_EU_LTR_VALIDATION_CONTROL 0x818EU
#define VIDEO_GET_CUR_EU_LEVEL_IDC_LIMIT_CONTROL 0x818FU
#define VIDEO_GET_CUR_EU_SEI_PAYLOADTYPE_CONTROL 0x8190U
#define VIDEO_GET_CUR_EU_QP_RANGE_CONTROL 0x8191U
#define VIDEO_GET_CUR_EU_PRIORITY_CONTROL 0x8192U
#define VIDEO_GET_CUR_EU_START_OR_STOP_LAYER_CONTROL 0x8193U
#define VIDEO_GET_CUR_EU_ERROR_RESILIENCY_CONTROL 0x8194U
#endif
/*! @brief Video device class-specific request GET MIN COMMAND */
#define VIDEO_GET_MIN_PU_BACKLIGHT_COMPENSATION_CONTROL 0x8221U
#define VIDEO_GET_MIN_PU_BRIGHTNESS_CONTROL 0x8222U
#define VIDEO_GET_MIN_PU_CONTRACT_CONTROL 0x8223U
#define VIDEO_GET_MIN_PU_GAIN_CONTROL 0x8224U
#define VIDEO_GET_MIN_PU_HUE_CONTROL 0x8226U
#define VIDEO_GET_MIN_PU_SATURATION_CONTROL 0x8227U
#define VIDEO_GET_MIN_PU_SHARRNESS_CONTROL 0x8228U
#define VIDEO_GET_MIN_PU_GAMMA_CONTROL 0x8229U
#define VIDEO_GET_MIN_PU_WHITE_BALANCE_TEMPERATURE_CONTROL 0x822AU
#define VIDEO_GET_MIN_PU_WHITE_BALANCE_COMPONENT_CONTROL 0x822CU
#define VIDEO_GET_MIN_PU_DIGITAL_MULTIPLIER_CONTROL 0x822EU
#define VIDEO_GET_MIN_PU_DIGITAL_MULTIPLIER_LIMIT_CONTROL 0x822FU
#define VIDEO_GET_MIN_CT_EXPOSURE_TIME_ABSOLUTE_CONTROL 0x8244U
#define VIDEO_GET_MIN_CT_FOCUS_ABSOLUTE_CONTROL 0x8246U
#define VIDEO_GET_MIN_CT_FOCUS_RELATIVE_CONTROL 0x8247U
#define VIDEO_GET_MIN_CT_IRIS_ABSOLUTE_CONTROL 0x8249U
#define VIDEO_GET_MIN_CT_ZOOM_ABSOLUTE_CONTROL 0x824BU
#define VIDEO_GET_MIN_CT_ZOOM_RELATIVE_CONTROL 0x824CU
#define VIDEO_GET_MIN_CT_PANTILT_ABSOLUTE_CONTROL 0x824DU
#define VIDEO_GET_MIN_CT_PANTILT_RELATIVE_CONTROL 0x824EU
#define VIDEO_GET_MIN_CT_ROLL_ABSOLUTE_CONTROL 0x824FU
#define VIDEO_GET_MIN_CT_ROLL_RELATIVE_CONTROL 0x8250U
#if defined(USB_DEVICE_VIDEO_CLASS_VERSION_1_5) && USB_DEVICE_VIDEO_CLASS_VERSION_1_5
#define VIDEO_GET_MIN_CT_DIGITAL_WINDOW_CONTROL 0x8251U
#define VIDEO_GET_MIN_CT_REGION_OF_INTEREST_CONTROL 0x8252U
#endif
#define VIDEO_GET_MIN_VS_PROBE_CONTROL 0x8261U
#define VIDEO_GET_MIN_VS_STILL_PROBE_CONTROL 0x8263U
#define VIDEO_GET_MIN_VS_UPDATE_FRAME_SEGMENT_CONTROL 0x8268U
#define VIDEO_GET_MIN_VS_SYNCH_DELAY_CONTROL 0x8269U
#if defined(USB_DEVICE_VIDEO_CLASS_VERSION_1_5) && USB_DEVICE_VIDEO_CLASS_VERSION_1_5
#define VIDEO_GET_MIN_EU_VIDEO_RESOLUTION_CONTROL 0x8283U
#define VIDEO_GET_MIN_EU_MIN_FRAME_INTERVAL_CONTROL 0x8284U
#define VIDEO_GET_MIN_EU_SLICE_MODE_CONTROL 0x8285U
#define VIDEO_GET_MIN_EU_AVERAGE_BITRATE_CONTROL 0x8287U
#define VIDEO_GET_MIN_EU_CPB_SIZE_CONTROL 0x8288U
#define VIDEO_GET_MIN_EU_PEAK_BIT_RATE_CONTROL 0x8289U
#define VIDEO_GET_MIN_EU_QUANTIZATION_PARAMS_CONTROL 0x828AU
#define VIDEO_GET_MIN_EU_SYNC_REF_FRAME_CONTROL 0x828BU
#define VIDEO_GET_MIN_EU_LEVEL_IDC_LIMIT_CONTROL 0x828FU
#define VIDEO_GET_MIN_EU_SEI_PAYLOADTYPE_CONTROL 0x8290U
#define VIDEO_GET_MIN_EU_QP_RANGE_CONTROL 0x8291U
#endif
/*! @brief Video device class-specific request GET MAX COMMAND */
#define VIDEO_GET_MAX_PU_BACKLIGHT_COMPENSATION_CONTROL 0x8321U
#define VIDEO_GET_MAX_PU_BRIGHTNESS_CONTROL 0x8322U
#define VIDEO_GET_MAX_PU_CONTRACT_CONTROL 0x8323U
#define VIDEO_GET_MAX_PU_GAIN_CONTROL 0x8324U
#define VIDEO_GET_MAX_PU_HUE_CONTROL 0x8326U
#define VIDEO_GET_MAX_PU_SATURATION_CONTROL 0x8327U
#define VIDEO_GET_MAX_PU_SHARRNESS_CONTROL 0x8328U
#define VIDEO_GET_MAX_PU_GAMMA_CONTROL 0x8329U
#define VIDEO_GET_MAX_PU_WHITE_BALANCE_TEMPERATURE_CONTROL 0x832AU
#define VIDEO_GET_MAX_PU_WHITE_BALANCE_COMPONENT_CONTROL 0x832CU
#define VIDEO_GET_MAX_PU_DIGITAL_MULTIPLIER_CONTROL 0x832EU
#define VIDEO_GET_MAX_PU_DIGITAL_MULTIPLIER_LIMIT_CONTROL 0x832FU
#define VIDEO_GET_MAX_CT_EXPOSURE_TIME_ABSOLUTE_CONTROL 0x8344U
#define VIDEO_GET_MAX_CT_FOCUS_ABSOLUTE_CONTROL 0x8346U
#define VIDEO_GET_MAX_CT_FOCUS_RELATIVE_CONTROL 0x8347U
#define VIDEO_GET_MAX_CT_IRIS_ABSOLUTE_CONTROL 0x8349U
#define VIDEO_GET_MAX_CT_ZOOM_ABSOLUTE_CONTROL 0x834BU
#define VIDEO_GET_MAX_CT_ZOOM_RELATIVE_CONTROL 0x834CU
#define VIDEO_GET_MAX_CT_PANTILT_ABSOLUTE_CONTROL 0x834DU
#define VIDEO_GET_MAX_CT_PANTILT_RELATIVE_CONTROL 0x834EU
#define VIDEO_GET_MAX_CT_ROLL_ABSOLUTE_CONTROL 0x834FU
#define VIDEO_GET_MAX_CT_ROLL_RELATIVE_CONTROL 0x8350U
#if defined(USB_DEVICE_VIDEO_CLASS_VERSION_1_5) && USB_DEVICE_VIDEO_CLASS_VERSION_1_5
#define VIDEO_GET_MAX_CT_DIGITAL_WINDOW_CONTROL 0x8351U
#define VIDEO_GET_MAX_CT_REGION_OF_INTEREST_CONTROL 0x8352U
#endif
#define VIDEO_GET_MAX_VS_PROBE_CONTROL 0x8361U
#define VIDEO_GET_MAX_VS_STILL_PROBE_CONTROL 0x8363U
#define VIDEO_GET_MAX_VS_UPDATE_FRAME_SEGMENT_CONTROL 0x8368U
#define VIDEO_GET_MAX_VS_SYNCH_DELAY_CONTROL 0x8369U
#if defined(USB_DEVICE_VIDEO_CLASS_VERSION_1_5) && USB_DEVICE_VIDEO_CLASS_VERSION_1_5
#define VIDEO_GET_MAX_EU_VIDEO_RESOLUTION_CONTROL 0x8383U
#define VIDEO_GET_MAX_EU_MIN_FRAME_INTERVAL_CONTROL 0x8384U
#define VIDEO_GET_MAX_EU_SLICE_MODE_CONTROL 0x8385U
#define VIDEO_GET_MAX_EU_AVERAGE_BITRATE_CONTROL 0x8387U
#define VIDEO_GET_MAX_EU_CPB_SIZE_CONTROL 0x8388U
#define VIDEO_GET_MAX_EU_PEAK_BIT_RATE_CONTROL 0x8389U
#define VIDEO_GET_MAX_EU_QUANTIZATION_PARAMS_CONTROL 0x838AU
#define VIDEO_GET_MAX_EU_SYNC_REF_FRAME_CONTROL 0x838BU
#define VIDEO_GET_MAX_EU_LTR_BUFFER_CONTROL 0x838CU
#define VIDEO_GET_MAX_EU_LEVEL_IDC_LIMIT_CONTROL 0x838FU
#define VIDEO_GET_MAX_EU_SEI_PAYLOADTYPE_CONTROL 0x8390U
#define VIDEO_GET_MAX_EU_QP_RANGE_CONTROL 0x8391U
#endif
/*! @brief Video device class-specific request GET RES COMMAND */
#define VIDEO_GET_RES_PU_BACKLIGHT_COMPENSATION_CONTROL 0x8421U
#define VIDEO_GET_RES_PU_BRIGHTNESS_CONTROL 0x8422U
#define VIDEO_GET_RES_PU_CONTRACT_CONTROL 0x8423U
#define VIDEO_GET_RES_PU_GAIN_CONTROL 0x8424U
#define VIDEO_GET_RES_PU_HUE_CONTROL 0x8426U
#define VIDEO_GET_RES_PU_SATURATION_CONTROL 0x8427U
#define VIDEO_GET_RES_PU_SHARRNESS_CONTROL 0x8428U
#define VIDEO_GET_RES_PU_GAMMA_CONTROL 0x8429U
#define VIDEO_GET_RES_PU_WHITE_BALANCE_TEMPERATURE_CONTROL 0x842AU
#define VIDEO_GET_RES_PU_WHITE_BALANCE_COMPONENT_CONTROL 0x842CU
#define VIDEO_GET_RES_PU_DIGITAL_MULTIPLIER_CONTROL 0x842EU
#define VIDEO_GET_RES_PU_DIGITAL_MULTIPLIER_LIMIT_CONTROL 0x842FU
#define VIDEO_GET_RES_CT_AE_MODE_CONTROL 0x8442U
#define VIDEO_GET_RES_CT_EXPOSURE_TIME_ABSOLUTE_CONTROL 0x8444U
#define VIDEO_GET_RES_CT_FOCUS_ABSOLUTE_CONTROL 0x8446U
#define VIDEO_GET_RES_CT_FOCUS_RELATIVE_CONTROL 0x8447U
#define VIDEO_GET_RES_CT_IRIS_ABSOLUTE_CONTROL 0x8449U
#define VIDEO_GET_RES_CT_ZOOM_ABSOLUTE_CONTROL 0x844BU
#define VIDEO_GET_RES_CT_ZOOM_RELATIVE_CONTROL 0x844CU
#define VIDEO_GET_RES_CT_PANTILT_ABSOLUTE_CONTROL 0x844DU
#define VIDEO_GET_RES_CT_PANTILT_RELATIVE_CONTROL 0x844EU
#define VIDEO_GET_RES_CT_ROLL_ABSOLUTE_CONTROL 0x844FU
#define VIDEO_GET_RES_CT_ROLL_RELATIVE_CONTROL 0x8450U
#define VIDEO_GET_RES_VS_PROBE_CONTROL 0x8461U
#define VIDEO_GET_RES_VS_STILL_PROBE_CONTROL 0x8463U
#define VIDEO_GET_RES_VS_UPDATE_FRAME_SEGMENT_CONTROL 0x8468U
#define VIDEO_GET_RES_VS_SYNCH_DELAY_CONTROL 0x8469U
#if defined(USB_DEVICE_VIDEO_CLASS_VERSION_1_5) && USB_DEVICE_VIDEO_CLASS_VERSION_1_5
#define VIDEO_GET_RES_EU_AVERAGE_BITRATE_CONTROL 0x8487U
#define VIDEO_GET_RES_EU_CPB_SIZE_CONTROL 0x8488U
#define VIDEO_GET_RES_EU_PEAK_BIT_RATE_CONTROL 0x8489U
#define VIDEO_GET_RES_EU_QUANTIZATION_PARAMS_CONTROL 0x848AU
#define VIDEO_GET_RES_EU_ERROR_RESILIENCY_CONTROL 0x8494U
#endif
/*! @brief Video device class-specific request GET LEN COMMAND */
#define VIDEO_GET_LEN_VS_PROBE_CONTROL 0x8561U
#define VIDEO_GET_LEN_VS_COMMIT_CONTROL 0x8562U
#define VIDEO_GET_LEN_VS_STILL_PROBE_CONTROL 0x8563U
#define VIDEO_GET_LEN_VS_STILL_COMMIT_CONTROL 0x8564U
#if defined(USB_DEVICE_VIDEO_CLASS_VERSION_1_5) && USB_DEVICE_VIDEO_CLASS_VERSION_1_5
#define VIDEO_GET_LEN_EU_SELECT_LAYER_CONTROL 0x8581U
#define VIDEO_GET_LEN_EU_PROFILE_TOOLSET_CONTROL 0x8582U
#define VIDEO_GET_LEN_EU_VIDEO_RESOLUTION_CONTROL 0x8583U
#define VIDEO_GET_LEN_EU_MIN_FRAME_INTERVAL_CONTROL 0x8584U
#define VIDEO_GET_LEN_EU_SLICE_MODE_CONTROL 0x8585U
#define VIDEO_GET_LEN_EU_RATE_CONTROL_MODE_CONTROL 0x8586U
#define VIDEO_GET_LEN_EU_AVERAGE_BITRATE_CONTROL 0x8587U
#define VIDEO_GET_LEN_EU_CPB_SIZE_CONTROL 0x8588U
#define VIDEO_GET_LEN_EU_PEAK_BIT_RATE_CONTROL 0x8589U
#define VIDEO_GET_LEN_EU_QUANTIZATION_PARAMS_CONTROL 0x858AU
#define VIDEO_GET_LEN_EU_SYNC_REF_FRAME_CONTROL 0x858BU
#define VIDEO_GET_LEN_EU_LTR_BUFFER_CONTROL 0x858CU
#define VIDEO_GET_LEN_EU_LTR_PICTURE_CONTROL 0x858DU
#define VIDEO_GET_LEN_EU_LTR_VALIDATION_CONTROL 0x858EU
#define VIDEO_GET_LEN_EU_QP_RANGE_CONTROL 0x8591U
#define VIDEO_GET_LEN_EU_PRIORITY_CONTROL 0x8592U
#define VIDEO_GET_LEN_EU_START_OR_STOP_LAYER_CONTROL 0x8593U
#endif
/*! @brief Video device class-specific request GET INFO COMMAND */
#define VIDEO_GET_INFO_VC_POWER_MODE_CONTROL 0x8601U
#define VIDEO_GET_INFO_VC_ERROR_CODE_CONTROL 0x8602U
#define VIDEO_GET_INFO_PU_BACKLIGHT_COMPENSATION_CONTROL 0x8621U
#define VIDEO_GET_INFO_PU_BRIGHTNESS_CONTROL 0x8622U
#define VIDEO_GET_INFO_PU_CONTRACT_CONTROL 0x8623U
#define VIDEO_GET_INFO_PU_GAIN_CONTROL 0x8624U
#define VIDEO_GET_INFO_PU_POWER_LINE_FREQUENCY_CONTROL 0x8625U
#define VIDEO_GET_INFO_PU_HUE_CONTROL 0x8626U
#define VIDEO_GET_INFO_PU_SATURATION_CONTROL 0x8627U
#define VIDEO_GET_INFO_PU_SHARRNESS_CONTROL 0x8628U
#define VIDEO_GET_INFO_PU_GAMMA_CONTROL 0x8629U
#define VIDEO_GET_INFO_PU_WHITE_BALANCE_TEMPERATURE_CONTROL 0x862AU
#define VIDEO_GET_INFO_PU_WHITE_BALANCE_TEMPERATURE_AUTO_CONTROL 0x862BU
#define VIDEO_GET_INFO_PU_WHITE_BALANCE_COMPONENT_CONTROL 0x862CU
#define VIDEO_GET_INFO_PU_WHITE_BALANCE_COMPONENT_AUTO_CONTROL 0x862DU
#define VIDEO_GET_INFO_PU_DIGITAL_MULTIPLIER_CONTROL 0x862EU
#define VIDEO_GET_INFO_PU_DIGITAL_MULTIPLIER_LIMIT_CONTROL 0x862FU
#define VIDEO_GET_INFO_PU_HUE_AUTO_CONTROL 0x8630U
#define VIDEO_GET_INFO_PU_ANALOG_VIDEO_STANDARD_CONTROL 0x8631U
#define VIDEO_GET_INFO_PU_ANALOG_LOCK_STATUS_CONTROL 0x8632U
#if defined(USB_DEVICE_VIDEO_CLASS_VERSION_1_5) && USB_DEVICE_VIDEO_CLASS_VERSION_1_5
#define VIDEO_GET_INFO_PU_CONTRAST_AUTO_CONTROL 0x8633U
#endif
#define VIDEO_GET_INFO_CT_SCANNING_MODE_CONTROL 0x8641U
#define VIDEO_GET_INFO_CT_AE_MODE_CONTROL 0x8642U
#define VIDEO_GET_INFO_CT_AE_PRIORITY_CONTROL 0x8643U
#define VIDEO_GET_INFO_CT_EXPOSURE_TIME_ABSOLUTE_CONTROL 0x8644U
#define VIDEO_GET_INFO_CT_EXPOSURE_TIME_RELATIVE_CONTROL 0x8645U
#define VIDEO_GET_INFO_CT_FOCUS_ABSOLUTE_CONTROL 0x8646U
#define VIDEO_GET_INFO_CT_FOCUS_RELATIVE_CONTROL 0x8647U
#define VIDEO_GET_INFO_CT_FOCUS_AUTO_CONTROL 0x8648U
#define VIDEO_GET_INFO_CT_IRIS_ABSOLUTE_CONTROL 0x8649U
#define VIDEO_GET_INFO_CT_IRIS_RELATIVE_CONTROL 0x864AU
#define VIDEO_GET_INFO_CT_ZOOM_ABSOLUTE_CONTROL 0x864BU
#define VIDEO_GET_INFO_CT_ZOOM_RELATIVE_CONTROL 0x864CU
#define VIDEO_GET_INFO_CT_PANTILT_ABSOLUTE_CONTROL 0x864DU
#define VIDEO_GET_INFO_CT_PANTILT_RELATIVE_CONTROL 0x864EU
#define VIDEO_GET_INFO_CT_ROLL_ABSOLUTE_CONTROL 0x864FU
#define VIDEO_GET_INFO_CT_ROLL_RELATIVE_CONTROL 0x8650U
#define VIDEO_GET_INFO_CT_PRIVACY_CONTROL 0x8651U
#if defined(USB_DEVICE_VIDEO_CLASS_VERSION_1_5) && USB_DEVICE_VIDEO_CLASS_VERSION_1_5
#define VIDEO_GET_INFO_CT_FOCUS_SIMPLE_CONTROL 0x8652U
#endif
#define VIDEO_GET_INFO_VS_PROBE_CONTROL 0x8661U
#define VIDEO_GET_INFO_VS_COMMIT_CONTROL 0x8662U
#define VIDEO_GET_INFO_VS_STILL_PROBE_CONTROL 0x8663U
#define VIDEO_GET_INFO_VS_STILL_COMMIT_CONTROL 0x8664U
#define VIDEO_GET_INFO_VS_STILL_IMAGE_TRIGGER_CONTROL 0x8665U
#define VIDEO_GET_INFO_VS_STREAM_ERROR_CODE_CONTROL 0x8666U
#define VIDEO_GET_INFO_VS_GENERATE_KEY_FRAME_CONTROL 0x8667U
#define VIDEO_GET_INFO_VS_UPDATE_FRAME_SEGMENT_CONTROL 0x8668U
#define VIDEO_GET_INFO_VS_SYNCH_DELAY_CONTROL 0x8669U
#if defined(USB_DEVICE_VIDEO_CLASS_VERSION_1_5) && USB_DEVICE_VIDEO_CLASS_VERSION_1_5
#define VIDEO_GET_INFO_EU_SELECT_LAYER_CONTROL 0x8681U
#define VIDEO_GET_INFO_EU_PROFILE_TOOLSET_CONTROL 0x8682U
#define VIDEO_GET_INFO_EU_VIDEO_RESOLUTION_CONTROL 0x8683U
#define VIDEO_GET_INFO_EU_MIN_FRAME_INTERVAL_CONTROL 0x8684U
#define VIDEO_GET_INFO_EU_SLICE_MODE_CONTROL 0x8685U
#define VIDEO_GET_INFO_EU_RATE_CONTROL_MODE_CONTROL 0x8686U
#define VIDEO_GET_INFO_EU_AVERAGE_BITRATE_CONTROL 0x8687U
#define VIDEO_GET_INFO_EU_CPB_SIZE_CONTROL 0x8688U
#define VIDEO_GET_INFO_EU_PEAK_BIT_RATE_CONTROL 0x8689U
#define VIDEO_GET_INFO_EU_QUANTIZATION_PARAMS_CONTROL 0x868AU
#define VIDEO_GET_INFO_EU_SYNC_REF_FRAME_CONTROL 0x868BU
#define VIDEO_GET_INFO_EU_LTR_BUFFER_CONTROL 0x868CU
#define VIDEO_GET_INFO_EU_LTR_PICTURE_CONTROL 0x868DU
#define VIDEO_GET_INFO_EU_LTR_VALIDATION_CONTROL 0x868EU
#define VIDEO_GET_INFO_EU_SEI_PAYLOADTYPE_CONTROL 0x8690U
#define VIDEO_GET_INFO_EU_QP_RANGE_CONTROL 0x8691U
#define VIDEO_GET_INFO_EU_PRIORITY_CONTROL 0x8692U
#define VIDEO_GET_INFO_EU_START_OR_STOP_LAYER_CONTROL 0x8693U
#endif
/*! @brief Video device class-specific request GET DEF COMMAND */
#define VIDEO_GET_DEF_PU_BACKLIGHT_COMPENSATION_CONTROL 0x8721U
#define VIDEO_GET_DEF_PU_BRIGHTNESS_CONTROL 0x8722U
#define VIDEO_GET_DEF_PU_CONTRACT_CONTROL 0x8723U
#define VIDEO_GET_DEF_PU_GAIN_CONTROL 0x8724U
#define VIDEO_GET_DEF_PU_POWER_LINE_FREQUENCY_CONTROL 0x8725U
#define VIDEO_GET_DEF_PU_HUE_CONTROL 0x8726U
#define VIDEO_GET_DEF_PU_SATURATION_CONTROL 0x8727U
#define VIDEO_GET_DEF_PU_SHARRNESS_CONTROL 0x8728U
#define VIDEO_GET_DEF_PU_GAMMA_CONTROL 0x8729U
#define VIDEO_GET_DEF_PU_WHITE_BALANCE_TEMPERATURE_CONTROL 0x872AU
#define VIDEO_GET_DEF_PU_WHITE_BALANCE_TEMPERATURE_AUTO_CONTROL 0x872BU
#define VIDEO_GET_DEF_PU_WHITE_BALANCE_COMPONENT_CONTROL 0x872CU
#define VIDEO_GET_DEF_PU_WHITE_BALANCE_COMPONENT_AUTO_CONTROL 0x872DU
#define VIDEO_GET_DEF_PU_DIGITAL_MULTIPLIER_CONTROL 0x872EU
#define VIDEO_GET_DEF_PU_DIGITAL_MULTIPLIER_LIMIT_CONTROL 0x872FU
#define VIDEO_GET_DEF_PU_HUE_AUTO_CONTROL 0x8730U
#if defined(USB_DEVICE_VIDEO_CLASS_VERSION_1_5) && USB_DEVICE_VIDEO_CLASS_VERSION_1_5
#define VIDEO_GET_DEF_PU_CONTRAST_AUTO_CONTROL 0x8731U
#endif
#define VIDEO_GET_DEF_CT_AE_MODE_CONTROL 0x8742U
#define VIDEO_GET_DEF_CT_EXPOSURE_TIME_ABSOLUTE_CONTROL 0x8744U
#define VIDEO_GET_DEF_CT_FOCUS_ABSOLUTE_CONTROL 0x8746U
#define VIDEO_GET_DEF_CT_FOCUS_RELATIVE_CONTROL 0x8747U
#define VIDEO_GET_DEF_CT_FOCUS_AUTO_CONTROL 0x8748U
#define VIDEO_GET_DEF_CT_IRIS_ABSOLUTE_CONTROL 0x8749U
#define VIDEO_GET_DEF_CT_ZOOM_ABSOLUTE_CONTROL 0x874BU
#define VIDEO_GET_DEF_CT_ZOOM_RELATIVE_CONTROL 0x874CU
#define VIDEO_GET_DEF_CT_PANTILT_ABSOLUTE_CONTROL 0x874DU
#define VIDEO_GET_DEF_CT_PANTILT_RELATIVE_CONTROL 0x874EU
#define VIDEO_GET_DEF_CT_ROLL_ABSOLUTE_CONTROL 0x874FU
#define VIDEO_GET_DEF_CT_ROLL_RELATIVE_CONTROL 0x8750U
#if defined(USB_DEVICE_VIDEO_CLASS_VERSION_1_5) && USB_DEVICE_VIDEO_CLASS_VERSION_1_5
#define VIDEO_GET_DEF_CT_FOCUS_SIMPLE_CONTROL 0x8751U
#define VIDEO_GET_DEF_CT_DIGITAL_WINDOW_CONTROL 0x8752U
#define VIDEO_GET_DEF_CT_REGION_OF_INTEREST_CONTROL 0x8753U
#endif
#define VIDEO_GET_DEF_VS_PROBE_CONTROL 0x8761U
#define VIDEO_GET_DEF_VS_STILL_PROBE_CONTROL 0x8763U
#define VIDEO_GET_DEF_VS_UPDATE_FRAME_SEGMENT_CONTROL 0x8768U
#define VIDEO_GET_DEF_VS_SYNCH_DELAY_CONTROL 0x8769U
#if defined(USB_DEVICE_VIDEO_CLASS_VERSION_1_5) && USB_DEVICE_VIDEO_CLASS_VERSION_1_5
#define VIDEO_GET_DEF_EU_PROFILE_TOOLSET_CONTROL 0x8782U
#define VIDEO_GET_DEF_EU_VIDEO_RESOLUTION_CONTROL 0x8783U
#define VIDEO_GET_DEF_EU_MIN_FRAME_INTERVAL_CONTROL 0x8784U
#define VIDEO_GET_DEF_EU_SLICE_MODE_CONTROL 0x8785U
#define VIDEO_GET_DEF_EU_RATE_CONTROL_MODE_CONTROL 0x8786U
#define VIDEO_GET_DEF_EU_AVERAGE_BITRATE_CONTROL 0x8787U
#define VIDEO_GET_DEF_EU_CPB_SIZE_CONTROL 0x8788U
#define VIDEO_GET_DEF_EU_PEAK_BIT_RATE_CONTROL 0x8789U
#define VIDEO_GET_DEF_EU_QUANTIZATION_PARAMS_CONTROL 0x878AU
#define VIDEO_GET_DEF_EU_LTR_BUFFER_CONTROL 0x878CU
#define VIDEO_GET_DEF_EU_LTR_PICTURE_CONTROL 0x878DU
#define VIDEO_GET_DEF_EU_LTR_VALIDATION_CONTROL 0x878EU
#define VIDEO_GET_DEF_EU_LEVEL_IDC_LIMIT_CONTROL 0x878FU
#define VIDEO_GET_DEF_EU_SEI_PAYLOADTYPE_CONTROL 0x8790U
#define VIDEO_GET_DEF_EU_QP_RANGE_CONTROL 0x8791U
#define VIDEO_GET_DEF_EU_ERROR_RESILIENCY_CONTROL 0x8794U
#endif
/*! @brief Video device class-specific request SET CUR COMMAND */
#define VIDEO_SET_CUR_VC_POWER_MODE_CONTROL 0x0101U
#define VIDEO_SET_CUR_PU_BACKLIGHT_COMPENSATION_CONTROL 0x0121U
#define VIDEO_SET_CUR_PU_BRIGHTNESS_CONTROL 0x0122U
#define VIDEO_SET_CUR_PU_CONTRACT_CONTROL 0x0123U
#define VIDEO_SET_CUR_PU_GAIN_CONTROL 0x0124U
#define VIDEO_SET_CUR_PU_POWER_LINE_FREQUENCY_CONTROL 0x0125U
#define VIDEO_SET_CUR_PU_HUE_CONTROL 0x0126U
#define VIDEO_SET_CUR_PU_SATURATION_CONTROL 0x0127U
#define VIDEO_SET_CUR_PU_SHARRNESS_CONTROL 0x0128U
#define VIDEO_SET_CUR_PU_GAMMA_CONTROL 0x0129U
#define VIDEO_SET_CUR_PU_WHITE_BALANCE_TEMPERATURE_CONTROL 0x012AU
#define VIDEO_SET_CUR_PU_WHITE_BALANCE_TEMPERATURE_AUTO_CONTROL 0x012BU
#define VIDEO_SET_CUR_PU_WHITE_BALANCE_COMPONENT_CONTROL 0x012CU
#define VIDEO_SET_CUR_PU_WHITE_BALANCE_COMPONENT_AUTO_CONTROL 0x012DU
#define VIDEO_SET_CUR_PU_DIGITAL_MULTIPLIER_CONTROL 0x012EU
#define VIDEO_SET_CUR_PU_DIGITAL_MULTIPLIER_LIMIT_CONTROL 0x012FU
#define VIDEO_SET_CUR_PU_HUE_AUTO_CONTROL 0x0130U
#if defined(USB_DEVICE_VIDEO_CLASS_VERSION_1_5) && USB_DEVICE_VIDEO_CLASS_VERSION_1_5
#define VIDEO_SET_CUR_PU_CONTRAST_AUTO_CONTROL 0x0131U
#endif
#define VIDEO_SET_CUR_CT_SCANNING_MODE_CONTROL 0x0141U
#define VIDEO_SET_CUR_CT_AE_MODE_CONTROL 0x0142U
#define VIDEO_SET_CUR_CT_AE_PRIORITY_CONTROL 0x0143U
#define VIDEO_SET_CUR_CT_EXPOSURE_TIME_ABSOLUTE_CONTROL 0x0144U
#define VIDEO_SET_CUR_CT_EXPOSURE_TIME_RELATIVE_CONTROL 0x0145U
#define VIDEO_SET_CUR_CT_FOCUS_ABSOLUTE_CONTROL 0x0146U
#define VIDEO_SET_CUR_CT_FOCUS_RELATIVE_CONTROL 0x0147U
#define VIDEO_SET_CUR_CT_FOCUS_AUTO_CONTROL 0x0148U
#define VIDEO_SET_CUR_CT_IRIS_ABSOLUTE_CONTROL 0x0149U
#define VIDEO_SET_CUR_CT_IRIS_RELATIVE_CONTROL 0x014AU
#define VIDEO_SET_CUR_CT_ZOOM_ABSOLUTE_CONTROL 0x014BU
#define VIDEO_SET_CUR_CT_ZOOM_RELATIVE_CONTROL 0x014CU
#define VIDEO_SET_CUR_CT_PANTILT_ABSOLUTE_CONTROL 0x014DU
#define VIDEO_SET_CUR_CT_PANTILT_RELATIVE_CONTROL 0x014EU
#define VIDEO_SET_CUR_CT_ROLL_ABSOLUTE_CONTROL 0x014FU
#define VIDEO_SET_CUR_CT_ROLL_RELATIVE_CONTROL 0x0150U
#define VIDEO_SET_CUR_CT_PRIVACY_CONTROL 0x0151U
#if defined(USB_DEVICE_VIDEO_CLASS_VERSION_1_5) && USB_DEVICE_VIDEO_CLASS_VERSION_1_5
#define VIDEO_SET_CUR_CT_FOCUS_SIMPLE_CONTROL 0x0152U
#define VIDEO_SET_CUR_CT_DIGITAL_WINDOW_CONTROL 0x0153U
#define VIDEO_SET_CUR_CT_REGION_OF_INTEREST_CONTROL 0x0154U
#endif
#define VIDEO_SET_CUR_VS_PROBE_CONTROL 0x0161U
#define VIDEO_SET_CUR_VS_COMMIT_CONTROL 0x0162U
#define VIDEO_SET_CUR_VS_STILL_PROBE_CONTROL 0x0163U
#define VIDEO_SET_CUR_VS_STILL_COMMIT_CONTROL 0x0164U
#define VIDEO_SET_CUR_VS_STILL_IMAGE_TRIGGER_CONTROL 0x0165U
#define VIDEO_SET_CUR_VS_STREAM_ERROR_CODE_CONTROL 0x0166U
#define VIDEO_SET_CUR_VS_GENERATE_KEY_FRAME_CONTROL 0x0167U
#define VIDEO_SET_CUR_VS_UPDATE_FRAME_SEGMENT_CONTROL 0x0168U
#define VIDEO_SET_CUR_VS_SYNCH_DELAY_CONTROL 0x0169U
#if defined(USB_DEVICE_VIDEO_CLASS_VERSION_1_5) && USB_DEVICE_VIDEO_CLASS_VERSION_1_5
#define VIDEO_SET_CUR_EU_SELECT_LAYER_CONTROL 0x0181U
#define VIDEO_SET_CUR_EU_PROFILE_TOOLSET_CONTROL 0x0182U
#define VIDEO_SET_CUR_EU_VIDEO_RESOLUTION_CONTROL 0x0183U
#define VIDEO_SET_CUR_EU_MIN_FRAME_INTERVAL_CONTROL 0x0184U
#define VIDEO_SET_CUR_EU_SLICE_MODE_CONTROL 0x0185U
#define VIDEO_SET_CUR_EU_RATE_CONTROL_MODE_CONTROL 0x0186U
#define VIDEO_SET_CUR_EU_AVERAGE_BITRATE_CONTROL 0x0187U
#define VIDEO_SET_CUR_EU_CPB_SIZE_CONTROL 0x0188U
#define VIDEO_SET_CUR_EU_PEAK_BIT_RATE_CONTROL 0x0189U
#define VIDEO_SET_CUR_EU_QUANTIZATION_PARAMS_CONTROL 0x018AU
#define VIDEO_SET_CUR_EU_SYNC_REF_FRAME_CONTROL 0x018BU
#define VIDEO_SET_CUR_EU_LTR_BUFFER_CONTROL 0x018CU
#define VIDEO_SET_CUR_EU_LTR_PICTURE_CONTROL 0x018DU
#define VIDEO_SET_CUR_EU_LTR_VALIDATION_CONTROL 0x018EU
#define VIDEO_SET_CUR_EU_LEVEL_IDC_LIMIT_CONTROL 0x018FU
#define VIDEO_SET_CUR_EU_SEI_PAYLOADTYPE_CONTROL 0x0190U
#define VIDEO_SET_CUR_EU_QP_RANGE_CONTROL 0x0191U
#define VIDEO_SET_CUR_EU_PRIORITY_CONTROL 0x0192U
#define VIDEO_SET_CUR_EU_START_OR_STOP_LAYER_CONTROL 0x0193U
#define VIDEO_SET_CUR_EU_ERROR_RESILIENCY_CONTROL 0x0194U
#endif
/*! @brief The payload header structure for MJPEG payload format. */
struct video_mjpeg_payload_header {
uint8_t bHeaderLength; /*!< The payload header length. */
union {
uint8_t bmheaderInfo; /*!< The payload header bitmap field. */
struct
{
uint8_t frameIdentifier : 1U; /*!< Frame Identifier. This bit toggles at each frame start boundary and stays
constant for the rest of the frame.*/
uint8_t endOfFrame : 1U; /*!< End of Frame. This bit indicates the end of a video frame and is set in the
last video sample that belongs to a frame.*/
uint8_t
presentationTimeStamp : 1U; /*!< Presentation Time Stamp. This bit, when set, indicates the presence of
a PTS field.*/
uint8_t sourceClockReference : 1U; /*!< Source Clock Reference. This bit, when set, indicates the presence
of a SCR field.*/
uint8_t reserved : 1U; /*!< Reserved. Set to 0. */
uint8_t stillImage : 1U; /*!< Still Image. This bit, when set, identifies a video sample that belongs to a
still image.*/
uint8_t errorBit : 1U; /*!< Error Bit. This bit, when set, indicates an error in the device streaming.*/
uint8_t endOfHeader : 1U; /*!< End of Header. This bit, when set, indicates the end of the BFH fields.*/
} headerInfoBits;
struct
{
uint8_t FID : 1U; /*!< Frame Identifier. This bit toggles at each frame start boundary and stays constant
for the rest of the frame.*/
uint8_t EOI : 1U; /*!< End of Frame. This bit indicates the end of a video frame and is set in the last
video sample that belongs to a frame.*/
uint8_t PTS : 1U; /*!< Presentation Time Stamp. This bit, when set, indicates the presence of a PTS field.*/
uint8_t SCR : 1U; /*!< Source Clock Reference. This bit, when set, indicates the presence of a SCR field.*/
uint8_t RES : 1U; /*!< Reserved. Set to 0. */
uint8_t STI : 1U; /*!< Still Image. This bit, when set, identifies a video sample that belongs to a still
image.*/
uint8_t ERR : 1U; /*!< Error Bit. This bit, when set, indicates an error in the device streaming.*/
uint8_t EOH : 1U; /*!< End of Header. This bit, when set, indicates the end of the BFH fields.*/
} headerInfoBitmap;
} headerInfoUnion;
uint32_t dwPresentationTime; /*!< Presentation time stamp (PTS) field.*/
uint8_t bSourceClockReference[6]; /*!< Source clock reference (SCR) field.*/
} __packed;
/*! @brief The Video probe and commit controls structure.*/
struct video_probe_and_commit_controls {
union {
uint8_t bmHint; /*!< Bit-field control indicating to the function what fields shall be kept fixed. */
struct
{
uint8_t dwFrameInterval : 1U; /*!< dwFrameInterval field.*/
uint8_t wKeyFrameRate : 1U; /*!< wKeyFrameRate field.*/
uint8_t wPFrameRate : 1U; /*!< wPFrameRate field.*/
uint8_t wCompQuality : 1U; /*!< wCompQuality field.*/
uint8_t wCompWindowSize : 1U; /*!< wCompWindowSize field.*/
uint8_t reserved : 3U; /*!< Reserved field.*/
} hintBitmap;
} hintUnion;
union {
uint8_t bmHint; /*!< Bit-field control indicating to the function what fields shall be kept fixed. */
struct
{
uint8_t reserved : 8U; /*!< Reserved field.*/
} hintBitmap;
} hintUnion1;
uint8_t bFormatIndex; /*!< Video format index from a format descriptor.*/
uint8_t bFrameIndex; /*!< Video frame index from a frame descriptor.*/
uint32_t dwFrameInterval; /*!< Frame interval in 100ns units.*/
uint16_t wKeyFrameRate; /*!< Key frame rate in key-frame per video-frame units.*/
uint16_t wPFrameRate; /*!< PFrame rate in PFrame/key frame units.*/
uint16_t wCompQuality; /*!< Compression quality control in abstract units 0U (lowest) to 10000U (highest).*/
uint16_t wCompWindowSize; /*!< Window size for average bit rate control.*/
uint16_t wDelay; /*!< Internal video streaming interface latency in ms from video data capture to presentation on
the USB.*/
uint32_t dwMaxVideoFrameSize; /*!< Maximum video frame or codec-specific segment size in bytes.*/
uint32_t dwMaxPayloadTransferSize; /*!< Specifies the maximum number of bytes that the device can transmit or
receive in a single payload transfer.*/
uint32_t dwClockFrequency; /*!< The device clock frequency in Hz for the specified format. This specifies the
units used for the time information fields in the Video Payload Headers in the data
stream.*/
uint8_t bmFramingInfo; /*!< Bit-field control supporting the following values: D0 Frame ID, D1 EOF.*/
uint8_t bPreferedVersion; /*!< The preferred payload format version supported by the host or device for the
specified bFormatIndex value.*/
uint8_t bMinVersion; /*!< The minimum payload format version supported by the device for the specified bFormatIndex
value.*/
uint8_t bMaxVersion; /*!< The maximum payload format version supported by the device for the specified bFormatIndex
value.*/
#if defined(USB_DEVICE_VIDEO_CLASS_VERSION_1_5) && USB_DEVICE_VIDEO_CLASS_VERSION_1_5
uint8_t bUsage; /*!< This bitmap enables features reported by the bmUsages field of the Video Frame Descriptor.*/
uint8_t
bBitDepthLuma; /*!< Represents bit_depth_luma_minus8 + 8U, which must be the same as bit_depth_chroma_minus8 +
8.*/
uint8_t bmSettings; /*!< A bitmap of flags that is used to discover and control specific features of a temporally
encoded video stream.*/
uint8_t bMaxNumberOfRefFramesPlus1; /*!< Host indicates the maximum number of frames stored for use as references.*/
uint16_t bmRateControlModes; /*!< This field contains 4U sub-fields, each of which is a 4U bit number.*/
uint64_t bmLayoutPerStream; /*!< This field contains 4U sub-fields, each of which is a 2U byte number.*/
#endif
} __packed;
/*! @brief The Video still probe and still commit controls structure.*/
struct video_still_probe_and_commit_controls {
uint8_t bFormatIndex; /*!< Video format index from a format descriptor.*/
uint8_t bFrameIndex; /*!< Video frame index from a frame descriptor.*/
uint8_t bCompressionIndex; /*!< Compression index from a frame descriptor.*/
uint32_t dwMaxVideoFrameSize; /*!< Maximum still image size in bytes.*/
uint32_t dwMaxPayloadTransferSize; /*!< Specifies the maximum number of bytes that the device can transmit or
receive in a single payload transfer.*/
} __packed;
void usbd_video_sof_callback(void);
void usbd_video_set_interface_callback(uint8_t value);
void usbd_video_add_interface(usbd_class_t *class, usbd_interface_t *intf);
#ifdef __cplusplus
}
#endif
#endif /* USB_VIDEO_H_ */

View File

@@ -0,0 +1,22 @@
#ifndef _USBD_WEBUSB_H
#define _USBD_WEBUSB_H
/* WebUSB Descriptor Types */
#define WEBUSB_DESCRIPTOR_SET_HEADER_TYPE 0x00
#define WEBUSB_CONFIGURATION_SUBSET_HEADER_TYPE 0x01
#define WEBUSB_FUNCTION_SUBSET_HEADER_TYPE 0x02
#define WEBUSB_URL_TYPE 0x03
/* WebUSB Request Codes */
#define WEBUSB_REQUEST_GET_URL 0x02
/* bScheme in URL descriptor */
#define WEBUSB_URL_SCHEME_HTTP 0x00
#define WEBUSB_URL_SCHEME_HTTPS 0x01
/* WebUSB Descriptor sizes */
#define WEBUSB_DESCRIPTOR_SET_HEADER_SIZE 5
#define WEBUSB_CONFIGURATION_SUBSET_HEADER_SIZE 4
#define WEBUSB_FUNCTION_SUBSET_HEADER_SIZE 3
#endif

View File

@@ -0,0 +1,26 @@
#ifndef _USBD_WINUSB_H
#define _USBD_WINUSB_H
/* WinUSB Microsoft OS 2.0 descriptor request codes */
#define WINUSB_REQUEST_GET_DESCRIPTOR_SET 0x07
#define WINUSB_REQUEST_SET_ALT_ENUM 0x08
/* WinUSB Microsoft OS 2.0 descriptor sizes */
#define WINUSB_DESCRIPTOR_SET_HEADER_SIZE 10
#define WINUSB_FUNCTION_SUBSET_HEADER_SIZE 8
#define WINUSB_FEATURE_COMPATIBLE_ID_SIZE 20
/* WinUSB Microsoft OS 2.0 Descriptor Types */
#define WINUSB_SET_HEADER_DESCRIPTOR_TYPE 0x00
#define WINUSB_SUBSET_HEADER_CONFIGURATION_TYPE 0x01
#define WINUSB_SUBSET_HEADER_FUNCTION_TYPE 0x02
#define WINUSB_FEATURE_COMPATIBLE_ID_TYPE 0x03
#define WINUSB_FEATURE_REG_PROPERTY_TYPE 0x04
#define WINUSB_FEATURE_MIN_RESUME_TIME_TYPE 0x05
#define WINUSB_FEATURE_MODEL_ID_TYPE 0x06
#define WINUSB_FEATURE_CCGP_DEVICE_TYPE 0x07
#define WINUSB_PROP_DATA_TYPE_REG_SZ 0x01
#define WINUSB_PROP_DATA_TYPE_REG_MULTI_SZ 0x07
#endif

View File

@@ -0,0 +1,197 @@
#ifndef _USB_DC_H
#define _USB_DC_H
#include "stdint.h"
#ifdef __cplusplus
extern "C" {
#endif
/**
* USB endpoint direction and number.
*/
#define USB_EP_DIR_MASK 0x80U
#define USB_EP_DIR_IN 0x80U
#define USB_EP_DIR_OUT 0x00U
/** Get endpoint index (number) from endpoint address */
#define USB_EP_GET_IDX(ep) ((ep) & ~USB_EP_DIR_MASK)
/** Get direction from endpoint address */
#define USB_EP_GET_DIR(ep) ((ep)&USB_EP_DIR_MASK)
/** Get endpoint address from endpoint index and direction */
#define USB_EP_GET_ADDR(idx, dir) ((idx) | ((dir)&USB_EP_DIR_MASK))
/** True if the endpoint is an IN endpoint */
#define USB_EP_DIR_IS_IN(ep) (USB_EP_GET_DIR(ep) == USB_EP_DIR_IN)
/** True if the endpoint is an OUT endpoint */
#define USB_EP_DIR_IS_OUT(ep) (USB_EP_GET_DIR(ep) == USB_EP_DIR_OUT)
/**
* USB endpoint Transfer Type mask.
*/
#define USBD_EP_TYPE_CTRL 0
#define USBD_EP_TYPE_ISOC 1
#define USBD_EP_TYPE_BULK 2
#define USBD_EP_TYPE_INTR 3
#define USBD_EP_TYPE_MASK 3
/* Default USB control EP, always 0 and 0x80 */
#define USB_CONTROL_OUT_EP0 0
#define USB_CONTROL_IN_EP0 0x80
/**
* @brief USB Device Controller API
* @defgroup _usb_device_controller_api USB Device Controller API
* @{
*/
/**< maximum packet size (MPS) for EP 0 */
#define USB_CTRL_EP_MPS 64
/**
* @brief USB Endpoint Transfer Type
*/
enum usb_dc_ep_transfer_type {
/** Control type endpoint */
USB_DC_EP_CONTROL = 0,
/** Isochronous type endpoint */
USB_DC_EP_ISOCHRONOUS,
/** Bulk type endpoint */
USB_DC_EP_BULK,
/** Interrupt type endpoint */
USB_DC_EP_INTERRUPT
};
/**
* @brief USB Endpoint Configuration.
*
* Structure containing the USB endpoint configuration.
*/
struct usbd_endpoint_cfg {
/** The number associated with the EP in the device
* configuration structure
* IN EP = 0x80 | \<endpoint number\>
* OUT EP = 0x00 | \<endpoint number\>
*/
uint8_t ep_addr;
/** Endpoint max packet size */
uint16_t ep_mps;
/** Endpoint Transfer Type.
* May be Bulk, Interrupt, Control or Isochronous
*/
enum usb_dc_ep_transfer_type ep_type;
};
/**
* @brief USB Device Core Layer API
* @defgroup _usb_device_core_api USB Device Core API
* @{
*/
/**
* @brief Set USB device address
*
* @param[in] addr Device address
*
* @return 0 on success, negative errno code on fail.
*/
int usbd_set_address(const uint8_t addr);
/*
* @brief configure and enable endpoint
*
* This function sets endpoint configuration according to one specified in USB
* endpoint descriptor and then enables it for data transfers.
*
* @param [in] ep_desc Endpoint descriptor byte array
*
* @return true if successfully configured and enabled
*/
int usbd_ep_open(const struct usbd_endpoint_cfg *ep_cfg);
/**
* @brief Disable the selected endpoint
*
* Function to disable the selected endpoint. Upon success interrupts are
* disabled for the corresponding endpoint and the endpoint is no longer able
* for transmitting/receiving data.
*
* @param[in] ep Endpoint address corresponding to the one
* listed in the device configuration table
*
* @return 0 on success, negative errno code on fail.
*/
int usbd_ep_close(const uint8_t ep);
/**
* @brief Set stall condition for the selected endpoint
*
* @param[in] ep Endpoint address corresponding to the one
* listed in the device configuration table
*
* @return 0 on success, negative errno code on fail.
*/
int usbd_ep_set_stall(const uint8_t ep);
/**
* @brief Clear stall condition for the selected endpoint
*
* @param[in] ep Endpoint address corresponding to the one
* listed in the device configuration table
*
* @return 0 on success, negative errno code on fail.
*/
int usbd_ep_clear_stall(const uint8_t ep);
/**
* @brief Check if the selected endpoint is stalled
*
* @param[in] ep Endpoint address corresponding to the one
* listed in the device configuration table
* @param[out] stalled Endpoint stall status
*
* @return 0 on success, negative errno code on fail.
*/
int usbd_ep_is_stalled(const uint8_t ep, uint8_t *stalled);
/**
* @brief Write data to the specified endpoint
*
* This function is called to write data to the specified endpoint. The
* supplied usbd_endpoint_callback function will be called when data is transmitted
* out.
*
* @param[in] ep Endpoint address corresponding to the one
* listed in the device configuration table
* @param[in] data Pointer to data to write
* @param[in] data_len Length of the data requested to write. This may
* be zero for a zero length status packet.
* @param[out] ret_bytes Bytes scheduled for transmission. This value
* may be NULL if the application expects all
* bytes to be written
*
* @return 0 on success, negative errno code on fail.
*/
int usbd_ep_write(const uint8_t ep, const uint8_t *data, uint32_t data_len, uint32_t *ret_bytes);
/**
* @brief Read data from the specified endpoint
*
* This is similar to usb_dc_ep_read, the difference being that, it doesn't
* clear the endpoint NAKs so that the consumer is not bogged down by further
* upcalls till he is done with the processing of the data. The caller should
* reactivate ep by setting max_data_len 0 do so.
*
* @param[in] ep Endpoint address corresponding to the one
* listed in the device configuration table
* @param[in] data Pointer to data buffer to write to
* @param[in] max_data_len Max length of data to read
* @param[out] read_bytes Number of bytes read. If data is NULL and
* max_data_len is 0 the number of bytes
* available for read should be returned.
*
* @return 0 on success, negative errno code on fail.
*/
int usbd_ep_read(const uint8_t ep, uint8_t *data, uint32_t max_data_len, uint32_t *read_bytes);
/**
* @}
*/
#ifdef __cplusplus
}
#endif
#endif

View File

@@ -0,0 +1,566 @@
#ifndef USB_REQUEST_H
#define USB_REQUEST_H
/* Useful define */
#define USB_1_1 0x0110
#define USB_2_0 0x0200
/* Set USB version to 2.1 so that the host will request the BOS descriptor */
#define USB_2_1 0x0210
// USB Speed
#define USB_SPEED_LOW 0U
#define USB_SPEED_FULL 1U
#define USB_SPEED_HIGH 2U
// USB PID Types
#define USB_PID_RESERVED 0U
#define USB_PID_OUT 1U
#define USB_PID_ACK 2U
#define USB_PID_DATA0 3U
#define USB_PID_PING 4U
#define USB_PID_SOF 5U
#define USB_PID_DATA2 7U
#define USB_PID_NYET 6U
#define USB_PID_SPLIT 8U
#define USB_PID_IN 9U
#define USB_PID_NAK 10U
#define USB_PID_DATA1 11U
#define USB_PID_PRE 12U
#define USB_PID_ERR 12U
#define USB_PID_SETUP 13U
#define USB_PID_STALL 14U
#define USB_PID_MDATA 15U
// bmRequestType.Dir
#define USB_REQUEST_HOST_TO_DEVICE 0U
#define USB_REQUEST_DEVICE_TO_HOST 1U
// bmRequestType.Type
#define USB_REQUEST_STANDARD 0U
#define USB_REQUEST_CLASS 1U
#define USB_REQUEST_VENDOR 2U
#define USB_REQUEST_RESERVED 3U
// bmRequestType.Recipient
#define USB_REQUEST_TO_DEVICE 0U
#define USB_REQUEST_TO_INTERFACE 1U
#define USB_REQUEST_TO_ENDPOINT 2U
#define USB_REQUEST_TO_OTHER 3U
/* USB Standard Request Codes */
#define USB_REQUEST_GET_STATUS 0x00
#define USB_REQUEST_CLEAR_FEATURE 0x01
#define USB_REQUEST_SET_FEATURE 0x03
#define USB_REQUEST_SET_ADDRESS 0x05
#define USB_REQUEST_GET_DESCRIPTOR 0x06
#define USB_REQUEST_SET_DESCRIPTOR 0x07
#define USB_REQUEST_GET_CONFIGURATION 0x08
#define USB_REQUEST_SET_CONFIGURATION 0x09
#define USB_REQUEST_GET_INTERFACE 0x0A
#define USB_REQUEST_SET_INTERFACE 0x0B
#define USB_REQUEST_SYNCH_FRAME 0x0C
#define USB_REQUEST_SET_ENCRYPTION 0x0D
#define USB_REQUEST_GET_ENCRYPTION 0x0E
#define USB_REQUEST_RPIPE_ABORT 0x0E
#define USB_REQUEST_SET_HANDSHAKE 0x0F
#define USB_REQUEST_RPIPE_RESET 0x0F
#define USB_REQUEST_GET_HANDSHAKE 0x10
#define USB_REQUEST_SET_CONNECTION 0x11
#define USB_REQUEST_SET_SECURITY_DATA 0x12
#define USB_REQUEST_GET_SECURITY_DATA 0x13
#define USB_REQUEST_SET_WUSB_DATA 0x14
#define USB_REQUEST_LOOPBACK_DATA_WRITE 0x15
#define USB_REQUEST_LOOPBACK_DATA_READ 0x16
#define USB_REQUEST_SET_INTERFACE_DS 0x17
/* USB GET_STATUS Bit Values */
#define USB_GETSTATUS_SELF_POWERED 0x01
#define USB_GETSTATUS_REMOTE_WAKEUP 0x02
#define USB_GETSTATUS_ENDPOINT_STALL 0x01
/* USB Standard Feature selectors */
#define USB_FEATURE_ENDPOINT_STALL 0
#define USB_FEATURE_REMOTE_WAKEUP 1
#define USB_FEATURE_TEST_MODE 2
/* Descriptor size in bytes */
#define USB_DEVICE_DESC_SIZE 0x12
#define USB_CONFIGURATION_DESC_SIZE 0x09
#define USB_INTERFACE_DESC_SIZE 0x09
#define USB_ENDPOINT_DESC_SIZE 0x07
#define USB_LANGID_STRING_DESC_SIZE 0x04
#define USB_OTHER_SPEED_DESC_SIZE 0x09
#define USB_DEVICE_QUAL_DESC_SIZE 0x0A
#define USB_INTERFACE_ASSOC_DESC_SIZE 0x08
#define USB_FUNCTION_DESC_SIZE 0x03
#define USB_OTG_DESC_SIZE 0x03
/* USB Descriptor Types */
#define USB_DESCRIPTOR_TYPE_DEVICE 0x01U
#define USB_DESCRIPTOR_TYPE_CONFIGURATION 0x02U
#define USB_DESCRIPTOR_TYPE_STRING 0x03U
#define USB_DESCRIPTOR_TYPE_INTERFACE 0x04U
#define USB_DESCRIPTOR_TYPE_ENDPOINT 0x05U
#define USB_DESCRIPTOR_TYPE_DEVICE_QUALIFIER 0x06U
#define USB_DESCRIPTOR_TYPE_OTHER_SPEED 0x07U
#define USB_DESCRIPTOR_TYPE_INTERFACE_POWER 0x08U
#define USB_DESCRIPTOR_TYPE_OTG 0x09U
#define USB_DESCRIPTOR_TYPE_DEBUG 0x0AU
#define USB_DESCRIPTOR_TYPE_INTERFACE_ASSOCIATION 0x0BU
#define USB_DESCRIPTOR_TYPE_BINARY_OBJECT_STORE 0x0FU
#define USB_DESCRIPTOR_TYPE_DEVICE_CAPABILITY 0x10U
#define USB_DESCRIPTOR_TYPE_FUNCTIONAL 0x21U
// Class Specific Descriptor
#define USB_CS_DESCRIPTOR_TYPE_DEVICE 0x21U
#define USB_CS_DESCRIPTOR_TYPE_CONFIGURATION 0x22U
#define USB_CS_DESCRIPTOR_TYPE_STRING 0x23U
#define USB_CS_DESCRIPTOR_TYPE_INTERFACE 0x24U
#define USB_CS_DESCRIPTOR_TYPE_ENDPOINT 0x25U
#define USB_DESCRIPTOR_TYPE_SUPERSPEED_ENDPOINT_COMPANION 0x30U
#define USB_DESCRIPTOR_TYPE_SUPERSPEED_ISO_ENDPOINT_COMPANION 0x31U
/* USB Device Classes */
#define USB_DEVICE_CLASS_RESERVED 0x00
#define USB_DEVICE_CLASS_AUDIO 0x01
#define USB_DEVICE_CLASS_CDC 0x02
#define USB_DEVICE_CLASS_HID 0x03
#define USB_DEVICE_CLASS_MONITOR 0x04
#define USB_DEVICE_CLASS_PHYSICAL 0x05
#define USB_DEVICE_CLASS_IMAGE 0x06
#define USB_DEVICE_CLASS_PRINTER 0x07
#define USB_DEVICE_CLASS_MASS_STORAGE 0x08
#define USB_DEVICE_CLASS_HUB 0x09
#define USB_DEVICE_CLASS_CDC_DATA 0x0a
#define USB_DEVICE_CLASS_SMART_CARD 0x0b
#define USB_DEVICE_CLASS_SECURITY 0x0d
#define USB_DEVICE_CLASS_VIDEO 0x0e
#define USB_DEVICE_CLASS_HEALTHCARE 0x0f
#define USB_DEVICE_CLASS_DIAG_DEVICE 0xdc
#define USB_DEVICE_CLASS_WIRELESS 0xe0
#define USB_DEVICE_CLASS_MISC 0xef
#define USB_DEVICE_CLASS_APP_SPECIFIC 0xfe
#define USB_DEVICE_CLASS_VEND_SPECIFIC 0xff
/* usb string index define */
#define USB_STRING_LANGID_INDEX 0x00
#define USB_STRING_MFC_INDEX 0x01
#define USB_STRING_PRODUCT_INDEX 0x02
#define USB_STRING_SERIAL_INDEX 0x03
#define USB_STRING_CONFIG_INDEX 0x04
#define USB_STRING_INTERFACE_INDEX 0x05
#define USB_STRING_OS_INDEX 0x06
#define USB_STRING_MAX USB_STRING_OS_INDEX
/*
* Devices supporting Microsoft OS Descriptors store special string
* descriptor at fixed index (0xEE). It is read when a new device is
* attached to a computer for the first time.
*/
#define USB_OSDESC_STRING_DESC_INDEX 0xEE
/* bmAttributes in Configuration Descriptor */
#define USB_CONFIG_POWERED_MASK 0x40
#define USB_CONFIG_BUS_POWERED 0x80
#define USB_CONFIG_SELF_POWERED 0xC0
#define USB_CONFIG_REMOTE_WAKEUP 0x20
/* bMaxPower in Configuration Descriptor */
#define USB_CONFIG_POWER_MA(mA) ((mA) / 2)
/* bEndpointAddress in Endpoint Descriptor */
#define USB_ENDPOINT_DIRECTION_MASK 0x80
#define USB_ENDPOINT_OUT(addr) ((addr) | 0x00)
#define USB_ENDPOINT_IN(addr) ((addr) | 0x80)
/* bmAttributes in Endpoint Descriptor */
#define USB_ENDPOINT_TYPE_MASK 0x03
#define USB_ENDPOINT_TYPE_CONTROL 0x00
#define USB_ENDPOINT_TYPE_ISOCHRONOUS 0x01
#define USB_ENDPOINT_TYPE_BULK 0x02
#define USB_ENDPOINT_TYPE_INTERRUPT 0x03
#define USB_ENDPOINT_SYNC_MASK 0x0C
#define USB_ENDPOINT_SYNC_NO_SYNCHRONIZATION 0x00
#define USB_ENDPOINT_SYNC_ASYNCHRONOUS 0x04
#define USB_ENDPOINT_SYNC_ADAPTIVE 0x08
#define USB_ENDPOINT_SYNC_SYNCHRONOUS 0x0C
#define USB_ENDPOINT_USAGE_MASK 0x30
#define USB_ENDPOINT_USAGE_DATA 0x00
#define USB_ENDPOINT_USAGE_FEEDBACK 0x10
#define USB_ENDPOINT_USAGE_IMPLICIT_FEEDBACK 0x20
#define USB_ENDPOINT_USAGE_RESERVED 0x30
/* bDevCapabilityType in Device Capability Descriptor */
#define USB_DEVICE_CAPABILITY_WIRELESS_USB 1
#define USB_DEVICE_CAPABILITY_USB_2_0_EXTENSION 2
#define USB_DEVICE_CAPABILITY_SUPERSPEED_USB 3
#define USB_DEVICE_CAPABILITY_CONTAINER_ID 4
#define USB_DEVICE_CAPABILITY_PLATFORM 5
#define USB_DEVICE_CAPABILITY_POWER_DELIVERY_CAPABILITY 6
#define USB_DEVICE_CAPABILITY_BATTERY_INFO_CAPABILITY 7
#define USB_DEVICE_CAPABILITY_PD_CONSUMER_PORT_CAPABILITY 8
#define USB_DEVICE_CAPABILITY_PD_PROVIDER_PORT_CAPABILITY 9
#define USB_DEVICE_CAPABILITY_SUPERSPEED_PLUS 10
#define USB_DEVICE_CAPABILITY_PRECISION_TIME_MEASUREMENT 11
#define USB_DEVICE_CAPABILITY_WIRELESS_USB_EXT 12
#define USB_BOS_CAPABILITY_EXTENSION 0x02
#define USB_BOS_CAPABILITY_PLATFORM 0x05
/* Setup packet definition used to read raw data from USB line */
struct usb_setup_packet {
__packed union {
uint8_t bmRequestType; /* bmRequestType */
struct
{
uint8_t Recipient : 5; /* D4..0: Recipient */
uint8_t Type : 2; /* D6..5: Type */
uint8_t Dir : 1; /* D7: Data Phase Txsfer Direction */
} bmRequestType_b;
};
uint8_t bRequest;
__packed union {
uint16_t wValue; /* wValue */
struct
{
uint8_t wValueL;
uint8_t wValueH;
};
};
__packed union {
uint16_t wIndex; /* wIndex */
struct
{
uint8_t wIndexL;
uint8_t wIndexH;
};
};
uint16_t wLength;
} __packed;
/** Standard Device Descriptor */
struct usb_device_descriptor {
uint8_t bLength; /* Descriptor size in bytes = 18 */
uint8_t bDescriptorType; /* DEVICE descriptor type = 1 */
uint16_t bcdUSB; /* USB spec in BCD, e.g. 0x0200 */
uint8_t bDeviceClass; /* Class code, if 0 see interface */
uint8_t bDeviceSubClass; /* Sub-Class code, 0 if class = 0 */
uint8_t bDeviceProtocol; /* Protocol, if 0 see interface */
uint8_t bMaxPacketSize0; /* Endpoint 0 max. size */
uint16_t idVendor; /* Vendor ID per USB-IF */
uint16_t idProduct; /* Product ID per manufacturer */
uint16_t bcdDevice; /* Device release # in BCD */
uint8_t iManufacturer; /* Index to manufacturer string */
uint8_t iProduct; /* Index to product string */
uint8_t iSerialNumber; /* Index to serial number string */
uint8_t bNumConfigurations; /* Number of possible configurations */
} __packed;
/** USB device_qualifier descriptor */
struct usb_device_qualifier_descriptor {
uint8_t bLength; /* Descriptor size in bytes = 10 */
uint8_t bDescriptorType; /* DEVICE QUALIFIER type = 6 */
uint16_t bcdUSB; /* USB spec in BCD, e.g. 0x0200 */
uint8_t bDeviceClass; /* Class code, if 0 see interface */
uint8_t bDeviceSubClass; /* Sub-Class code, 0 if class = 0 */
uint8_t bDeviceProtocol; /* Protocol, if 0 see interface */
uint8_t bMaxPacketSize; /* Endpoint 0 max. size */
uint8_t bNumConfigurations; /* Number of possible configurations */
uint8_t bReserved; /* Reserved = 0 */
} __packed;
/** Standard Configuration Descriptor */
struct usb_configuration_descriptor {
uint8_t bLength; /* Descriptor size in bytes = 9 */
uint8_t bDescriptorType; /* CONFIGURATION type = 2 or 7 */
uint16_t wTotalLength; /* Length of concatenated descriptors */
uint8_t bNumInterfaces; /* Number of interfaces, this config. */
uint8_t bConfigurationValue; /* Value to set this config. */
uint8_t iConfiguration; /* Index to configuration string */
uint8_t bmAttributes; /* Config. characteristics */
uint8_t bMaxPower; /* Max.power from bus, 2mA units */
} __packed;
/** Standard Interface Descriptor */
struct usb_interface_descriptor {
uint8_t bLength; /* Descriptor size in bytes = 9 */
uint8_t bDescriptorType; /* INTERFACE descriptor type = 4 */
uint8_t bInterfaceNumber; /* Interface no.*/
uint8_t bAlternateSetting; /* Value to select this IF */
uint8_t bNumEndpoints; /* Number of endpoints excluding 0 */
uint8_t bInterfaceClass; /* Class code, 0xFF = vendor */
uint8_t bInterfaceSubClass; /* Sub-Class code, 0 if class = 0 */
uint8_t bInterfaceProtocol; /* Protocol, 0xFF = vendor */
uint8_t iInterface; /* Index to interface string */
} __packed;
/** Standard Endpoint Descriptor */
struct usb_endpoint_descriptor {
uint8_t bLength; /* Descriptor size in bytes = 7 */
uint8_t bDescriptorType; /* ENDPOINT descriptor type = 5 */
uint8_t bEndpointAddress; /* Endpoint # 0 - 15 | IN/OUT */
uint8_t bmAttributes; /* Transfer type */
uint16_t wMaxPacketSize; /* Bits 10:0 = max. packet size */
uint8_t bInterval; /* Polling interval in (micro) frames */
} __packed;
/** Unicode (UTF16LE) String Descriptor */
struct usb_string_descriptor {
uint8_t bLength;
uint8_t bDescriptorType;
uint16_t bString;
} __packed;
/* USB Interface Association Descriptor */
struct usb_interface_association_descriptor {
uint8_t bLength;
uint8_t bDescriptorType;
uint8_t bFirstInterface;
uint8_t bInterfaceCount;
uint8_t bFunctionClass;
uint8_t bFunctionSubClass;
uint8_t bFunctionProtocol;
uint8_t iFunction;
} __packed;
/* MS OS 1.0 string descriptor */
struct usb_msosv1_string_descriptor {
uint8_t bLength;
uint8_t bDescriptorType;
uint8_t bString[14];
uint8_t bMS_VendorCode; /* Vendor Code, used for a control request */
uint8_t bPad; /* Padding byte for VendorCode look as UTF16 */
} __packed;
/* MS OS 1.0 Header descriptor */
struct usb_msosv1_compat_id_header_descriptor {
uint32_t dwLength;
uint16_t bcdVersion;
uint16_t wIndex;
uint8_t bCount;
uint8_t reserved[7];
} __packed;
/* MS OS 1.0 Function descriptor */
struct usb_msosv1_comp_id_function_descriptor {
uint8_t bFirstInterfaceNumber;
uint8_t reserved1;
uint8_t compatibleID[8];
uint8_t subCompatibleID[8];
uint8_t reserved2[6];
} __packed;
#define usb_msosv1_comp_id_create(x) \
struct usb_msosv1_comp_id { \
struct usb_msosv1_compat_id_header_descriptor compat_id_header; \
struct usb_msosv1_comp_id_function_descriptor compat_id_function[x]; \
};
struct usb_msosv1_descriptor {
uint8_t *string;
uint8_t string_len;
uint8_t vendor_code;
uint8_t *compat_id;
uint16_t compat_id_len;
uint8_t *comp_id_property;
uint16_t comp_id_property_len;
};
/* MS OS 2.0 Header descriptor */
struct usb_msosv2_header_descriptor {
uint32_t dwLength;
uint16_t bcdVersion;
uint16_t wIndex;
uint8_t bCount;
} __packed;
/*Microsoft OS 2.0 set header descriptor*/
struct usb_msosv2_set_header_descriptor {
uint16_t wLength;
uint16_t wDescriptorType;
uint32_t dwWindowsVersion;
uint16_t wDescriptorSetTotalLength;
} __packed;
/* Microsoft OS 2.0 compatibleID descriptor*/
struct usb_msosv2_comp_id_descriptor {
uint16_t wLength;
uint16_t wDescriptorType;
uint8_t compatibleID[8];
uint8_t subCompatibleID[8];
} __packed;
/* MS OS 2.0 property descriptor */
struct usb_msosv2_property_descriptor {
uint16_t wLength;
uint16_t wDescriptorType;
uint32_t dwPropertyDataType;
uint16_t wPropertyNameLength;
const char *bPropertyName;
uint32_t dwPropertyDataLength;
const char *bPropertyData;
};
/* Microsoft OS 2.0 subset function descriptor */
struct usb_msosv2_subset_function_descriptor {
uint16_t wLength;
uint16_t wDescriptorType;
uint8_t bFirstInterface;
uint8_t bReserved;
uint16_t wSubsetLength;
} __packed;
struct usb_msosv2_descriptor {
uint8_t *compat_id;
uint16_t compat_id_len;
uint8_t vendor_code;
};
/* BOS header Descriptor */
struct usb_bos_header_descriptor {
uint8_t bLength;
uint8_t bDescriptorType;
uint16_t wTotalLength;
uint8_t bNumDeviceCaps;
} __packed;
/* BOS Capability platform Descriptor */
struct usb_bos_capability_platform_descriptor {
uint8_t bLength;
uint8_t bDescriptorType;
uint8_t bDevCapabilityType;
uint8_t bReserved;
uint8_t PlatformCapabilityUUID[16];
} __packed;
/* BOS Capability MS OS Descriptors version 2 */
struct usb_bos_capability_msosv2_descriptor {
uint32_t dwWindowsVersion;
uint16_t wMSOSDescriptorSetTotalLength;
uint8_t bVendorCode;
uint8_t bAltEnumCode;
} __packed;
/* BOS Capability webusb */
struct usb_bos_capability_webusb_descriptor {
uint16_t bcdVersion;
uint8_t bVendorCode;
uint8_t iLandingPage;
} __packed;
/* BOS Capability extension Descriptor*/
struct usb_bos_capability_extension_descriptor {
uint8_t bLength;
uint8_t bDescriptorType;
uint8_t bDevCapabilityType;
uint32_t bmAttributes;
} __packed;
/* Microsoft OS 2.0 Platform Capability Descriptor
* See https://docs.microsoft.com/en-us/windows-hardware/drivers/usbcon/
* microsoft-defined-usb-descriptors
* Adapted from the source:
* https://github.com/sowbug/weblight/blob/master/firmware/webusb.c
* (BSD-2) Thanks http://janaxelson.com/files/ms_os_20_descriptors.c
*/
struct usb_bos_capability_platform_msosv2_descriptor {
struct usb_bos_capability_platform_descriptor platform_msos;
struct usb_bos_capability_msosv2_descriptor data_msosv2;
} __packed;
/* WebUSB Platform Capability Descriptor:
* https://wicg.github.io/webusb/#webusb-platform-capability-descriptor
*/
struct usb_bos_capability_platform_webusb_descriptor {
struct usb_bos_capability_platform_descriptor platform_webusb;
struct usb_bos_capability_webusb_descriptor data_webusb;
} __packed;
struct usb_webusb_url_descriptor {
uint8_t bLength;
uint8_t bDescriptorType;
uint8_t bScheme;
char URL[];
} __packed;
struct usb_bos_descriptor {
uint8_t *string;
uint32_t string_len;
};
/* USB Device Capability Descriptor */
struct usb_device_capability_descriptor {
uint8_t bLength;
uint8_t bDescriptorType;
uint8_t bDevCapabilityType;
} __packed;
/** USB descriptor header */
struct usb_desc_header {
uint8_t bLength; /**< descriptor length */
uint8_t bDescriptorType; /**< descriptor type */
};
// clang-format off
#define USB_DEVICE_DESCRIPTOR_INIT(bcdUSB, bDeviceClass, bDeviceSubClass, bDeviceProtocol, idVendor, idProduct, bcdDevice, bNumConfigurations) \
0x12, /* bLength */ \
USB_DESCRIPTOR_TYPE_DEVICE, /* bDescriptorType */ \
WBVAL(bcdUSB), /* bcdUSB */ \
bDeviceClass, /* bDeviceClass */ \
bDeviceSubClass, /* bDeviceSubClass */ \
bDeviceProtocol, /* bDeviceProtocol */ \
0x40, /* bMaxPacketSize */ \
WBVAL(idVendor), /* idVendor */ \
WBVAL(idProduct), /* idProduct */ \
WBVAL(bcdDevice), /* bcdDevice */ \
USB_STRING_MFC_INDEX, /* iManufacturer */ \
USB_STRING_PRODUCT_INDEX, /* iProduct */ \
USB_STRING_SERIAL_INDEX, /* iSerial */ \
bNumConfigurations /* bNumConfigurations */
#define USB_CONFIG_DESCRIPTOR_INIT(wTotalLength, bNumInterfaces, bConfigurationValue, bmAttributes, bMaxPower) \
0x09, /* bLength */ \
USB_DESCRIPTOR_TYPE_CONFIGURATION, /* bDescriptorType */ \
WBVAL(wTotalLength), /* wTotalLength */ \
bNumInterfaces, /* bNumInterfaces */ \
bConfigurationValue, /* bConfigurationValue */ \
0x00, /* iConfiguration */ \
bmAttributes, /* bmAttributes */ \
USB_CONFIG_POWER_MA(bMaxPower) /* bMaxPower */
#define USB_INTERFACE_DESCRIPTOR_INIT(bInterfaceNumber, bAlternateSetting, bNumEndpoints, \
bInterfaceClass, bInterfaceSubClass, bInterfaceProtocol, iInterface) \
0x09, /* bLength */ \
USB_DESCRIPTOR_TYPE_INTERFACE, /* bDescriptorType */ \
bInterfaceNumber, /* bInterfaceNumber */ \
bAlternateSetting, /* bAlternateSetting */ \
bNumEndpoints, /* bNumEndpoints */ \
bInterfaceClass, /* bInterfaceClass */ \
bInterfaceSubClass, /* bInterfaceSubClass */ \
bInterfaceProtocol, /* bInterfaceProtocol */ \
iInterface /* iInterface */
#define USB_ENDPOINT_DESCRIPTOR_INIT(bEndpointAddress, bmAttributes, wMaxPacketSize, bInterval) \
0x07, /* bLength */ \
USB_DESCRIPTOR_TYPE_ENDPOINT, /* bDescriptorType */ \
bEndpointAddress, /* bEndpointAddress */ \
bmAttributes, /* bmAttributes */ \
WBVAL(wMaxPacketSize), /* wMaxPacketSize */ \
bInterval /* bInterval */
#define USB_IAD_INIT(bFirstInterface, bInterfaceCount, bFunctionClass, bFunctionSubClass, bFunctionProtocol) \
0x08, /* bLength */ \
USB_DESCRIPTOR_TYPE_INTERFACE_ASSOCIATION, /* bDescriptorType */ \
bFirstInterface, /* bFirstInterface */ \
bInterfaceCount, /* bInterfaceCount */ \
bFunctionClass, /* bFunctionClass */ \
bFunctionSubClass, /* bFunctionSubClass */ \
bFunctionProtocol, /* bFunctionProtocol */ \
0x00 /* iFunction */
#define USB_LANGID_INIT(id) \
0x04, /* bLength */ \
USB_DESCRIPTOR_TYPE_STRING, /* bDescriptorType */ \
WBVAL(id) /* wLangID0 */
// clang-format on
#endif

View File

@@ -0,0 +1,224 @@
#ifndef __USB_SLIST_H__
#define __USB_SLIST_H__
#include "string.h"
#include "stdint.h"
#ifdef __cplusplus
extern "C" {
#endif
/**
* usb_container_of - return the member address of ptr, if the type of ptr is the
* struct type.
*/
#define usb_container_of(ptr, type, member) \
((type *)((char *)(ptr) - (unsigned long)(&((type *)0)->member)))
/**
* Single List structure
*/
struct usb_slist_node {
struct usb_slist_node *next; /**< point to next node. */
};
typedef struct usb_slist_node usb_slist_t; /**< Type for single list. */
/**
* @brief initialize a single list
*
* @param l the single list to be initialized
*/
static inline void usb_slist_init(usb_slist_t *l)
{
l->next = NULL;
}
static inline void usb_slist_add_head(usb_slist_t *l, usb_slist_t *n)
{
n->next = l->next;
l->next = n;
}
static inline void usb_slist_add_tail(usb_slist_t *l, usb_slist_t *n)
{
while (l->next) {
l = l->next;
}
/* append the node to the tail */
l->next = n;
n->next = NULL;
}
static inline void usb_slist_insert(usb_slist_t *l, usb_slist_t *next, usb_slist_t *n)
{
if (!next) {
usb_slist_add_tail(next, l);
return;
}
while (l->next) {
if (l->next == next) {
l->next = n;
n->next = next;
}
l = l->next;
}
}
static inline usb_slist_t *usb_slist_remove(usb_slist_t *l, usb_slist_t *n)
{
/* remove slist head */
while (l->next && l->next != n) {
l = l->next;
}
/* remove node */
if (l->next != (usb_slist_t *)0) {
l->next = l->next->next;
}
return l;
}
static inline unsigned int usb_slist_len(const usb_slist_t *l)
{
unsigned int len = 0;
const usb_slist_t *list = l->next;
while (list != NULL) {
list = list->next;
len++;
}
return len;
}
static inline unsigned int usb_slist_contains(usb_slist_t *l, usb_slist_t *n)
{
while (l->next) {
if (l->next == n) {
return 0;
}
l = l->next;
}
return 1;
}
static inline usb_slist_t *usb_slist_head(usb_slist_t *l)
{
return l->next;
}
static inline usb_slist_t *usb_slist_tail(usb_slist_t *l)
{
while (l->next) {
l = l->next;
}
return l;
}
static inline usb_slist_t *usb_slist_next(usb_slist_t *n)
{
return n->next;
}
static inline int usb_slist_isempty(usb_slist_t *l)
{
return l->next == NULL;
}
/**
* @brief initialize a slist object
*/
#define USB_SLIST_OBJECT_INIT(object) \
{ \
NULL \
}
/**
* @brief initialize a slist object
*/
#define USB_SLIST_DEFINE(slist) \
usb_slist_t slist = { NULL }
/**
* @brief get the struct for this single list node
* @param node the entry point
* @param type the type of structure
* @param member the name of list in structure
*/
#define usb_slist_entry(node, type, member) \
usb_container_of(node, type, member)
/**
* usb_slist_first_entry - get the first element from a slist
* @ptr: the slist head to take the element from.
* @type: the type of the struct this is embedded in.
* @member: the name of the slist_struct within the struct.
*
* Note, that slist is expected to be not empty.
*/
#define usb_slist_first_entry(ptr, type, member) \
usb_slist_entry((ptr)->next, type, member)
/**
* usb_slist_tail_entry - get the tail element from a slist
* @ptr: the slist head to take the element from.
* @type: the type of the struct this is embedded in.
* @member: the name of the slist_struct within the struct.
*
* Note, that slist is expected to be not empty.
*/
#define usb_slist_tail_entry(ptr, type, member) \
usb_slist_entry(usb_slist_tail(ptr), type, member)
/**
* usb_slist_first_entry_or_null - get the first element from a slist
* @ptr: the slist head to take the element from.
* @type: the type of the struct this is embedded in.
* @member: the name of the slist_struct within the struct.
*
* Note, that slist is expected to be not empty.
*/
#define usb_slist_first_entry_or_null(ptr, type, member) \
(usb_slist_isempty(ptr) ? NULL : usb_slist_first_entry(ptr, type, member))
/**
* usb_slist_for_each - iterate over a single list
* @pos: the usb_slist_t * to use as a loop cursor.
* @head: the head for your single list.
*/
#define usb_slist_for_each(pos, head) \
for (pos = (head)->next; pos != NULL; pos = pos->next)
#define usb_slist_for_each_safe(pos, next, head) \
for (pos = (head)->next, next = pos->next; pos; \
pos = next, next = pos->next)
/**
* usb_slist_for_each_entry - iterate over single list of given type
* @pos: the type * to use as a loop cursor.
* @head: the head for your single list.
* @member: the name of the list_struct within the struct.
*/
#define usb_slist_for_each_entry(pos, head, member) \
for (pos = usb_slist_entry((head)->next, typeof(*pos), member); \
&pos->member != (NULL); \
pos = usb_slist_entry(pos->member.next, typeof(*pos), member))
#define usb_slist_for_each_entry_safe(pos, n, head, member) \
for (pos = usb_slist_entry((head)->next, typeof(*pos), member), \
n = usb_slist_entry(pos->member.next, typeof(*pos), member); \
&pos->member != (NULL); \
pos = n, n = usb_slist_entry(pos->member.next, typeof(*pos), member))
#ifdef __cplusplus
}
#endif
#endif

View File

@@ -0,0 +1,150 @@
#ifndef _USB_UTIL_H
#define _USB_UTIL_H
#include "stdbool.h"
#include "string.h"
#include "stdint.h"
#include "stdio.h"
#include "stdlib.h"
#include "usb_slist.h"
#include "bflb_platform.h"
#ifndef __packed
#define __packed __attribute__((__packed__))
#endif
#ifndef __aligned
#define __aligned(x) __attribute__((__aligned__(x)))
#endif
#define __may_alias __attribute__((__may_alias__))
#ifndef __printf_like
#define __printf_like(f, a) __attribute__((format(printf, f, a)))
#endif
#define __used __attribute__((__used__))
#ifndef __deprecated
#define __deprecated __attribute__((deprecated))
#endif
#define ARG_UNUSED(x) (void)(x)
// #define likely(x) __builtin_expect((bool)!!(x), true)
// #define unlikely(x) __builtin_expect((bool)!!(x), false)
#define popcount(x) __builtin_popcount(x)
#ifndef __no_optimization
#define __no_optimization __attribute__((optimize("-O0")))
#endif
#ifndef __weak
#define __weak __attribute__((__weak__))
#endif
#define __unused __attribute__((__unused__))
#ifndef __ALIGN_BEGIN
#define __ALIGN_BEGIN
#endif
#ifndef __ALIGN_END
#define __ALIGN_END __attribute__((aligned(4)))
#endif
#ifndef LO_BYTE
#define LO_BYTE(x) ((uint8_t)(x & 0x00FF))
#endif
#ifndef HI_BYTE
#define HI_BYTE(x) ((uint8_t)((x & 0xFF00) >> 8))
#endif
/**
* @def MAX
* @brief The larger value between @p a and @p b.
* @note Arguments are evaluated twice.
*/
#ifndef MAX
/* Use Z_MAX for a GCC-only, single evaluation version */
#define MAX(a, b) (((a) > (b)) ? (a) : (b))
#endif
/**
* @def MIN
* @brief The smaller value between @p a and @p b.
* @note Arguments are evaluated twice.
*/
#ifndef MIN
/* Use Z_MIN for a GCC-only, single evaluation version */
#define MIN(a, b) (((a) < (b)) ? (a) : (b))
#endif
#ifndef BCD
#define BCD(x) ((((x) / 10) << 4) | ((x) % 10))
#endif
#ifdef BIT
#undef BIT
#define BIT(n) (1UL << (n))
#else
#define BIT(n) (1UL << (n))
#endif
#ifndef ARRAY_SIZE
#define ARRAY_SIZE(array) \
((int)((sizeof(array) / sizeof((array)[0]))))
#endif
#ifndef BSWAP16
#define BSWAP16(u16) (__builtin_bswap16(u16))
#endif
#ifndef BSWAP32
#define BSWAP32(u32) (__builtin_bswap32(u32))
#endif
#define GET_BE16(field) \
(((uint16_t)(field)[0] << 8) | ((uint16_t)(field)[1]))
#define GET_BE32(field) \
(((uint32_t)(field)[0] << 24) | ((uint32_t)(field)[1] << 16) | ((uint32_t)(field)[2] << 8) | ((uint32_t)(field)[3] << 0))
#define SET_BE16(field, value) \
do { \
(field)[0] = (uint8_t)((value) >> 8); \
(field)[1] = (uint8_t)((value) >> 0); \
} while (0)
#define SET_BE24(field, value) \
do { \
(field)[0] = (uint8_t)((value) >> 16); \
(field)[1] = (uint8_t)((value) >> 8); \
(field)[2] = (uint8_t)((value) >> 0); \
} while (0)
#define SET_BE32(field, value) \
do { \
(field)[0] = (uint8_t)((value) >> 24); \
(field)[1] = (uint8_t)((value) >> 16); \
(field)[2] = (uint8_t)((value) >> 8); \
(field)[3] = (uint8_t)((value) >> 0); \
} while (0)
#define REQTYPE_GET_DIR(x) (((x) >> 7) & 0x01)
#define REQTYPE_GET_TYPE(x) (((x) >> 5) & 0x03U)
#define REQTYPE_GET_RECIP(x) ((x)&0x1F)
#define GET_DESC_TYPE(x) (((x) >> 8) & 0xFFU)
#define GET_DESC_INDEX(x) ((x)&0xFFU)
#define WBVAL(x) (x & 0xFF), ((x >> 8) & 0xFF)
#define DBVAL(x) (x & 0xFF), ((x >> 8) & 0xFF), ((x >> 16) & 0xFF), ((x >> 24) & 0xFF)
#define USB_DESC_SECTION __attribute__((section("usb_desc"))) __used __aligned(1)
#if 0
#define USBD_LOG_WRN(a, ...) bflb_platform_printf(a, ##__VA_ARGS__)
#define USBD_LOG_DBG(a, ...) bflb_platform_printf(a, ##__VA_ARGS__)
#define USBD_LOG_ERR(a, ...) bflb_platform_printf(a, ##__VA_ARGS__)
#else
#define USBD_LOG_INFO(a, ...) bflb_platform_printf(a, ##__VA_ARGS__)
#define USBD_LOG_DBG(a, ...)
#define USBD_LOG_WRN(a, ...) bflb_platform_printf(a, ##__VA_ARGS__)
#define USBD_LOG_ERR(a, ...) bflb_platform_printf(a, ##__VA_ARGS__)
#endif
#endif

File diff suppressed because it is too large Load Diff

View File

@@ -0,0 +1,138 @@
/**
* @file usbd_core.h
*
* Copyright (c) 2021 Bouffalolab team
*
* Licensed to the Apache Software Foundation (ASF) under one or more
* contributor license agreements. See the NOTICE file distributed with
* this work for additional information regarding copyright ownership. The
* ASF licenses this file to you under the Apache License, Version 2.0 (the
* "License"); you may not use this file except in compliance with the
* License. You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
* License for the specific language governing permissions and limitations
* under the License.
*
*/
#ifndef _USBD_CORE_H
#define _USBD_CORE_H
#ifdef __cplusplus
extern "C" {
#endif
#include "usb_util.h"
#include "usb_def.h"
#include "usb_dc.h"
enum usb_event_type {
/** USB error reported by the controller */
USB_EVENT_ERROR,
/** USB reset */
USB_EVENT_RESET,
/** Start of Frame received */
USB_EVENT_SOF,
/** USB connection established, hardware enumeration is completed */
USB_EVENT_CONNECTED,
/** USB configuration done */
USB_EVENT_CONFIGURED,
/** USB connection suspended by the HOST */
USB_EVENT_SUSPEND,
/** USB connection lost */
USB_EVENT_DISCONNECTED,
/** USB connection resumed by the HOST */
USB_EVENT_RESUME,
/** USB interface selected */
USB_EVENT_SET_INTERFACE,
/** USB interface selected */
USB_EVENT_SET_REMOTE_WAKEUP,
/** USB interface selected */
USB_EVENT_CLEAR_REMOTE_WAKEUP,
/** Set Feature ENDPOINT_HALT received */
USB_EVENT_SET_HALT,
/** Clear Feature ENDPOINT_HALT received */
USB_EVENT_CLEAR_HALT,
/** setup packet received */
USB_EVENT_SETUP_NOTIFY,
/** ep0 in packet received */
USB_EVENT_EP0_IN_NOTIFY,
/** ep0 out packet received */
USB_EVENT_EP0_OUT_NOTIFY,
/** ep in packet except ep0 received */
USB_EVENT_EP_IN_NOTIFY,
/** ep out packet except ep0 received */
USB_EVENT_EP_OUT_NOTIFY,
/** Initial USB connection status */
USB_EVENT_UNKNOWN
};
/**
* @brief Callback function signature for the USB Endpoint status
*/
typedef void (*usbd_endpoint_callback)(uint8_t ep);
/**
* @brief Callback function signature for class specific requests
*
* Function which handles Class specific requests corresponding to an
* interface number specified in the device descriptor table. For host
* to device direction the 'len' and 'payload_data' contain the length
* of the received data and the pointer to the received data respectively.
* For device to host class requests, 'len' and 'payload_data' should be
* set by the callback function with the length and the address of the
* data to be transmitted buffer respectively.
*/
typedef int (*usbd_request_handler)(struct usb_setup_packet *setup,
uint8_t **data, uint32_t *transfer_len);
/* callback function pointer structure for Application to handle events */
typedef void (*usbd_notify_handler)(uint8_t event, void *arg);
typedef struct usbd_endpoint {
usb_slist_t list;
uint8_t ep_addr;
usbd_endpoint_callback ep_cb;
} usbd_endpoint_t;
typedef struct usbd_interface {
usb_slist_t list;
/** Handler for USB Class specific Control (EP 0) communications */
usbd_request_handler class_handler;
/** Handler for USB Vendor specific commands */
usbd_request_handler vendor_handler;
/** Handler for USB custom specific commands */
usbd_request_handler custom_handler;
/** Handler for USB event notify commands */
usbd_notify_handler notify_handler;
uint8_t intf_num;
usb_slist_t ep_list;
} usbd_interface_t;
typedef struct usbd_class {
usb_slist_t list;
const char *name;
usb_slist_t intf_list;
} usbd_class_t;
void usbd_event_notify_handler(uint8_t event, void *arg);
void usbd_desc_register(const uint8_t *desc);
void usbd_class_register(usbd_class_t *class);
void usbd_msosv1_desc_register(struct usb_msosv1_descriptor *desc);
void usbd_msosv2_desc_register(struct usb_msosv2_descriptor *desc);
void usbd_bos_desc_register(struct usb_bos_descriptor *desc);
void usbd_class_add_interface(usbd_class_t *class, usbd_interface_t *intf);
void usbd_interface_add_endpoint(usbd_interface_t *intf, usbd_endpoint_t *ep);
bool usb_device_is_configured(void);
#ifdef __cplusplus
}
#endif
#endif

View File

@@ -0,0 +1,64 @@
################# Add global include #################
list(APPEND ADD_INCLUDE
"${CMAKE_CURRENT_SOURCE_DIR}/hal_drv/inc"
"${CMAKE_CURRENT_SOURCE_DIR}/std_drv/inc"
"${CMAKE_CURRENT_SOURCE_DIR}/regs"
"${CMAKE_CURRENT_SOURCE_DIR}/startup"
"${CMAKE_CURRENT_SOURCE_DIR}"
)
#######################################################
################# Add private include #################
list(APPEND ADD_PRIVATE_INCLUDE
"${CMAKE_CURRENT_SOURCE_DIR}/hal_drv/default_config"
)
#######################################################
############## Add current dir source files ###########
file(GLOB_RECURSE sources
"${CMAKE_CURRENT_SOURCE_DIR}/std_drv/src/*.c"
"${CMAKE_CURRENT_SOURCE_DIR}/hal_drv/src/*.c"
"${CMAKE_CURRENT_SOURCE_DIR}/startup/interrupt.c"
"${CMAKE_CURRENT_SOURCE_DIR}/startup/system_bl702.c"
"${CMAKE_CURRENT_SOURCE_DIR}/startup/GCC/entry.S"
"${CMAKE_CURRENT_SOURCE_DIR}/startup/GCC/start_load.c"
)
list(APPEND ADD_SRCS ${sources})
# aux_source_directory(src ADD_SRCS)
list(REMOVE_ITEM ADD_SRCS "${CMAKE_CURRENT_SOURCE_DIR}/std_drv/src/bl702_snflash.c"
"${CMAKE_CURRENT_SOURCE_DIR}/std_drv/src/bl702_romdriver.c"
"${CMAKE_CURRENT_SOURCE_DIR}/std_drv/src/bl702_clock.c"
)
#######################################################
########### Add required/dependent components #########
list(APPEND ADD_REQUIREMENTS common)
#######################################################
############ Add static libs ##########################
#list(APPEND ADD_STATIC_LIB "lib/libtest.a")
#######################################################
############ Add dynamic libs #########################
# list(APPEND ADD_DYNAMIC_LIB "lib/arch/v831/libmaix_nn.so"
# "lib/arch/v831/libmaix_cam.so"
# )
#######################################################
############ Add global compile option ################
#add components denpend on this component
if(CONFIG_ROMAPI)
list(APPEND ADD_DEFINITIONS -DBFLB_USE_ROM_DRIVER)
endif()
if(CONFIG_HALAPI)
list(APPEND ADD_DEFINITIONS -DBFLB_USE_HAL_DRIVER)
endif()
list(APPEND ADD_DEFINITIONS -DARCH_RISCV)
#######################################################
############ Add private compile option ################
#add compile option for this component that won't affect other modules
# list(APPEND ADD_PRIVATE_DEFINITIONS -DAAAAA=1)
#######################################################
generate_library()

View File

@@ -0,0 +1,299 @@
/****************************************************************************************
* @file bl702_flash.ld
*
* @brief This file is the map file (gnuarm or armgcc).
*
* Copyright (C) BouffaloLab 2021
*
****************************************************************************************
*/
/* configure the CPU type */
OUTPUT_ARCH( "riscv" )
/* link with the standard c library */
/* INPUT(-lc) */
/* link with the standard GCC library */
/* INPUT(-lgcc) */
/* configure the entry point */
ENTRY(_enter)
StackSize = 0x1000; /* 4KB */
MEMORY
{
xip_memory (rx) : ORIGIN = 0x23000000, LENGTH = 1022K /* 1024K, less the two pages we are using for settings and logo*/
itcm_memory (rx) : ORIGIN = 0x22014000, LENGTH = 16K
dtcm_memory (rx) : ORIGIN = 0x42018000, LENGTH = 16K
ram_memory (!rx) : ORIGIN = 0x4201C000, LENGTH = 80K
hbn_memory (rx) : ORIGIN = 0x40010000, LENGTH = 0xE00 /* hbn ram 4K used 3.5K*/
}
SECTIONS
{
PROVIDE(__metal_chicken_bit = 0);
.text :
{
. = ALIGN(4);
__text_code_start__ = .;
KEEP (*(.text.metal.init.enter))
KEEP (*(SORT_NONE(.init)))
/* section information for shell */
. = ALIGN(4);
__fsymtab_start = .;
KEEP(*(FSymTab))
__fsymtab_end = .;
. = ALIGN(4);
__vsymtab_start = .;
KEEP(*(VSymTab))
__vsymtab_end = .;
/* section information for usb desc */
. = ALIGN(4);
_usb_desc_start = .;
KEEP(*(usb_desc))
. = ALIGN(4);
_usb_desc_end = .;
*(.text)
*(.text.*)
/*put .rodata**/
*(EXCLUDE_FILE( *bl702_glb*.o* \
*bl702_pds*.o* \
*bl702_common*.o* \
*bl702_sf_cfg*.o* \
*bl702_sf_cfg_ext*.o* \
*bl702_sf_ctrl*.o* \
*bl702_sflash*.o* \
*bl702_sflash_ext*.o* \
*bl702_xip_sflash*.o* \
*bl702_xip_sflash_ext*.o* \
*bl702_ef_ctrl*.o*) .rodata*)
*(.srodata)
*(.srodata.*)
. = ALIGN(4);
__text_code_end__ = .;
} > xip_memory
.preinit_array :
{
PROVIDE_HIDDEN (__preinit_array_start = .);
KEEP (*(.preinit_array))
PROVIDE_HIDDEN (__preinit_array_end = .);
} >xip_memory AT>xip_memory
.init_array :
{
PROVIDE_HIDDEN (__init_array_start = .);
KEEP (*(SORT_BY_INIT_PRIORITY(.init_array.*) SORT_BY_INIT_PRIORITY(.ctors.*)))
KEEP (*(.init_array EXCLUDE_FILE (*crtbegin.o *crtbegin?.o *crtend.o *crtend?.o ) .ctors))
PROVIDE_HIDDEN (__init_array_end = .);
} >xip_memory AT>xip_memory
.fini_array :
{
PROVIDE_HIDDEN (__fini_array_start = .);
KEEP (*(SORT_BY_INIT_PRIORITY(.fini_array.*) SORT_BY_INIT_PRIORITY(.dtors.*)))
KEEP (*(.fini_array EXCLUDE_FILE (*crtbegin.o *crtbegin?.o *crtend.o *crtend?.o ) .dtors))
PROVIDE_HIDDEN (__fini_array_end = .);
} >xip_memory AT>xip_memory
.ctors :
{
/* gcc uses crtbegin.o to find the start of
* the constructors, so we make sure it is
* first. Because this is a wildcard, it
* doesn't matter if the user does not
* actually link against crtbegin.o; the
* linker won't look for a file to match a
* wildcard. The wildcard also means that it
* doesn't matter which directory crtbegin.o
* is in.
*/
KEEP (*crtbegin.o(.ctors))
KEEP (*crtbegin?.o(.ctors))
/* We don't want to include the .ctor section from
* the crtend.o file until after the sorted ctors.
* The .ctor section from the crtend file contains the
* end of ctors marker and it must be last
*/
KEEP (*(EXCLUDE_FILE (*crtend.o *crtend?.o ) .ctors))
KEEP (*(SORT(.ctors.*)))
KEEP (*(.ctors))
} >xip_memory AT>xip_memory
.dtors :
{
KEEP (*crtbegin.o(.dtors))
KEEP (*crtbegin?.o(.dtors))
KEEP (*(EXCLUDE_FILE (*crtend.o *crtend?.o ) .dtors))
KEEP (*(SORT(.dtors.*)))
KEEP (*(.dtors))
} >xip_memory AT>xip_memory
.lalign :
{
. = ALIGN(4);
PROVIDE( _data_lma = . );
} >xip_memory AT>xip_memory
. = ALIGN(4);
__itcm_load_addr = .;
.itcm_region : AT (__itcm_load_addr)
{
. = ALIGN(4);
__tcm_code_start__ = .;
*(.tcm_code.*)
*(.tcm_const.*)
*(.sclock_rlt_code.*)
*(.sclock_rlt_const.*)
*bl702_glb*.o*(.rodata*)
*bl702_pds*.o*(.rodata*)
*bl702_common*.o*(.rodata*)
*bl702_sf_cfg*.o*(.rodata*)
*bl702_sf_cfg_ext*.o*(.rodata*)
*bl702_sf_ctrl*.o*(.rodata*)
*bl702_sflash*.o*(.rodata*)
*bl702_sflash_ext*.o*(.rodata*)
*bl702_xip_sflash*.o*(.rodata*)
*bl702_xip_sflash_ext*.o*(.rodata*)
*bl702_ef_ctrl*.o*(.rodata*)
. = ALIGN(4);
__tcm_code_end__ = .;
} > itcm_memory
__hbn_load_addr = __itcm_load_addr + SIZEOF(.itcm_region);
.hbn_ram_region : AT (__hbn_load_addr)
{
. = ALIGN(4);
__hbn_ram_start__ = .;
*bl702_hbn_wakeup*.o*(.rodata*)
*(.hbn_ram_code*)
*(.hbn_ram_data)
. = ALIGN(4);
__hbn_ram_end__ = .;
} > hbn_memory
__dtcm_load_addr = __hbn_load_addr + SIZEOF(.hbn_ram_region);
.dtcm_region : AT (__dtcm_load_addr)
{
. = ALIGN(4);
__tcm_data_start__ = .;
*(.tcm_data)
/* *finger_print.o(.data*) */
. = ALIGN(4);
__tcm_data_end__ = .;
} > dtcm_memory
/*************************************************************************/
/* .stack_dummy section doesn't contains any symbols. It is only
* used for linker to calculate size of stack sections, and assign
* values to stack symbols later */
.stack_dummy (NOLOAD):
{
. = ALIGN(0x4);
. = . + StackSize;
. = ALIGN(0x4);
} > dtcm_memory
/* Set stack top to end of RAM, and stack limit move down by
* size of stack_dummy section */
__StackTop = ORIGIN(dtcm_memory) + LENGTH(dtcm_memory);
PROVIDE( __freertos_irq_stack_top = __StackTop);
__StackLimit = __StackTop - SIZEOF(.stack_dummy);
/* Check if data + heap + stack exceeds RAM limit */
ASSERT(__StackLimit >= __tcm_data_end__, "region RAM overflowed with stack")
/*************************************************************************/
__system_ram_load_addr = __dtcm_load_addr + SIZEOF(.dtcm_region);
.system_ram_data_region : AT (__system_ram_load_addr)
{
. = ALIGN(4);
__system_ram_data_start__ = .;
*(.system_ram)
. = ALIGN(4);
__system_ram_data_end__ = .;
} > ram_memory
__ram_load_addr = __system_ram_load_addr + SIZEOF(.system_ram_data_region);
/* Data section */
RAM_DATA : AT (__ram_load_addr)
{
. = ALIGN(4);
__ram_data_start__ = .;
PROVIDE( __global_pointer$ = . + 0x800 );
*(.data)
*(.data.*)
*(.sdata)
*(.sdata.*)
*(.sdata2)
*(.sdata2.*)
. = ALIGN(4);
__ram_data_end__ = .;
} > ram_memory
.bss (NOLOAD) :
{
. = ALIGN(4);
__bss_start__ = .;
*(.bss*)
*(.sbss*)
*(COMMON)
. = ALIGN(4);
__bss_end__ = .;
} > ram_memory
.noinit_data (NOLOAD) :
{
. = ALIGN(4);
__noinit_data_start__ = .;
*(.noinit_data*)
. = ALIGN(4);
__noinit_data_end__ = .;
} > ram_memory
.heap (NOLOAD):
{
. = ALIGN(4);
__HeapBase = .;
KEEP(*(.heap*))
. = ALIGN(4);
__HeapLimit = .;
} > ram_memory
PROVIDE (__heap_min_size = 0x400);
__HeapLimit = ORIGIN(ram_memory) + LENGTH(ram_memory);
ASSERT((__HeapLimit - __HeapBase ) >= __heap_min_size, "heap size is too short.")
}

View File

@@ -0,0 +1,11 @@
SET(CPU_ARCH "RISCV")
SET(MCPU "riscv-e24")
SET(MARCH "rv32imafc")
SET(MABI "ilp32f")
list(APPEND GLOBAL_C_FLAGS -march=${MARCH} -mabi=${MABI})
list(APPEND GLOBAL_LD_FLAGS -march=${MARCH} -mabi=${MABI})
SET(LINKER_SCRIPT ${CMAKE_CURRENT_LIST_DIR}/bl702_flash.ld)
SET(RAM_LINKER_SCRIPT ${CMAKE_CURRENT_LIST_DIR}/bl702_ram.ld)
SET(BOOT2_LINKER_SCRIPT ${CMAKE_CURRENT_LIST_DIR}/blsp_boot2_iap_flash.ld)

View File

@@ -0,0 +1,17 @@
#ifndef _ADC_CONFIG_H
#define _ADC_CONFIG_H
#define ADC_DATA_WIDIH_12 (0)
#define ADC_V18_SELECT (2) /*!< ADC 1.8V select */
#define ADC_V11_SELECT (1) /*!< ADC 1.1V select */
#define ADC_PGA_VCM (0) /*!< ADC VCM value */
#define ADC_PGA_GAIN1 (0) /*!< PGA gain 1 */
#define ADC_PGA_GAIN2 (0) /*!< PGA gain 2 */
#define ADC_CHOP_MODE (2) /*!< ADC chop mode select */
#define ADC_BIAS_SELECT (0) /*!< ADC current form main bandgap or aon bandgap */
#define ADC_OFFSET_CALIB_EN (0) /*!< Offset calibration enable */
#define ADC_OFFSER_CALIB_VAL (0) /*!< Offset calibration value */
#endif

View File

@@ -0,0 +1,7 @@
#ifndef _DAC_CONFIG_H
#define _DAC_CONFIG_H
#define DAC_REF_SEL (0)
#define DAC_EXT_REF_GPIO (7)
#endif

View File

@@ -0,0 +1,11 @@
#ifndef _I2S_CONFIG_H
#define _I2S_CONFIG_H
#define I2S_ADUIO_PLL_DEFAULT AUDIO_PLL_12288000_HZ
#define I2S_DATA_ENDIAN I2S_DATA_ENDIAN_MSB
#define I2S_MONO_CHANNEL I2S_RX_MONO_MODE_RIGHT_CHANNEL
#define I2S_LR_EXCHANGE DISABLE /*The position of L/R channel data within each entry is exchanged if enabled*/
#define I2S_FS_INVERT DISABLE
#define I2S_BCLK_INVERT DISABLE
#endif

View File

@@ -0,0 +1,16 @@
#ifndef _UART_CONFIG_H
#define _UART_CONFIG_H
#define UART_CTS_FLOWCONTROL_ENABLE (0)
#define UART_RTS_FLOWCONTROL_ENABLE (0)
#define UART_RX_DEGLITCH_ENABLE (0)
#define UART_MSB_FIRST_ENABLE (0)
#define UART_TX_SWCONTROL_ENABLE (0)
#define UART_TX_LINMODE_ENABLE (0)
#define UART_RX_LINMODE_ENABLE (0)
#define UART_TX_BREAKBIT_CNT (0)
#define UART_FIFO_MAX_LEN 128
#define UART_DEFAULT_RTO_TIMEOUT 100
#endif

View File

@@ -0,0 +1,185 @@
/**
* @file hal_adc.h
* @brief
*
* Copyright (c) 2021 Bouffalolab team
*
* Licensed to the Apache Software Foundation (ASF) under one or more
* contributor license agreements. See the NOTICE file distributed with
* this work for additional information regarding copyright ownership. The
* ASF licenses this file to you under the Apache License, Version 2.0 (the
* "License"); you may not use this file except in compliance with the
* License. You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
* License for the specific language governing permissions and limitations
* under the License.
*
*/
#ifndef __HAL_ADC__H__
#define __HAL_ADC__H__
#ifdef __cplusplus
extern "C" {
#endif
#include "hal_common.h"
#include "drv_device.h"
#include "bl702_config.h"
#define DEVICE_CTRL_ADC_CHANNEL_START 0x10
#define DEVICE_CTRL_ADC_CHANNEL_STOP 0x11
#define DEVICE_CTRL_ADC_CHANNEL_CONFIG 0x12
#define DEVICE_CTRL_ADC_VBAT_ON 0x13
#define DEVICE_CTRL_ADC_VBAT_OFF 0x14
#define DEVICE_CTRL_ADC_TSEN_ON 0x15
#define DEVICE_CTRL_ADC_TSEN_OFF 0x16
#define DEVICE_CTRL_ADC_DATA_PARSE 0x17
enum adc_index_type {
#ifdef BSP_USING_ADC0
ADC0_INDEX,
#endif
ADC_MAX_INDEX
};
#define adc_channel_start(dev) device_control(dev, DEVICE_CTRL_ADC_CHANNEL_START, NULL)
#define adc_channel_stop(dev) device_control(dev, DEVICE_CTRL_ADC_CHANNEL_STOP, NULL)
#define adc_channel_config(dev, list) device_control(dev, DEVICE_CTRL_ADC_CHANNEL_CONFIG, list)
typedef enum {
ADC_CHANNEL0, /* ADC channel 0 */
ADC_CHANNEL1, /* ADC channel 1 */
ADC_CHANNEL2, /* ADC channel 2 */
ADC_CHANNEL3, /* ADC channel 3 */
ADC_CHANNEL4, /* ADC channel 4 */
ADC_CHANNEL5, /* ADC channel 5 */
ADC_CHANNEL6, /* ADC channel 6 */
ADC_CHANNEL7, /* ADC channel 7 */
ADC_CHANNEL8, /* ADC channel 8 */
ADC_CHANNEL9, /* ADC channel 9 */
ADC_CHANNEL10, /* ADC channel 10 */
ADC_CHANNEL11, /* ADC channel 11 */
ADC_CHANNEL_DAC_OUTA, /* DACA, ADC channel 12 */
ADC_CHANNEL_DAC_OUTB, /* DACB, ADC channel 13 */
ADC_CHANNEL_TSEN_P, /* TSenp, ADC channel 14 */
ADC_CHANNEL_TSEN_N, /* TSenn, ADC channel 15 */
ADC_CHANNEL_VREF, /* Vref, ADC channel 16 */
ADC_CHANNEL_DCTEST, /* DCTest, ADC channel 17 */
ADC_CHANNEL_VABT_HALF, /* VBAT/2, ADC channel 18 */
ADC_CHANNEL_SENP3, /* SenVP3, ADC channel 19 */
ADC_CHANNEL_SENP2, /* SenVP2, ADC channel 20 */
ADC_CHANNEL_SENP1, /* SenVP1, ADC channel 21 */
ADC_CHANNEL_SENP0, /* SenVP0, ADC channel 22 */
ADC_CHANNEL_GND, /* GND, ADC channel 23 */
} adc_channel_t;
typedef enum {
ADC_CLOCK_DIV_1, /*!< ADC clock:on 32M clock is 32M */
ADC_CLOCK_DIV_4, /*!< ADC clock:on 32M clock is 8M */
ADC_CLOCK_DIV_8, /*!< ADC clock:on 32M clock is 4M */
ADC_CLOCK_DIV_12, /*!< ADC clock:on 32M clock is 2.666M */
ADC_CLOCK_DIV_16, /*!< ADC clock:on 32M clock is 2M */
ADC_CLOCK_DIV_20, /*!< ADC clock:on 32M clock is 1.6M */
ADC_CLOCK_DIV_24, /*!< ADC clock:on 32M clock is 1.333M */
ADC_CLOCK_DIV_32, /*!< ADC clock:on 32M clock is 1M */
} adc_clk_div_t;
typedef enum {
ADC_VREF_3V2 = 0, /* ADC select 3.2V as reference voltage */
ADC_VREF_2V = 1, /* ADC select 2V as reference voltage */
} adc_vref_t;
/**
* @brief ADC data width type definition
*/
typedef enum {
ADC_DATA_WIDTH_12B, /*!< ADC 12 bits */
ADC_DATA_WIDTH_14B_WITH_16_AVERAGE, /*!< ADC 14 bits,and the value is average of 16 converts */
ADC_DATA_WIDTH_14B_WITH_64_AVERAGE, /*!< ADC 14 bits,and the value is average of 64 converts */
ADC_DATA_WIDTH_16B_WITH_128_AVERAGE, /*!< ADC 16 bits,and the value is average of 128 converts */
ADC_DATA_WIDTH_16B_WITH_256_AVERAGE, /*!< ADC 16 bits,and the value is average of 256 converts */
} adc_data_width_t;
/**
* @brief ADC FIFO threshold type definition
*/
typedef enum {
ADC_FIFO_THRESHOLD_1BYTE, /*!< ADC FIFO threshold is 1 */
ADC_FIFO_THRESHOLD_4BYTE, /*!< ADC FIFO threshold is 4 */
ADC_FIFO_THRESHOLD_8BYTE, /*!< ADC FIFO threshold is 8 */
ADC_FIFO_THRESHOLD_16BYTE, /*!< ADC FIFO threshold is 16 */
} adc_fifo_threshold_t;
/**
* @brief ADC PGA gain type definition
*/
typedef enum {
ADC_GAIN_NONE, /*!< No PGA gain */
ADC_GAIN_1, /*!< PGA gain 1 */
ADC_GAIN_2, /*!< PGA gain 2 */
ADC_GAIN_4, /*!< PGA gain 4 */
ADC_GAIN_8, /*!< PGA gain 8 */
ADC_GAIN_16, /*!< PGA gain 16 */
ADC_GAIN_32, /*!< PGA gain 32 */
} adc_pga_gain_t;
enum adc_event_type {
ADC_EVENT_UNDERRUN,
ADC_EVENT_OVERRUN,
ADC_EVENT_FIFO,
ADC_EVENT_UNKNOWN
};
enum adc_it_type {
ADC_UNDERRUN_IT = 1 << 2,
ADC_OVERRUN_IT = 1 << 3,
ADC_FIFO_IT = 1 << 5,
};
typedef struct {
uint8_t *pos_channel;
uint8_t *neg_channel;
uint8_t num;
} adc_channel_cfg_t;
typedef struct {
int8_t posChan; /*!< Positive channel */
int8_t negChan; /*!< Negative channel */
uint16_t value; /*!< ADC value */
float volt; /*!< ADC voltage result */
} adc_channel_val_t;
typedef struct
{
uint32_t *input;
adc_channel_val_t *output;
uint32_t num;
} adc_data_parse_t;
typedef struct adc_device {
struct device parent;
adc_clk_div_t clk_div; /* CLK is not more than 2Mhz */
adc_vref_t vref; /* ADC voltage reference*/
bool continuous_conv_mode; /** conversion mode: shot conversion mode or continuous conversion mode. */
bool differential_mode; /** Channel type: single-ended or differential. */
adc_data_width_t data_width;
adc_fifo_threshold_t fifo_threshold;
adc_pga_gain_t gain;
void *rx_dma;
} adc_device_t;
#define ADC_DEV(dev) ((adc_device_t *)dev)
int adc_register(enum adc_index_type index, const char *name);
int adc_trim_tsen(uint16_t *tsen_offset);
float adc_get_tsen(uint16_t tsen_offset);
#ifdef __cplusplus
}
#endif
#endif

View File

@@ -0,0 +1,273 @@
/**
* *****************************************************************************
* @file hal_boot2_custom.h
* @version 0.1
* @date 2021-07-17
* @brief
* *****************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2020 Bouffalo Lab</center></h2>
*
* 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. Neither the name of Bouffalo Lab nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
* *****************************************************************************
*/
#ifndef __HAL_BOOT2_H__
#define __HAL_BOOT2_H__
#ifdef __cplusplus
extern "C"{
#endif
#include "hal_common.h"
#include "bl702_sflash.h"
#include "bl702_glb.h"
#define BL_TCM_BASE BL702_TCM_BASE
#define BL_SYS_CLK_PLL GLB_SYS_CLK_DLL144M
#define BL_SFLASH_CLK GLB_SFLASH_CLK_72M
#define HAL_PLL_CFG_MAGICCODE "PCFG"
#define HAL_BOOT2_PK_HASH_SIZE 256 / 8
#define HAL_BOOT2_IMG_HASH_SIZE 256 / 8
#define HAL_BOOT2_ECC_KEYXSIZE 256 / 8
#define HAL_BOOT2_ECC_KEYYSIZE 256 / 8
#define HAL_BOOT2_SIGN_MAXSIZE (2048 / 8)
#define HAL_BOOT2_DEADBEEF_VAL 0xdeadbeef
#define HAL_BOOT2_CPU0_MAGIC "BFNP"
#define HAL_BOOT2_CPU1_MAGIC "BFAP"
#define HAL_BOOT2_CP_FLAG 0x02
#define HAL_BOOT2_MP_FLAG 0x01
#define HAL_BOOT2_SP_FLAG 0x00
#define HAL_BOOT2_SUPPORT_DECOMPRESS 1 /* 1 support decompress, 0 not support */
#define HAL_BOOT2_SUPPORT_USB_IAP 0 /* 1 support decompress, 0 not support */
#define HAL_BOOT2_SUPPORT_EFLASH_LOADER_RAM 1 /* 1 support decompress, 0 not support */
#define HAL_BOOT2_SUPPORT_EFLASH_LOADER_FLASH 0 /* 1 support decompress, 0 not support */
#define HAL_BOOT2_CPU_GROUP_MAX 1
#define HAL_BOOT2_CPU_MAX 1
#define HAL_BOOT2_RAM_IMG_COUNT_MAX 0
#define HAL_BOOT2_FW_IMG_OFFSET_AFTER_HEADER 4*1024
typedef struct
{
uint8_t encrypted[HAL_BOOT2_CPU_GROUP_MAX];
uint8_t sign[HAL_BOOT2_CPU_GROUP_MAX];
uint8_t hbn_check_sign;
uint8_t rsvd[1];
uint8_t chip_id[8];
uint8_t pk_hash_cpu0[HAL_BOOT2_PK_HASH_SIZE];
uint8_t pk_hash_cpu1[HAL_BOOT2_PK_HASH_SIZE];
uint8_t uart_download_cfg;
uint8_t sf_pin_cfg;
uint8_t keep_dbg_port_closed;
uint8_t boot_pin_cfg;
} boot2_efuse_hw_config;
struct __attribute__((packed, aligned(4))) hal_flash_config
{
uint32_t magicCode; /*'FCFG'*/
SPI_Flash_Cfg_Type cfg;
uint32_t crc32;
} ;
typedef struct
{
uint8_t xtal_type;
uint8_t pll_clk;
uint8_t hclk_div;
uint8_t bclk_div;
uint8_t flash_clk_type;
uint8_t flash_clk_div;
uint8_t rsvd[2];
} hal_sys_clk_config;
typedef struct
{
uint32_t magicCode; /*'PCFG'*/
hal_sys_clk_config cfg;
uint32_t crc32;
} hal_pll_config;
struct __attribute__((packed, aligned(4))) hal_basic_cfg_t {
uint32_t sign_type : 2; /* [1: 0] for sign */
uint32_t encrypt_type : 2; /* [3: 2] for encrypt */
uint32_t key_sel : 2; /* [5: 4] key slot */
uint32_t xts_mode : 1; /* [6] for xts mode */
uint32_t aes_region_lock : 1; /* [7] rsvd */
uint32_t no_segment : 1; /* [8] no segment info */
uint32_t boot2_enable : 1; /* [9] boot2 enable */
uint32_t boot2_rollback : 1; /* [10] boot2 rollback */
uint32_t cpu_master_id : 4; /* [14: 11] master id */
uint32_t notload_in_bootrom : 1; /* [15] notload in bootrom */
uint32_t crc_ignore : 1; /* [16] ignore crc */
uint32_t hash_ignore : 1; /* [17] hash ignore */
uint32_t power_on_mm : 1; /* [18] power on mm */
uint32_t em_sel : 3; /* [21: 19] em_sel */
uint32_t cmds_en : 1; /* [22] command spliter enable */
uint32_t cmds_wrap_mode : 2; /* [24: 23] cmds wrap mode */
uint32_t cmds_wrap_len : 4; /* [28: 25] cmds wrap len */
uint32_t icache_invalid : 1; /* [29] icache invalid */
uint32_t dcache_invalid : 1; /* [30] dcache invalid */
uint32_t fpga_halt_release : 1; /* [31] FPGA halt release function */
uint32_t group_image_offset; /* flash controller offset */
uint32_t aes_region_len; /* aes region length */
uint32_t img_len_cnt; /* image length or segment count */
uint32_t hash[8]; /* hash of the image */
};
struct __attribute__((packed, aligned(4))) hal_cpu_cfg_t {
uint8_t config_enable; /* coinfig this cpu */
uint8_t halt_cpu; /* halt this cpu */
uint8_t cache_enable : 1; /* cache setting */
uint8_t cache_wa : 1; /* cache setting */
uint8_t cache_wb : 1; /* cache setting */
uint8_t cache_wt : 1; /* cache setting */
uint8_t cache_way_dis : 4; /* cache setting */
uint8_t rsvd;
uint32_t image_address_offset; /* image address on flash */
uint32_t boot_entry; /* entry point of the m0 image */
uint32_t msp_val; /* msp value */
};
struct hal_bootheader_t
{
uint32_t magicCode; /*'BFXP'*/
uint32_t rivison;
struct hal_flash_config flash_cfg;
hal_pll_config clk_cfg;
__PACKED_UNION
{
__PACKED_STRUCT
{
uint32_t sign : 2; /* [1: 0] for sign*/
uint32_t encrypt_type : 2; /* [3: 2] for encrypt */
uint32_t key_sel : 2; /* [5: 4] for key sel in boot interface*/
uint32_t rsvd6_7 : 2; /* [7: 6] for encrypt*/
uint32_t no_segment : 1; /* [8] no segment info */
uint32_t cache_enable : 1; /* [9] for cache */
uint32_t notLoadInBoot : 1; /* [10] not load this img in bootrom */
uint32_t aes_region_lock : 1; /* [11] aes region lock */
uint32_t cache_way_disable : 4; /* [15: 12] cache way disable info*/
uint32_t crcIgnore : 1; /* [16] ignore crc */
uint32_t hash_ignore : 1; /* [17] hash crc */
uint32_t halt_cpu1 : 1; /* [18] halt ap */
uint32_t rsvd19_31 : 13; /* [31:19] rsvd */
}
bval;
uint32_t wval;
}
bootCfg;
__PACKED_UNION
{
uint32_t segment_cnt;
uint32_t img_len;
}
img_segment_info;
uint32_t bootEntry; /* entry point of the image*/
__PACKED_UNION
{
uint32_t ram_addr;
uint32_t flash_offset;
}
img_start;
uint8_t hash[HAL_BOOT2_IMG_HASH_SIZE]; /*hash of the image*/
uint32_t rsv1;
uint32_t rsv2;
uint32_t crc32;
} ;
typedef struct
{
uint8_t img_valid;
uint8_t pk_src;
uint8_t rsvd[2];
struct hal_basic_cfg_t basic_cfg;
struct hal_cpu_cfg_t cpu_cfg[HAL_BOOT2_CPU_MAX];
uint8_t aes_iv[16 + 4]; //iv in boot header
uint8_t eckye_x[HAL_BOOT2_ECC_KEYXSIZE]; //ec key in boot header
uint8_t eckey_y[HAL_BOOT2_ECC_KEYYSIZE]; //ec key in boot header
uint8_t eckey_x2[HAL_BOOT2_ECC_KEYXSIZE]; //ec key in boot header
uint8_t eckey_y2[HAL_BOOT2_ECC_KEYYSIZE]; //ec key in boot header
uint8_t signature[HAL_BOOT2_SIGN_MAXSIZE]; //signature in boot header
uint8_t signature2[HAL_BOOT2_SIGN_MAXSIZE]; //signature in boot header
} boot2_image_config;
extern boot2_efuse_hw_config g_efuse_cfg;
extern uint8_t g_ps_mode;
extern uint32_t g_user_hash_ignored;
extern struct device *dev_check_hash;
uint32_t hal_boot2_custom(void);
void hal_boot2_reset_sec_eng(void);
void hal_boot2_sw_system_reset(void);
void hal_boot2_set_psmode_status(uint32_t flag);
uint32_t hal_boot2_get_psmode_status(void);
uint32_t hal_boot2_get_user_fw(void);
void hal_boot2_clr_user_fw(void);
void hal_boot2_get_efuse_cfg(boot2_efuse_hw_config *efuse_cfg);
int32_t hal_boot2_get_clk_cfg(hal_pll_config *cfg);
void hal_boot2_sboot_finish(void);
void hal_boot2_uart_gpio_init(void);
void hal_boot2_debug_uart_gpio_init(void);
#if HAL_BOOT2_SUPPORT_USB_IAP
void hal_boot2_debug_usb_port_init(void);
#endif
void hal_boot2_debug_uart_gpio_deinit(void);
int32_t hal_boot_parse_bootheader(boot2_image_config *boot_img_cfg, uint8_t *data);
void hal_boot2_clean_cache(void);
BL_Err_Type hal_boot2_set_cache(uint8_t cont_read, boot2_image_config *boot_img_cfg);
void hal_boot2_get_ram_img_cnt(char* img_name[],uint32_t *ram_img_cnt );
void hal_boot2_get_img_info(uint8_t *data, uint32_t *image_offset, uint32_t *img_len,uint8_t **hash);
void hal_boot2_release_cpu(uint32_t core, uint32_t boot_addr);
uint32_t hal_boot2_get_xip_addr(uint32_t flash_addr);
uint32_t hal_boot2_get_grp_count(void);
uint32_t hal_boot2_get_cpu_count(void);
uint32_t hal_boot2_get_feature_flag(void);
uint32_t hal_boot2_get_bootheader_offset(void);
#ifdef __cplusplus
}
#endif
#endif

View File

@@ -0,0 +1,95 @@
/**
* @file hal_clock.h
* @brief
*
* Copyright (c) 2021 Bouffalolab team
*
* Licensed to the Apache Software Foundation (ASF) under one or more
* contributor license agreements. See the NOTICE file distributed with
* this work for additional information regarding copyright ownership. The
* ASF licenses this file to you under the Apache License, Version 2.0 (the
* "License"); you may not use this file except in compliance with the
* License. You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
* License for the specific language governing permissions and limitations
* under the License.
*
*/
#ifndef __HAL_CLOCK__H__
#define __HAL_CLOCK__H__
#ifdef __cplusplus
extern "C"{
#endif
#include "hal_common.h"
#include "bl702_config.h"
/*XTAL_TYPE*/
#define XTAL_NONE 0
#define EXTERNAL_XTAL_32M 1
#define INTERNAL_RC_32M 2
/*CLOCK_32K_XTAL*/
#define EXTERNAL_XTAL_32K 0
#define INTERNAL_RC_32K 1
/*BSP_ROOT_CLOCK_SOURCE*/
#if XTAL_TYPE != EXTERNAL_XTAL_32M
#define ROOT_CLOCK_SOURCE_XCLK 0
#else
#define ROOT_CLOCK_SOURCE_XCLK 1
#endif
#define ROOT_CLOCK_SOURCE_PLL_57P6M 2
#define ROOT_CLOCK_SOURCE_PLL_96M 3
#define ROOT_CLOCK_SOURCE_PLL_144M 4
/*BSP_XXX_CLOCK_SOURCE*/
#define ROOT_CLOCK_SOURCE_32K_CLK 5
#define ROOT_CLOCK_SOURCE_FCLK 6
#define ROOT_CLOCK_SOURCE_BCLK 7
#define ROOT_CLOCK_SOURCE_1K_CLK 8
/*BSP_AUDIO_PLL_CLOCK_SOURCE*/
#define ROOT_CLOCK_SOURCE_AUPLL_12288000_HZ 9
#define ROOT_CLOCK_SOURCE_AUPLL_11289600_HZ 10
#define ROOT_CLOCK_SOURCE_AUPLL_5644800_HZ 11
#define ROOT_CLOCK_SOURCE_AUPLL_24576000_HZ 12
#define ROOT_CLOCK_SOURCE_AUPLL_24000000_HZ 13
enum system_clock_type {
SYSTEM_CLOCK_ROOT_CLOCK = 0, /* clock source before fclk_div*/
SYSTEM_CLOCK_FCLK, /* clock source after fclk_div*/
SYSTEM_CLOCK_BCLK, /* clock source after bclk_div*/
SYSTEM_CLOCK_XCLK, /* xtal clock*/
SYSTEM_CLOCK_32K_CLK,
SYSTEM_CLOCK_AUPLL,
};
enum peripheral_clock_type {
PERIPHERAL_CLOCK_UART = 0,
PERIPHERAL_CLOCK_SPI,
PERIPHERAL_CLOCK_I2C,
PERIPHERAL_CLOCK_ADC,
PERIPHERAL_CLOCK_DAC,
PERIPHERAL_CLOCK_I2S,
PERIPHERAL_CLOCK_PWM,
PERIPHERAL_CLOCK_CAM,
PERIPHERAL_CLOCK_TIMER0,
PERIPHERAL_CLOCK_TIMER1,
PERIPHERAL_CLOCK_WDT,
};
void system_clock_init(void);
void peripheral_clock_init(void);
uint32_t system_clock_get(enum system_clock_type type);
uint32_t peripheral_clock_get(enum peripheral_clock_type type);
void system_mtimer_clock_init(void);
void system_mtimer_clock_reinit(void);
#ifdef __cplusplus
}
#endif
#endif

View File

@@ -0,0 +1,46 @@
/**
* @file hal_common.h
* @brief
*
* Copyright (c) 2021 Bouffalolab team
*
* Licensed to the Apache Software Foundation (ASF) under one or more
* contributor license agreements. See the NOTICE file distributed with
* this work for additional information regarding copyright ownership. The
* ASF licenses this file to you under the Apache License, Version 2.0 (the
* "License"); you may not use this file except in compliance with the
* License. You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
* License for the specific language governing permissions and limitations
* under the License.
*
*/
#ifndef __HAL_COMMON__H__
#define __HAL_COMMON__H__
#ifdef __cplusplus
extern "C" {
#endif
#include "bl702_common.h"
void cpu_global_irq_enable(void);
void cpu_global_irq_disable(void);
void hal_por_reset(void);
void hal_system_reset(void);
void hal_cpu_reset(void);
void hal_get_chip_id(uint8_t chip_id[8]);
void hal_enter_usb_iap(void);
void hal_jump2app(uint32_t flash_offset);
int hal_get_trng_seed(void);
#ifdef __cplusplus
}
#endif
#endif

View File

@@ -0,0 +1,190 @@
/**
* @file hal_dma.h
* @brief
*
* Copyright (c) 2021 Bouffalolab team
*
* Licensed to the Apache Software Foundation (ASF) under one or more
* contributor license agreements. See the NOTICE file distributed with
* this work for additional information regarding copyright ownership. The
* ASF licenses this file to you under the Apache License, Version 2.0 (the
* "License"); you may not use this file except in compliance with the
* License. You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
* License for the specific language governing permissions and limitations
* under the License.
*
*/
#ifndef __HAL_DMA__H__
#define __HAL_DMA__H__
#ifdef __cplusplus
extern "C" {
#endif
#include "hal_common.h"
#include "drv_device.h"
#include "bl702_config.h"
#define DEVICE_CTRL_DMA_CHANNEL_GET_STATUS 0x10
#define DEVICE_CTRL_DMA_CHANNEL_START 0x11
#define DEVICE_CTRL_DMA_CHANNEL_STOP 0x12
#define DEVICE_CTRL_DMA_CHANNEL_UPDATE 0x13
#define DEVICE_CTRL_DMA_CONFIG_SI 0x14
#define DEVICE_CTRL_DMA_CONFIG_DI 0x15
enum dma_index_type {
#ifdef BSP_USING_DMA0_CH0
DMA0_CH0_INDEX,
#endif
#ifdef BSP_USING_DMA0_CH1
DMA0_CH1_INDEX,
#endif
#ifdef BSP_USING_DMA0_CH2
DMA0_CH2_INDEX,
#endif
#ifdef BSP_USING_DMA0_CH3
DMA0_CH3_INDEX,
#endif
#ifdef BSP_USING_DMA0_CH4
DMA0_CH4_INDEX,
#endif
#ifdef BSP_USING_DMA0_CH5
DMA0_CH5_INDEX,
#endif
#ifdef BSP_USING_DMA0_CH6
DMA0_CH6_INDEX,
#endif
#ifdef BSP_USING_DMA0_CH7
DMA0_CH7_INDEX,
#endif
DMA_MAX_INDEX
};
#define dma_channel_start(dev) device_control(dev, DEVICE_CTRL_DMA_CHANNEL_START, NULL)
#define dma_channel_stop(dev) device_control(dev, DEVICE_CTRL_DMA_CHANNEL_STOP, NULL)
#define dma_channel_update(dev, list) device_control(dev, DEVICE_CTRL_DMA_CHANNEL_UPDATE, list)
#define dma_channel_check_busy(dev) device_control(dev, DEVICE_CTRL_DMA_CHANNEL_GET_STATUS, NULL)
#define DMA_LLI_ONCE_MODE 0
#define DMA_LLI_CYCLE_MODE 1
#define DMA_ADDR_INCREMENT_DISABLE 0 /*!< Addr increment mode disable */
#define DMA_ADDR_INCREMENT_ENABLE 1 /*!< Addr increment mode enable */
#define DMA_TRANSFER_WIDTH_8BIT 0
#define DMA_TRANSFER_WIDTH_16BIT 1
#define DMA_TRANSFER_WIDTH_32BIT 2
#define DMA_BURST_1BYTE 0
#define DMA_BURST_4BYTE 1
#define DMA_BURST_8BYTE 2
#define DMA_BURST_16BYTE 3
#define DMA_ADDR_UART0_TDR (0x4000A000 + 0x88)
#define DMA_ADDR_UART0_RDR (0x4000A000 + 0x8C)
#define DMA_ADDR_UART1_TDR (0x4000A100 + 0x88)
#define DMA_ADDR_UART1_RDR (0x4000A100 + 0x8C)
#define DMA_ADDR_I2C_TDR (0x4000A300 + 0x88)
#define DMA_ADDR_I2C_RDR (0x4000A300 + 0x8C)
#define DMA_ADDR_SPI_TDR (0x4000A200 + 0x88)
#define DMA_ADDR_SPI_RDR (0x4000A200 + 0x8C)
#define DMA_ADDR_I2S_TDR (0x4000AA00 + 0x88)
#define DMA_ADDR_I2S_RDR (0x4000AA00 + 0x8C)
#define DMA_ADDR_ADC_RDR (0x40002000 + 0x04)
#define DMA_ADDR_DAC_TDR (0x40002000 + 0X48)
#define DMA_REQUEST_NONE 0x00000000 /*!< DMA request peripheral:None */
#define DMA_REQUEST_UART0_RX 0x00000000 /*!< DMA request peripheral:UART0 RX */
#define DMA_REQUEST_UART0_TX 0x00000001 /*!< DMA request peripheral:UART0 TX */
#define DMA_REQUEST_UART1_RX 0x00000002 /*!< DMA request peripheral:UART1 RX */
#define DMA_REQUEST_UART1_TX 0x00000003 /*!< DMA request peripheral:UART1 TX */
#define DMA_REQUEST_I2C0_RX 0x00000006 /*!< DMA request peripheral:I2C RX */
#define DMA_REQUEST_I2C0_TX 0x00000007 /*!< DMA request peripheral:I2C TX */
#define DMA_REQUEST_SPI0_RX 0x0000000A /*!< DMA request peripheral:SPI RX */
#define DMA_REQUEST_SPI0_TX 0x0000000B /*!< DMA request peripheral:SPI TX */
#define DMA_REQUEST_I2S_RX 0x00000014 /*!< DMA request peripheral:I2S RX */
#define DMA_REQUEST_I2S_TX 0x00000015 /*!< DMA request peripheral:I2S TX */
#define DMA_REQUEST_ADC0 0x00000016 /*!< DMA request peripheral:ADC0 */
#define DMA_REQUEST_DAC0 0x00000017 /*!< DMA request peripheral:DAC0 */
#define DMA_REQUEST_USB_EP0 0x00000018 /*!< DMA request peripheral:USB EP0*/
#define DMA_REQUEST_USB_EP1 0x00000019 /*!< DMA request peripheral:USB EP1*/
#define DMA_REQUEST_USB_EP2 0x0000001A /*!< DMA request peripheral:USB EP2*/
#define DMA_REQUEST_USB_EP3 0x0000001B /*!< DMA request peripheral:USB EP3*/
#define DMA_REQUEST_USB_EP4 0x0000001C /*!< DMA request peripheral:USB EP4*/
#define DMA_REQUEST_USB_EP5 0x0000001D /*!< DMA request peripheral:USB EP5*/
#define DMA_REQUEST_USB_EP6 0x0000001E /*!< DMA request peripheral:USB EP6*/
#define DMA_REQUEST_USB_EP7 0x0000001F /*!< DMA request peripheral:USB EP7 */
/**
* @brief DMA transfer direction type definition
*/
typedef enum {
DMA_MEMORY_TO_MEMORY = 0, /*!< DMA transfer type:memory to memory */
DMA_MEMORY_TO_PERIPH, /*!< DMA transfer type:memory to peripheral */
DMA_PERIPH_TO_MEMORY, /*!< DMA transfer type:peripheral to memory */
DMA_PERIPH_TO_PERIPH, /*!< DMA transfer type:peripheral to peripheral */
} dma_transfer_dir_type;
typedef union {
struct
{
uint32_t TransferSize : 12; /* [11: 0], r/w, 0x0 */
uint32_t SBSize : 2; /* [13:12], r/w, 0x1 */
uint32_t dst_min_mode : 1; /* [ 14], r/w, 0x0 */
uint32_t DBSize : 2; /* [16:15], r/w, 0x1 */
uint32_t dst_add_mode : 1; /* [ 17], r/w, 0x0 */
uint32_t SWidth : 2; /* [19:18], r/w, 0x2 */
uint32_t reserved_20 : 1; /* [ 20], rsvd, 0x0 */
uint32_t DWidth : 2; /* [22:21], r/w, 0x2 */
uint32_t fix_cnt : 2; /* [24:23], r/w, 0x0 */
uint32_t SLargerD : 1; /* [ 25], r/w, 0x0 */
uint32_t SI : 1; /* [ 26], r/w, 0x1 */
uint32_t DI : 1; /* [ 27], r/w, 0x1 */
uint32_t Prot : 3; /* [30:28], r/w, 0x0 */
uint32_t I : 1; /* [ 31], r/w, 0x0 */
} bits;
uint32_t WORD;
} dma_control_data_t;
typedef struct
{
uint32_t src_addr;
uint32_t dst_addr;
uint32_t nextlli;
dma_control_data_t cfg;
} dma_lli_ctrl_t;
typedef struct dma_device {
struct device parent;
uint8_t id;
uint8_t ch;
uint8_t transfer_mode;
uint8_t direction;
uint32_t src_req;
uint32_t dst_req;
uint8_t src_addr_inc;
uint8_t dst_addr_inc;
uint8_t src_burst_size;
uint8_t dst_burst_size;
uint8_t src_width;
uint8_t dst_width;
dma_lli_ctrl_t *lli_cfg;
} dma_device_t;
#define DMA_DEV(dev) ((dma_device_t *)dev)
int dma_register(enum dma_index_type index, const char *name);
int dma_allocate_register(const char *name);
int dma_reload(struct device *dev, uint32_t src_addr, uint32_t dst_addr, uint32_t transfer_size);
#ifdef __cplusplus
}
#endif
#endif

View File

@@ -0,0 +1,50 @@
/**
* @file hal_flash.h
* @brief
*
* Copyright 2019-2030 Bouffalolab team
*
* Licensed to the Apache Software Foundation (ASF) under one or more
* contributor license agreements. See the NOTICE file distributed with
* this work for additional information regarding copyright ownership. The
* ASF licenses this file to you under the Apache License, Version 2.0 (the
* "License"); you may not use this file except in compliance with the
* License. You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
* License for the specific language governing permissions and limitations
* under the License.
*
*/
#ifndef __HAL_FLASH__H__
#define __HAL_FLASH__H__
#ifdef __cplusplus
extern "C"{
#endif
#include "hal_common.h"
#include "bl702_sflash.h"
#include "bl702_sflash_ext.h"
#define FLASH_NOT_DETECT 0x10
#define BL_FLASH_XIP_BASE BL702_FLASH_XIP_BASE
uint32_t flash_get_jedecid(void);
BL_Err_Type flash_init(void);
BL_Err_Type flash_read_jedec_id(uint8_t *data);
BL_Err_Type flash_read_via_xip(uint32_t addr, uint8_t *data, uint32_t len);
BL_Err_Type flash_read(uint32_t addr, uint8_t *data, uint32_t len);
BL_Err_Type flash_write(uint32_t addr, uint8_t *data, uint32_t len);
BL_Err_Type flash_erase(uint32_t startaddr, uint32_t len);
BL_Err_Type flash_set_cache(uint8_t cont_read, uint8_t cache_enable, uint8_t cache_way_disable, uint32_t flash_offset);
BL_Err_Type flash_get_cfg(uint8_t **cfg_addr, uint32_t *len);
BL_Err_Type flash_write_protect_set(SFlash_Protect_Kh25v40_Type protect);
#ifdef __cplusplus
}
#endif
#endif

View File

@@ -0,0 +1,96 @@
/**
* @file hal_gpio.h
* @brief
*
* Copyright (c) 2021 Bouffalolab team
*
* Licensed to the Apache Software Foundation (ASF) under one or more
* contributor license agreements. See the NOTICE file distributed with
* this work for additional information regarding copyright ownership. The
* ASF licenses this file to you under the Apache License, Version 2.0 (the
* "License"); you may not use this file except in compliance with the
* License. You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
* License for the specific language governing permissions and limitations
* under the License.
*
*/
#ifndef __HAL_GPIO__H__
#define __HAL_GPIO__H__
#ifdef __cplusplus
extern "C" {
#endif
#include "bl702_config.h"
#include "drv_device.h"
#include "hal_common.h"
enum gpio_pin_type {
GPIO_PIN_0 = 0,
GPIO_PIN_1,
GPIO_PIN_2,
GPIO_PIN_3,
GPIO_PIN_4,
GPIO_PIN_5,
GPIO_PIN_6,
GPIO_PIN_7,
GPIO_PIN_8,
GPIO_PIN_9,
GPIO_PIN_10,
GPIO_PIN_11,
GPIO_PIN_12,
GPIO_PIN_13,
GPIO_PIN_14,
GPIO_PIN_15,
GPIO_PIN_16,
GPIO_PIN_17,
GPIO_PIN_18,
GPIO_PIN_19,
GPIO_PIN_20,
GPIO_PIN_21,
GPIO_PIN_22,
GPIO_PIN_23,
GPIO_PIN_24,
GPIO_PIN_25,
GPIO_PIN_26,
GPIO_PIN_27,
GPIO_PIN_28,
GPIO_PIN_29,
GPIO_PIN_30,
GPIO_PIN_31,
GPIO_PIN_MAX,
};
#define GPIO_OUTPUT_MODE 0
#define GPIO_OUTPUT_PP_MODE 1
#define GPIO_OUTPUT_PD_MODE 2
#define GPIO_INPUT_MODE 3
#define GPIO_INPUT_PU_MODE 4
#define GPIO_INPUT_PD_MODE 5
#define GPIO_ASYNC_RISING_TRIGER_INT_MODE 6
#define GPIO_ASYNC_FALLING_TRIGER_INT_MODE 7
#define GPIO_ASYNC_HIGH_LEVEL_INT_MODE 8
#define GPIO_ASYNC_LOW_LEVEL_INT_MODE 9
#define GPIO_SYNC_RISING_TRIGER_INT_MODE 10
#define GPIO_SYNC_FALLING_TRIGER_INT_MODE 11
#define GPIO_SYNC_HIGH_LEVEL_INT_MODE 12
#define GPIO_SYNC_LOW_LEVEL_INT_MODE 13
#define GPIO_HZ_MODE 14
void gpio_set_mode(uint32_t pin, uint32_t mode);
void gpio_write(uint32_t pin, uint32_t value);
void gpio_toggle(uint32_t pin);
int gpio_read(uint32_t pin);
void gpio_attach_irq(uint32_t pin, void (*cbfun)(uint32_t pin));
void gpio_irq_enable(uint32_t pin, uint8_t enabled);
#ifdef __cplusplus
}
#endif
#endif

Some files were not shown because too many files have changed in this diff Show More